From e8368b5b09a91711a0c59f560098f29182766bfb Mon Sep 17 00:00:00 2001 From: malte Date: Wed, 15 May 2024 15:19:27 +0200 Subject: [PATCH 01/43] add test for simple pouring and velocity limits --- test/test_integration_hsr.py | 32 +++++++++++++++++-- test/test_integration_pr2.py | 61 ++++++++++++++++++++++++++++++++++-- 2 files changed, 89 insertions(+), 4 deletions(-) diff --git a/test/test_integration_hsr.py b/test/test_integration_hsr.py index 0ff50221bf..f1f4ce1ae8 100644 --- a/test/test_integration_hsr.py +++ b/test/test_integration_hsr.py @@ -3,7 +3,7 @@ import numpy as np import pytest -from geometry_msgs.msg import PoseStamped, Point, Quaternion, PointStamped, Vector3Stamped +from geometry_msgs.msg import PoseStamped, Point, Quaternion, PointStamped, Vector3Stamped, Vector3 from numpy import pi from tf.transformations import quaternion_from_matrix, quaternion_about_axis @@ -36,7 +36,7 @@ def __init__(self, giskard=None): giskard = Giskard(world_config=WorldWithHSRConfig(), collision_avoidance_config=HSRCollisionAvoidanceConfig(), robot_interface_config=HSRStandaloneInterface(), - behavior_tree_config=StandAloneBTConfig(debug_mode=True, publish_js=True), + behavior_tree_config=StandAloneBTConfig(debug_mode=True, publish_js=True, simulation_max_hz=20), qp_controller_config=QPControllerConfig()) super().__init__(giskard) self.gripper_group = 'gripper' @@ -450,3 +450,31 @@ def test_add(self, zero_pose): zero_pose.set_joint_goal({'arm_flex_joint': -0.7}) zero_pose.plan_and_execute() + + +class TestVelocityLimit: + # test to see in rviz whether the rotation with limited velocity is oscilaating as it is doing it in mujoco closed loop + def test_vel(self, zero_pose): + goal_pose = PoseStamped() + goal_pose.header.frame_id = 'map' + goal_pose.pose.position = Point(1, 0, 0.5) + goal_pose.pose.orientation = Quaternion(*quaternion_from_matrix([[0, 0, 1, 0], + [0, -1, 0, 0], + [1, 0, 0, 0], + [0, 0, 0, 1]])) + zero_pose.motion_goals.add_cartesian_pose(goal_pose=goal_pose, tip_link='hand_palm_link', root_link='map') + zero_pose.execute() + + goal_pose = PoseStamped() + goal_pose.header.frame_id = 'hand_palm_link' + rotation_axis = Vector3Stamped() + rotation_axis.header.frame_id = 'hand_palm_link' + rotation_axis.vector = Vector3(*[0, 0, 1]) + + goal_pose.pose.orientation = Quaternion( + *quaternion_about_axis(1.7, [rotation_axis.vector.x, rotation_axis.vector.y, rotation_axis.vector.z])) + zero_pose.motion_goals.add_cartesian_pose(goal_pose, 'hand_palm_link', 'map') + zero_pose.motion_goals.add_limit_cartesian_velocity(tip_link='hand_palm_link', root_link='map', + max_angular_velocity=0.1) + zero_pose.add_default_end_motion_conditions() + zero_pose.execute() diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 337ee5cf73..c2cf9d3034 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -9,7 +9,8 @@ import numpy as np import pytest import rospy -from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, QuaternionStamped, Pose +from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, QuaternionStamped, Pose, \ + Vector3 from numpy import pi from shape_msgs.msg import SolidPrimitive from tf.transformations import quaternion_from_matrix, quaternion_about_axis @@ -162,7 +163,7 @@ def __init__(self, giskard: Optional[Giskard] = None): robot_interface_config=PR2StandaloneInterface(drive_joint_name=drive_joint_name), collision_avoidance_config=PR2CollisionAvoidance(drive_joint_name=drive_joint_name), behavior_tree_config=StandAloneBTConfig(debug_mode=True, - simulation_max_hz=None), + simulation_max_hz=30, publish_tf=True), qp_controller_config=QPControllerConfig()) super().__init__(giskard) self.robot = god_map.world.groups[self.robot_name] @@ -4307,6 +4308,62 @@ def test_manip2(self, zero_pose: PR2TestWrapper): tip_link='l_gripper_tool_frame') zero_pose.execute(add_local_minimum_reached=True) + +class TestTCMPs: + def test_tcmp_pouring(self, zero_pose: PR2TestWrapper): + #TODO: Parameters + angle = 1.7 + velocity = 0.2 + + goal_pose = PoseStamped() + goal_pose.header.frame_id = 'map' + goal_pose.pose.orientation = Quaternion(*quaternion_from_matrix(np.array([[1, 0, 0, 0], + [0, 1, 0, 0], + [0, 0, 1, 0], + [0, 0, 0, 1]]))) + goal_pose.pose.position = Point(2, 0, 0.8) + + goal_rot = PoseStamped() + goal_rot.header.frame_id = zero_pose.r_tip + + rotation_axis = Vector3Stamped() + rotation_axis.header.frame_id = zero_pose.r_tip + rotation_axis.vector = Vector3(1, 0, 0) + + goal_quat = QuaternionStamped() + goal_quat.header.frame_id = zero_pose.r_tip + goal_quat.quaternion = Quaternion( + *quaternion_about_axis(angle, [rotation_axis.vector.x, rotation_axis.vector.y, rotation_axis.vector.z])) + goal_rot.pose.orientation = goal_quat.quaternion + + goal_quat2 = QuaternionStamped() + goal_quat2.header.frame_id = zero_pose.r_tip + goal_quat2.quaternion = Quaternion( + *quaternion_about_axis(-angle, [rotation_axis.vector.x, rotation_axis.vector.y, rotation_axis.vector.z])) + + pose_monitor = zero_pose.monitors.add_cartesian_pose(root_link='map', tip_link=zero_pose.r_tip, + goal_pose=goal_pose) + rot_monitor = zero_pose.monitors.add_cartesian_orientation(root_link='map', tip_link=zero_pose.r_tip, + goal_orientation=goal_quat, + start_condition=pose_monitor) + rot_monitor2 = zero_pose.monitors.add_cartesian_orientation(root_link='map', tip_link=zero_pose.r_tip, + goal_orientation=goal_quat2, + start_condition=rot_monitor) + + zero_pose.motion_goals.add_cartesian_pose(goal_pose=goal_pose, tip_link=zero_pose.r_tip, root_link='map', + end_condition=pose_monitor) + + zero_pose.motion_goals.add_cartesian_pose(goal_rot, zero_pose.r_tip, 'map', + reference_angular_velocity=velocity, + start_condition=pose_monitor, end_condition=rot_monitor) + goal_rot.pose.orientation = goal_quat2.quaternion + zero_pose.motion_goals.add_cartesian_pose(goal_rot, zero_pose.r_tip, 'map', + reference_angular_velocity=velocity*2, + start_condition=rot_monitor, end_condition=rot_monitor2) + zero_pose.monitors.add_end_motion(rot_monitor2) + zero_pose.allow_all_collisions() + zero_pose.execute(add_local_minimum_reached=False) + # kernprof -lv py.test -s test/test_integration_pr2.py # time: [1-9][1-9]*.[1-9]* s # import pytest From a45cf7f3fc1b56dcfb73631a287ca4465c0deebc Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 27 May 2024 15:42:03 +0200 Subject: [PATCH 02/43] added some feature functions and a tcmp blueprint --- src/giskardpy/goals/feature_functions.py | 169 ++++++++++++++++ .../task_critical_motion_pattern_goal.py | 62 ++++++ test/test_integration_pr2.py | 186 +++++++++++++++++- 3 files changed, 415 insertions(+), 2 deletions(-) create mode 100644 src/giskardpy/goals/feature_functions.py create mode 100644 src/giskardpy/goals/task_critical_motion_pattern_goal.py diff --git a/src/giskardpy/goals/feature_functions.py b/src/giskardpy/goals/feature_functions.py new file mode 100644 index 0000000000..3fa8ba7603 --- /dev/null +++ b/src/giskardpy/goals/feature_functions.py @@ -0,0 +1,169 @@ +from __future__ import division + +from geometry_msgs.msg import PointStamped, PoseStamped, QuaternionStamped +from geometry_msgs.msg import Vector3Stamped +from giskardpy import casadi_wrapper as cas +from giskardpy.goals.goal import Goal +from giskardpy.god_map import god_map +from giskardpy.symbol_manager import symbol_manager +from giskardpy.tasks.task import Task, WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE +from giskardpy.goals.pointing import Pointing + +from typing import Optional, List, Dict + + +class PerpendicularFeatureFunction(Goal): + def __init__(self, tip_link: str, root_link: str, + world_feature: Vector3Stamped, + robot_feature: Vector3Stamped, + name: str = None, + weight: int = WEIGHT_BELOW_CA, + max_vel: float = 0.2, + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.TrueSymbol + ): + self.root_link = god_map.world.search_for_link_name(root_link, None) + self.tip_link = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' + super().__init__(name) + world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) + root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) + robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) + tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) + + root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) + root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) + root_V_world_feature = cas.Vector3(root_world_feature) + + expr = cas.dot(root_V_world_feature[:3], root_V_robot_feature[:3]) + + task = self.create_and_add_task() + task.add_equality_constraint(reference_velocity=max_vel, + equality_bound=0 - expr, + weight=weight, + task_expression=expr, + name=f'{name}_constraint') + self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) + + +class HeightFeatureFunction(Goal): + def __init__(self, tip_link: str, root_link: str, + world_feature: PointStamped, + robot_feature: PointStamped, + lower_limit: float, + upper_limit: float, + name: str = None, + weight: int = WEIGHT_BELOW_CA, + max_vel: float = 0.2, + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.TrueSymbol + ): + self.root_link = god_map.world.search_for_link_name(root_link, None) + self.tip_link = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' + super().__init__(name) + world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) + root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) + robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) + tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) + + root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) + root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) + root_P_world_feature = cas.Point3(root_world_feature) + + distance = root_P_robot_feature - root_P_world_feature + + height_vector = cas.Vector3([0, 0, 1]) + + projection = cas.dot(distance, height_vector) + expr = projection + + task = self.create_and_add_task() + task.add_inequality_constraint(reference_velocity=max_vel, + upper_error=upper_limit - expr, + lower_error=lower_limit - expr, + weight=weight, + task_expression=expr, + name=f'{name}_constraint') + self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) + + +class DistanceFeatureFunction(Goal): + def __init__(self, tip_link: str, root_link: str, + world_feature: PointStamped, + robot_feature: PointStamped, + lower_limit: float, + upper_limit: float, + name: str = None, + weight: int = WEIGHT_BELOW_CA, + max_vel: float = 0.2, + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.TrueSymbol + ): + self.root_link = god_map.world.search_for_link_name(root_link, None) + self.tip_link = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' + super().__init__(name) + world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) + root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) + robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) + tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) + + root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) + root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) + root_P_world_feature = cas.Point3(root_world_feature) + + # distance between the two feature points + distance = root_P_robot_feature - root_P_world_feature + + # normal vector defining the x-y plane + height_vector = cas.Vector3([0, 0, 1]) + + # project the distance vector onto the x-y plane and calculate its length + projection = cas.norm(distance - cas.dot(distance, height_vector) * height_vector) + expr = projection + + task = self.create_and_add_task() + task.add_inequality_constraint(reference_velocity=max_vel, + upper_error=upper_limit - expr, + lower_error=lower_limit - expr, + weight=weight, + task_expression=expr, + name=f'{name}_constraint') + # god_map.debug_expression_manager.add_debug_expression('distance-expr', expr) + self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) + + +class PointingFeatureFunction(Goal): + def __init__(self, tip_link: str, root_link: str, + world_feature: PointStamped, + robot_feature: Vector3Stamped, + name: str = None, + weight: int = WEIGHT_BELOW_CA, + max_vel: float = 0.2, + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.TrueSymbol + ): + self.root_link = god_map.world.search_for_link_name(root_link, None) + self.tip_link = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' + super().__init__(name) + + self.add_constraints_of_goal(Pointing(tip_link=tip_link, + goal_point=world_feature, + root_link=root_link, + pointing_axis=robot_feature, + max_velocity=max_vel, + weight=weight, + name=name, + start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition)) diff --git a/src/giskardpy/goals/task_critical_motion_pattern_goal.py b/src/giskardpy/goals/task_critical_motion_pattern_goal.py new file mode 100644 index 0000000000..12d65c5879 --- /dev/null +++ b/src/giskardpy/goals/task_critical_motion_pattern_goal.py @@ -0,0 +1,62 @@ +from __future__ import division + +from geometry_msgs.msg import PointStamped, PoseStamped, QuaternionStamped +from geometry_msgs.msg import Vector3Stamped +from giskardpy import casadi_wrapper as cas +from giskardpy.goals.goal import Goal +from giskardpy.god_map import god_map +from giskardpy.symbol_manager import symbol_manager +from giskardpy.tasks.task import Task, WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE +from giskardpy.goals.feature_functions import DistanceFeatureFunction, PointingFeatureFunction, \ + PerpendicularFeatureFunction, HeightFeatureFunction + +from typing import Optional, List, Dict + + +class TCMPGoal(Goal): + """ + A Task Critical Motion Pattern models the motions that are essential to successfully execute a task. + For everyday activities of household robots it is assumed that they are always composed of an approach movement + followed by a general movement function and a release movement. + This is more or less in line with the Flanagan model and the movement function could also be further divided + following the Flanagan model. + """ + + def __init__(self, tip_link: str, root_link: str, name: str = None, + movement_function: str = None, + reference_frame: str = None, + monitoring_list: List[str] = None, + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.TrueSymbol + ): + self.root_link = god_map.world.search_for_link_name(root_link, None) + self.tip_link = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' + super().__init__(name) + + # collect approach constraints and monitor their success + # approach_task = self.create_and_add_task(task_name='approach task') + + # define the task critical movement using the movement function or constraints and monitor their success + critical_task = self.create_and_add_task(task_name='critial task') + + def select_movement_function(function_description: str, params: Dict[str, float] = None): + return cas.sin(symbol_manager.get_symbol(f'god_map.time')) + + function = select_movement_function(function_description=movement_function) + root_P_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link).to_position() + critical_task.add_equality_constraint_vector(reference_velocities=[0.3] * 3, + equality_bounds=(cas.Vector3([2, function, 0.8]) - root_P_tip)[:3], + weights=[WEIGHT_BELOW_CA] * 3, + task_expression=root_P_tip[:3], + names=['sdf', 'gdf', 'hgj']) + + # collect release constraints and monitor their success + # release_task = self.create_and_add_task(task_name="release task") + + # monitor additional values throughout the motion execution + # for monitoring_request in monitoring_list: + # pass + self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index c2cf9d3034..89783a256a 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -41,6 +41,8 @@ from utils_for_tests import compare_poses, publish_marker_vector, \ GiskardTestWrapper, pr2_urdf from giskardpy.goals.manipulability_goals import MaxManipulability +from giskardpy.goals.feature_functions import DistanceFeatureFunction, PointingFeatureFunction, \ + PerpendicularFeatureFunction, HeightFeatureFunction # scopes = ['module', 'class', 'function'] pocky_pose = {'r_elbow_flex_joint': -1.29610152504, @@ -4311,7 +4313,7 @@ def test_manip2(self, zero_pose: PR2TestWrapper): class TestTCMPs: def test_tcmp_pouring(self, zero_pose: PR2TestWrapper): - #TODO: Parameters + # TODO: Parameters angle = 1.7 velocity = 0.2 @@ -4358,12 +4360,192 @@ def test_tcmp_pouring(self, zero_pose: PR2TestWrapper): start_condition=pose_monitor, end_condition=rot_monitor) goal_rot.pose.orientation = goal_quat2.quaternion zero_pose.motion_goals.add_cartesian_pose(goal_rot, zero_pose.r_tip, 'map', - reference_angular_velocity=velocity*2, + reference_angular_velocity=velocity * 2, start_condition=rot_monitor, end_condition=rot_monitor2) zero_pose.monitors.add_end_motion(rot_monitor2) zero_pose.allow_all_collisions() zero_pose.execute(add_local_minimum_reached=False) + def test_tcmp_goal(self, zero_pose: PR2TestWrapper): + zero_pose.motion_goals.add_motion_goal(motion_goal_class='TCMPGoal', + name='tcmpTest', + root_link='map', + tip_link=zero_pose.r_tip) + zero_pose.execute() + + def test_feature_perpendicular(self, zero_pose: PR2TestWrapper): + world_feature = Vector3Stamped() + world_feature.header.frame_id = 'map' + world_feature.vector.x = 1 + + robot_feature = Vector3Stamped() + robot_feature.header.frame_id = zero_pose.r_tip + robot_feature.vector.x = 1 + + zero_pose.motion_goals.add_motion_goal(motion_goal_class='PerpendicularFeatureFunction', + root_link='map', + tip_link=zero_pose.r_tip, + world_feature=world_feature, + robot_feature=robot_feature) + + zero_pose.add_default_end_motion_conditions() + zero_pose.execute() + + def test_feature_height(self, zero_pose: PR2TestWrapper): + world_feature = PointStamped() + world_feature.header.frame_id = 'map' + + robot_feature = PointStamped() + robot_feature.header.frame_id = zero_pose.r_tip + + zero_pose.motion_goals.add_motion_goal(motion_goal_class='HeightFeatureFunction', + root_link='map', + tip_link=zero_pose.r_tip, + world_feature=world_feature, + robot_feature=robot_feature, + lower_limit=1, + upper_limit=2) + + zero_pose.add_default_end_motion_conditions() + zero_pose.execute() + + def test_feature_distance(self, zero_pose: PR2TestWrapper): + world_feature = PointStamped() + world_feature.header.frame_id = 'map' + + robot_feature = PointStamped() + robot_feature.header.frame_id = zero_pose.r_tip + + zero_pose.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction', + root_link='map', + tip_link=zero_pose.r_tip, + world_feature=world_feature, + robot_feature=robot_feature, + lower_limit=2, + upper_limit=2, + max_vel=0.3 + ) + + zero_pose.add_default_end_motion_conditions() + zero_pose.execute() + + def test_feature_pointing(self, zero_pose: PR2TestWrapper): + world_feature = PointStamped() + world_feature.header.frame_id = 'map' + + robot_feature = Vector3Stamped() + robot_feature.header.frame_id = zero_pose.r_tip + robot_feature.vector.x = 1 + + zero_pose.motion_goals.add_motion_goal(motion_goal_class='PointingFeatureFunction', + root_link='map', + tip_link=zero_pose.r_tip, + world_feature=world_feature, + robot_feature=robot_feature, + ) + + zero_pose.add_default_end_motion_conditions() + zero_pose.execute() + + def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): + # -------------- world definition --------------- + spoon_pose = PoseStamped() + spoon_pose.header.frame_id = zero_pose.r_tip + spoon_pose.pose.orientation.w = 1 + spoon_pose.pose.position.z = -0.1 + zero_pose.add_box(name='spoon', size=(0.03, 0.03, 0.20), pose=spoon_pose, parent_link=zero_pose.r_tip) + pot_pose = PoseStamped() + pot_pose.header.frame_id = 'map' + pot_pose.pose.orientation.w = 1 + pot_pose.pose.position.x = 2 + pot_pose.pose.position.y = 0 + pot_pose.pose.position.z = 0.8 + zero_pose.add_box(name='pot', size=(0.2, 0.2, 0.1), pose=pot_pose, parent_link='map') + + # --------------------------------- object feature definition ------------------------------------------- + spoon_tip_point = PointStamped() + spoon_tip_point.header.frame_id = 'spoon' + spoon_tip_point.point.z = -0.1 + spoon_tool_vector = Vector3Stamped() + spoon_tool_vector.header.frame_id = 'spoon' + spoon_tool_vector.vector.z = -1 + + pot_center_point = PointStamped() + pot_center_point.header.frame_id = 'pot' + pot_vector_x = Vector3Stamped() + pot_vector_x.header.frame_id = 'pot' + pot_vector_x.vector.x = 1 + pot_vector_y = Vector3Stamped() + pot_vector_y.header.frame_id = 'pot' + pot_vector_y.vector.y = 1 + + # ------------------------------- motion code ------------------------------------------------------------- + monitor = zero_pose.monitors.add_pointing_at(goal_point=pot_center_point, tip_link='spoon', + pointing_axis=spoon_tool_vector, root_link='map') + time_monitor = zero_pose.monitors.add_time_above(20) + + zero_pose.motion_goals.add_motion_goal(motion_goal_class=HeightFeatureFunction.__name__, + robot_feature=spoon_tip_point, + world_feature=pot_center_point, + lower_limit=0.1, + upper_limit=0.1, + tip_link='spoon', + root_link='map', + end_condition=monitor) + zero_pose.motion_goals.add_motion_goal(motion_goal_class=DistanceFeatureFunction.__name__, + robot_feature=spoon_tip_point, + world_feature=pot_center_point, + lower_limit=0.0, + upper_limit=0.0, + tip_link='spoon', + root_link='map', + max_vel=0.1, + end_condition=monitor) + # zero_pose.motion_goals.add_motion_goal(motion_goal_class=PointingFeatureFunction.__name__, + # robot_feature=spoon_tool_vector, + # world_feature=pot_center_point, + # tip_link='spoon', + # root_link='map') + zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, + robot_feature=spoon_tool_vector, + world_feature=pot_vector_x, + tip_link='spoon', + root_link='map', + end_condition=monitor) + zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, + robot_feature=spoon_tool_vector, + world_feature=pot_vector_y, + tip_link='spoon', + root_link='map', + end_condition=monitor) + + # zero_pose.allow_all_collisions() + # zero_pose.execute() + + zero_pose.motion_goals.add_motion_goal(motion_goal_class='TCMPGoal', + name='tcmpTest', + root_link='map', + tip_link='spoon', + start_condition=monitor, + end_condition=time_monitor) + zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, + robot_feature=spoon_tool_vector, + world_feature=pot_vector_x, + tip_link='spoon', + root_link='map', + start_condition=monitor, + end_condition=time_monitor) + zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, + robot_feature=spoon_tool_vector, + world_feature=pot_vector_y, + tip_link='spoon', + root_link='map', + start_condition=monitor, + end_condition=time_monitor) + zero_pose.monitors.add_end_motion(time_monitor) + zero_pose.allow_all_collisions() + zero_pose.execute(add_local_minimum_reached=False) + # kernprof -lv py.test -s test/test_integration_pr2.py # time: [1-9][1-9]*.[1-9]* s # import pytest From bb3604a0859ebef6ad06aa57807439d243ee3175 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 28 May 2024 10:05:13 +0200 Subject: [PATCH 03/43] improved distance function and added aligned function --- src/giskardpy/goals/feature_functions.py | 37 +++++++++++++++++ test/test_integration_pr2.py | 51 ++++++++++++------------ 2 files changed, 62 insertions(+), 26 deletions(-) diff --git a/src/giskardpy/goals/feature_functions.py b/src/giskardpy/goals/feature_functions.py index 3fa8ba7603..1ce82d3c8c 100644 --- a/src/giskardpy/goals/feature_functions.py +++ b/src/giskardpy/goals/feature_functions.py @@ -8,6 +8,7 @@ from giskardpy.symbol_manager import symbol_manager from giskardpy.tasks.task import Task, WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE from giskardpy.goals.pointing import Pointing +from giskardpy.goals.align_planes import AlignPlanes from typing import Optional, List, Dict @@ -128,6 +129,7 @@ def __init__(self, tip_link: str, root_link: str, # project the distance vector onto the x-y plane and calculate its length projection = cas.norm(distance - cas.dot(distance, height_vector) * height_vector) expr = projection + projected_vector = distance - cas.dot(distance, height_vector) * height_vector task = self.create_and_add_task() task.add_inequality_constraint(reference_velocity=max_vel, @@ -136,6 +138,12 @@ def __init__(self, tip_link: str, root_link: str, weight=weight, task_expression=expr, name=f'{name}_constraint') + task.add_inequality_constraint_vector(reference_velocities=[max_vel] * 3, + lower_errors=[0, 0, 0], + upper_errors=[0, 0, 0], + weights=[weight] * 3, + task_expression=projected_vector[:3], + names=['dsf', 'sdf', 'fdg']) # god_map.debug_expression_manager.add_debug_expression('distance-expr', expr) self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) @@ -167,3 +175,32 @@ def __init__(self, tip_link: str, root_link: str, start_condition=start_condition, hold_condition=hold_condition, end_condition=end_condition)) + + +class AlignFeatureFunction(Goal): + def __init__(self, tip_link: str, root_link: str, + world_feature: Vector3Stamped, + robot_feature: Vector3Stamped, + name: str = None, + weight: int = WEIGHT_BELOW_CA, + max_vel: float = 0.2, + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.TrueSymbol + ): + self.root_link = god_map.world.search_for_link_name(root_link, None) + self.tip_link = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' + super().__init__(name) + + self.add_constraints_of_goal(AlignPlanes(root_link=root_link, + tip_link=tip_link, + goal_normal=world_feature, + tip_normal=robot_feature, + reference_velocity=max_vel, + weight=weight, + name=name, + start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition)) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 89783a256a..6db72ca6f5 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -42,7 +42,7 @@ GiskardTestWrapper, pr2_urdf from giskardpy.goals.manipulability_goals import MaxManipulability from giskardpy.goals.feature_functions import DistanceFeatureFunction, PointingFeatureFunction, \ - PerpendicularFeatureFunction, HeightFeatureFunction + PerpendicularFeatureFunction, HeightFeatureFunction, AlignFeatureFunction # scopes = ['module', 'class', 'function'] pocky_pose = {'r_elbow_flex_joint': -1.29610152504, @@ -4478,6 +4478,9 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): pot_vector_y = Vector3Stamped() pot_vector_y.header.frame_id = 'pot' pot_vector_y.vector.y = 1 + pot_vector_z = Vector3Stamped() + pot_vector_z.header.frame_id = 'pot' + pot_vector_z.vector.z = -1 # ------------------------------- motion code ------------------------------------------------------------- monitor = zero_pose.monitors.add_pointing_at(goal_point=pot_center_point, tip_link='spoon', @@ -4499,25 +4502,30 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): upper_limit=0.0, tip_link='spoon', root_link='map', - max_vel=0.1, + max_vel=0.3, end_condition=monitor) + zero_pose.motion_goals.add_motion_goal(motion_goal_class=AlignFeatureFunction.__name__, + robot_feature=spoon_tool_vector, + world_feature=pot_vector_z, + tip_link='spoon', + root_link='map') # zero_pose.motion_goals.add_motion_goal(motion_goal_class=PointingFeatureFunction.__name__, # robot_feature=spoon_tool_vector, # world_feature=pot_center_point, # tip_link='spoon', # root_link='map') - zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, - robot_feature=spoon_tool_vector, - world_feature=pot_vector_x, - tip_link='spoon', - root_link='map', - end_condition=monitor) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, - robot_feature=spoon_tool_vector, - world_feature=pot_vector_y, - tip_link='spoon', - root_link='map', - end_condition=monitor) + # zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, + # robot_feature=spoon_tool_vector, + # world_feature=pot_vector_x, + # tip_link='spoon', + # root_link='map', + # end_condition=monitor) + # zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, + # robot_feature=spoon_tool_vector, + # world_feature=pot_vector_y, + # tip_link='spoon', + # root_link='map', + # end_condition=monitor) # zero_pose.allow_all_collisions() # zero_pose.execute() @@ -4528,20 +4536,11 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): tip_link='spoon', start_condition=monitor, end_condition=time_monitor) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, + zero_pose.motion_goals.add_motion_goal(motion_goal_class=AlignFeatureFunction.__name__, robot_feature=spoon_tool_vector, - world_feature=pot_vector_x, + world_feature=pot_vector_z, tip_link='spoon', - root_link='map', - start_condition=monitor, - end_condition=time_monitor) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, - robot_feature=spoon_tool_vector, - world_feature=pot_vector_y, - tip_link='spoon', - root_link='map', - start_condition=monitor, - end_condition=time_monitor) + root_link='map') zero_pose.monitors.add_end_motion(time_monitor) zero_pose.allow_all_collisions() zero_pose.execute(add_local_minimum_reached=False) From 0ed1cd4a6a7b6ad0ba5ecff5477ac0e7adce3474 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 28 May 2024 10:08:28 +0200 Subject: [PATCH 04/43] cleaned up code --- test/test_integration_pr2.py | 22 +--------------------- 1 file changed, 1 insertion(+), 21 deletions(-) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 6db72ca6f5..34cd951d1c 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -4509,27 +4509,7 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): world_feature=pot_vector_z, tip_link='spoon', root_link='map') - # zero_pose.motion_goals.add_motion_goal(motion_goal_class=PointingFeatureFunction.__name__, - # robot_feature=spoon_tool_vector, - # world_feature=pot_center_point, - # tip_link='spoon', - # root_link='map') - # zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, - # robot_feature=spoon_tool_vector, - # world_feature=pot_vector_x, - # tip_link='spoon', - # root_link='map', - # end_condition=monitor) - # zero_pose.motion_goals.add_motion_goal(motion_goal_class=PerpendicularFeatureFunction.__name__, - # robot_feature=spoon_tool_vector, - # world_feature=pot_vector_y, - # tip_link='spoon', - # root_link='map', - # end_condition=monitor) - - # zero_pose.allow_all_collisions() - # zero_pose.execute() - + # --------------------- second phase ---------------------------------------------------------- zero_pose.motion_goals.add_motion_goal(motion_goal_class='TCMPGoal', name='tcmpTest', root_link='map', From 45cdf7ef0de2d08637357e570d22da5c0a3395b1 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 28 May 2024 11:10:43 +0200 Subject: [PATCH 05/43] added HeightFeature Monitor and improved mixing test --- .../task_critical_motion_pattern_goal.py | 4 +- src/giskardpy/monitors/feature_monitors.py | 41 +++++++++++++++ test/test_integration_pr2.py | 52 +++++++++++++++++-- 3 files changed, 92 insertions(+), 5 deletions(-) create mode 100644 src/giskardpy/monitors/feature_monitors.py diff --git a/src/giskardpy/goals/task_critical_motion_pattern_goal.py b/src/giskardpy/goals/task_critical_motion_pattern_goal.py index 12d65c5879..098d885193 100644 --- a/src/giskardpy/goals/task_critical_motion_pattern_goal.py +++ b/src/giskardpy/goals/task_critical_motion_pattern_goal.py @@ -43,12 +43,12 @@ def __init__(self, tip_link: str, root_link: str, name: str = None, critical_task = self.create_and_add_task(task_name='critial task') def select_movement_function(function_description: str, params: Dict[str, float] = None): - return cas.sin(symbol_manager.get_symbol(f'god_map.time')) + return cas.sin(symbol_manager.get_symbol(f'god_map.time') * 3) * 0.05 function = select_movement_function(function_description=movement_function) root_P_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link).to_position() critical_task.add_equality_constraint_vector(reference_velocities=[0.3] * 3, - equality_bounds=(cas.Vector3([2, function, 0.8]) - root_P_tip)[:3], + equality_bounds=(cas.Vector3([2, function, 0.9]) - root_P_tip)[:3], weights=[WEIGHT_BELOW_CA] * 3, task_expression=root_P_tip[:3], names=['sdf', 'gdf', 'hgj']) diff --git a/src/giskardpy/monitors/feature_monitors.py b/src/giskardpy/monitors/feature_monitors.py new file mode 100644 index 0000000000..9bee936687 --- /dev/null +++ b/src/giskardpy/monitors/feature_monitors.py @@ -0,0 +1,41 @@ +from typing import List, Optional + +from geometry_msgs.msg import PointStamped, QuaternionStamped, PoseStamped, Vector3Stamped + +import giskardpy.casadi_wrapper as cas +from giskardpy.monitors.monitors import ExpressionMonitor, Monitor +from giskardpy.god_map import god_map +import giskardpy.utils.tfwrapper as tf +from giskardpy.utils.expression_definition_utils import transform_msg, transform_msg_and_turn_to_expr + + +class HeightFeature(ExpressionMonitor): + def __init__(self, + tip_link: str, root_link: str, + world_feature: PointStamped, + robot_feature: PointStamped, + lower_limit: float, + upper_limit: float, + name: Optional[str] = None, + stay_true: bool = True, + start_condition: cas.Expression = cas.TrueSymbol): + super().__init__(name=name, stay_true=stay_true, start_condition=start_condition) + self.root = god_map.world.search_for_link_name(root_link, None) + self.tip = god_map.world.search_for_link_name(tip_link, None) + + world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) + root_world_feature = god_map.world.transform_msg(self.root, world_feature) + robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) + tip_robot_feature = god_map.world.transform_msg(self.tip, robot_feature) + + root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) + root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) + root_P_world_feature = cas.Point3(root_world_feature) + + distance = root_P_robot_feature - root_P_world_feature + + height_vector = cas.Vector3([0, 0, 1]) + + projection = cas.dot(distance, height_vector) + expr = cas.logic_and(cas.greater(projection, lower_limit), cas.less(projection, upper_limit)) + self.expression = expr diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 34cd951d1c..35a8e4513f 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -43,6 +43,7 @@ from giskardpy.goals.manipulability_goals import MaxManipulability from giskardpy.goals.feature_functions import DistanceFeatureFunction, PointingFeatureFunction, \ PerpendicularFeatureFunction, HeightFeatureFunction, AlignFeatureFunction +from giskardpy.monitors.feature_monitors import HeightFeature # scopes = ['module', 'class', 'function'] pocky_pose = {'r_elbow_flex_joint': -1.29610152504, @@ -4486,6 +4487,15 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): monitor = zero_pose.monitors.add_pointing_at(goal_point=pot_center_point, tip_link='spoon', pointing_axis=spoon_tool_vector, root_link='map') time_monitor = zero_pose.monitors.add_time_above(20) + monitor2 = zero_pose.monitors.add_monitor(monitor_class=HeightFeature.__name__, + robot_feature=spoon_tip_point, + world_feature=pot_center_point, + lower_limit=0.09, + upper_limit=0.2, + tip_link='spoon', + root_link='map', + start_condition=time_monitor + ) zero_pose.motion_goals.add_motion_goal(motion_goal_class=HeightFeatureFunction.__name__, robot_feature=spoon_tip_point, @@ -4508,7 +4518,8 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): robot_feature=spoon_tool_vector, world_feature=pot_vector_z, tip_link='spoon', - root_link='map') + root_link='map', + end_condition=monitor) # --------------------- second phase ---------------------------------------------------------- zero_pose.motion_goals.add_motion_goal(motion_goal_class='TCMPGoal', name='tcmpTest', @@ -4520,8 +4531,43 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): robot_feature=spoon_tool_vector, world_feature=pot_vector_z, tip_link='spoon', - root_link='map') - zero_pose.monitors.add_end_motion(time_monitor) + root_link='map', + start_condition=monitor, + end_condition=time_monitor + ) + # -------------------- third phase --------------------------------------------------------- + zero_pose.motion_goals.add_motion_goal(motion_goal_class=HeightFeatureFunction.__name__, + robot_feature=spoon_tip_point, + world_feature=pot_center_point, + lower_limit=0.1, + upper_limit=0.1, + tip_link='spoon', + root_link='map', + start_condition=time_monitor, + end_condition=monitor2) + zero_pose.motion_goals.add_motion_goal(motion_goal_class=DistanceFeatureFunction.__name__, + robot_feature=spoon_tip_point, + world_feature=pot_center_point, + lower_limit=-0.1, + upper_limit=-0.1, + tip_link='spoon', + root_link='map', + max_vel=0.3, + start_condition=time_monitor, + end_condition=monitor2) + zero_pose.motion_goals.add_motion_goal(motion_goal_class=AlignFeatureFunction.__name__, + robot_feature=spoon_tool_vector, + world_feature=pot_vector_z, + tip_link='spoon', + root_link='map', + start_condition=time_monitor, + end_condition=monitor2) + # -------------------- secondary tasks ----------------------------------------------------- + zero_pose.motion_goals.add_motion_goal(motion_goal_class=MaxManipulability.__name__, + root_link='torso_lift_link', + tip_link=zero_pose.r_tip) + + zero_pose.monitors.add_end_motion(monitor2) zero_pose.allow_all_collisions() zero_pose.execute(add_local_minimum_reached=False) From 58074d515b9009f3c4adc4d77cb9a2a4320d8b09 Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 30 May 2024 12:22:02 +0200 Subject: [PATCH 06/43] added monitors for all feature functions --- src/giskardpy/goals/feature_functions.py | 39 ++++++++++ src/giskardpy/monitors/feature_monitors.py | 91 +++++++++++++++++++--- test/test_integration_pr2.py | 26 ++++++- 3 files changed, 144 insertions(+), 12 deletions(-) diff --git a/src/giskardpy/goals/feature_functions.py b/src/giskardpy/goals/feature_functions.py index 1ce82d3c8c..00363b38c0 100644 --- a/src/giskardpy/goals/feature_functions.py +++ b/src/giskardpy/goals/feature_functions.py @@ -204,3 +204,42 @@ def __init__(self, tip_link: str, root_link: str, start_condition=start_condition, hold_condition=hold_condition, end_condition=end_condition)) + + +class AngleFeatureFunction(Goal): + def __init__(self, tip_link: str, root_link: str, + world_feature: Vector3Stamped, + robot_feature: Vector3Stamped, + lower_angle: float, + upper_angle: float, + name: str = None, + weight: int = WEIGHT_BELOW_CA, + max_vel: float = 0.2, + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.TrueSymbol + ): + self.root_link = god_map.world.search_for_link_name(root_link, None) + self.tip_link = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' + super().__init__(name) + world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) + root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) + robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) + tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) + + root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) + root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) + root_V_world_feature = cas.Vector3(root_world_feature) + + expr = cas.angle_between_vector(root_V_world_feature, root_V_robot_feature) + + task = self.create_and_add_task() + task.add_inequality_constraint(reference_velocity=max_vel, + upper_error=upper_angle - expr, + lower_error=lower_angle - expr, + weight=weight, + task_expression=expr, + name=f'{name}_constraint') + self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) diff --git a/src/giskardpy/monitors/feature_monitors.py b/src/giskardpy/monitors/feature_monitors.py index 9bee936687..9bd2fb1e73 100644 --- a/src/giskardpy/monitors/feature_monitors.py +++ b/src/giskardpy/monitors/feature_monitors.py @@ -1,4 +1,4 @@ -from typing import List, Optional +from typing import List, Optional, Union from geometry_msgs.msg import PointStamped, QuaternionStamped, PoseStamped, Vector3Stamped @@ -9,13 +9,11 @@ from giskardpy.utils.expression_definition_utils import transform_msg, transform_msg_and_turn_to_expr -class HeightFeature(ExpressionMonitor): +class FeatureMonitor(ExpressionMonitor): def __init__(self, tip_link: str, root_link: str, - world_feature: PointStamped, - robot_feature: PointStamped, - lower_limit: float, - upper_limit: float, + world_feature: Union[PointStamped, Vector3Stamped], + robot_feature: Union[PointStamped, Vector3Stamped], name: Optional[str] = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol): @@ -29,13 +27,88 @@ def __init__(self, tip_robot_feature = god_map.world.transform_msg(self.tip, robot_feature) root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) - root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) - root_P_world_feature = cas.Point3(root_world_feature) + if type(robot_feature) == PointStamped: + self.root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) + elif type(robot_feature) == Vector3Stamped: + self.root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) + + if type(world_feature) == PointStamped: + self.root_P_world_feature = cas.Point3(root_world_feature) + if type(world_feature) == Vector3Stamped: + self.root_V_world_feature = cas.Vector3(root_world_feature) + + +class HeightFeatureMonitor(FeatureMonitor): + def __init__(self, + tip_link: str, root_link: str, + world_feature: PointStamped, + robot_feature: PointStamped, + lower_limit: float, + upper_limit: float, + name: Optional[str] = None, + stay_true: bool = True, + start_condition: cas.Expression = cas.TrueSymbol): + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) - distance = root_P_robot_feature - root_P_world_feature + distance = self.root_P_robot_feature - self.root_P_world_feature height_vector = cas.Vector3([0, 0, 1]) projection = cas.dot(distance, height_vector) expr = cas.logic_and(cas.greater(projection, lower_limit), cas.less(projection, upper_limit)) self.expression = expr + + +class PerpendicularFeatureMonitor(FeatureMonitor): + def __init__(self, tip_link: str, root_link: str, + world_feature: Vector3Stamped, + robot_feature: Vector3Stamped, + threshold: float = 0.01, + name: str = None, + stay_true: bool = True, + start_condition: cas.Expression = cas.TrueSymbol, + ): + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) + + expr = cas.dot(self.root_V_world_feature[:3], self.root_V_robot_feature[:3]) + self.expression = cas.less_equal(cas.abs(expr), threshold) + + +class DistanceFeatureMonitor(FeatureMonitor): + def __init__(self, tip_link: str, root_link: str, + world_feature: PointStamped, + robot_feature: PointStamped, + lower_limit: float, + upper_limit: float, + name: str = None, + stay_true: bool = True, + start_condition: cas.Expression = cas.TrueSymbol, + ): + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) + + distance_vector = self.root_P_robot_feature - self.root_P_world_feature + height_vector = cas.Vector3([0, 0, 1]) + projection = cas.norm(distance_vector - cas.dot(distance_vector, height_vector) * height_vector) + self.expression = cas.logic_and(cas.greater(projection, lower_limit), cas.less(projection, upper_limit)) + + +#TODO: PointingAt monitor and VectorAligned monitor already exist + +class AngleFeatureMonitor(FeatureMonitor): + def __init__(self, tip_link: str, root_link: str, + world_feature: Vector3Stamped, + robot_feature: Vector3Stamped, + lower_limit: float, + upper_limit: float, + name: str = None, + stay_true: bool = True, + start_condition: cas.Expression = cas.TrueSymbol, + ): + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) + + expr = cas.angle_between_vector(self.root_V_world_feature, self.root_V_robot_feature) + self.expression = cas.logic_and(cas.greater(expr, lower_limit), cas.less(expr, upper_limit)) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 35a8e4513f..1267afe2aa 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -43,7 +43,7 @@ from giskardpy.goals.manipulability_goals import MaxManipulability from giskardpy.goals.feature_functions import DistanceFeatureFunction, PointingFeatureFunction, \ PerpendicularFeatureFunction, HeightFeatureFunction, AlignFeatureFunction -from giskardpy.monitors.feature_monitors import HeightFeature +from giskardpy.monitors.feature_monitors import HeightFeatureMonitor # scopes = ['module', 'class', 'function'] pocky_pose = {'r_elbow_flex_joint': -1.29610152504, @@ -4392,6 +4392,26 @@ def test_feature_perpendicular(self, zero_pose: PR2TestWrapper): zero_pose.add_default_end_motion_conditions() zero_pose.execute() + def test_feature_angle(self, zero_pose: PR2TestWrapper): + world_feature = Vector3Stamped() + world_feature.header.frame_id = 'map' + world_feature.vector.z = 1 + + robot_feature = Vector3Stamped() + robot_feature.header.frame_id = zero_pose.r_tip + robot_feature.vector.z = 1 + + zero_pose.motion_goals.add_motion_goal(motion_goal_class='AngleFeatureFunction', + root_link='map', + tip_link=zero_pose.r_tip, + world_feature=world_feature, + robot_feature=robot_feature, + lower_angle=0.6, + upper_angle=0.9) + + zero_pose.add_default_end_motion_conditions() + zero_pose.execute() + def test_feature_height(self, zero_pose: PR2TestWrapper): world_feature = PointStamped() world_feature.header.frame_id = 'map' @@ -4486,8 +4506,8 @@ def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): # ------------------------------- motion code ------------------------------------------------------------- monitor = zero_pose.monitors.add_pointing_at(goal_point=pot_center_point, tip_link='spoon', pointing_axis=spoon_tool_vector, root_link='map') - time_monitor = zero_pose.monitors.add_time_above(20) - monitor2 = zero_pose.monitors.add_monitor(monitor_class=HeightFeature.__name__, + time_monitor = zero_pose.monitors.add_time_above(10, start_condition=monitor) + monitor2 = zero_pose.monitors.add_monitor(monitor_class=HeightFeatureMonitor.__name__, robot_feature=spoon_tip_point, world_feature=pot_center_point, lower_limit=0.09, From c326376dcea45392861b41e45332caf5e27c3770 Mon Sep 17 00:00:00 2001 From: malte Date: Fri, 14 Jun 2024 10:56:31 +0200 Subject: [PATCH 07/43] small cleanup --- src/giskardpy/goals/manipulability_goals.py | 16 ++++++++-------- .../goals/task_critical_motion_pattern_goal.py | 5 +++++ 2 files changed, 13 insertions(+), 8 deletions(-) diff --git a/src/giskardpy/goals/manipulability_goals.py b/src/giskardpy/goals/manipulability_goals.py index a75d00ee6c..53806509b3 100644 --- a/src/giskardpy/goals/manipulability_goals.py +++ b/src/giskardpy/goals/manipulability_goals.py @@ -54,14 +54,14 @@ def __init__(self, root_link: str, tip_link: str, gain: float = 0.5, monitor = ManipulabilityMonitor(name=f'manipMonitor{tip_link}') self.add_monitor(monitor) # monitor.expression = cas.less(percentual_diff, monitor_threshold) - task.end_condition = monitor - god_map.debug_expression_manager.add_debug_expression('percentualDiff', percentual_diff) - god_map.debug_expression_manager.add_debug_expression('OldmMnitorValue', - cas.less(percentual_diff, monitor_threshold)) - god_map.debug_expression_manager.add_debug_expression('monitorValue', symbol_manager.get_symbol( - f'god_map.monitor_manager.payload_monitors[-1].state')) - god_map.debug_expression_manager.add_debug_expression('start', 1) - god_map.debug_expression_manager.add_debug_expression('mIndex', m) + # task.end_condition = monitor + # god_map.debug_expression_manager.add_debug_expression('percentualDiff', percentual_diff) + # god_map.debug_expression_manager.add_debug_expression('OldmMnitorValue', + # cas.less(percentual_diff, monitor_threshold)) + # god_map.debug_expression_manager.add_debug_expression('monitorValue', symbol_manager.get_symbol( + # f'god_map.monitor_manager.payload_monitors[-1].state')) + # god_map.debug_expression_manager.add_debug_expression('start', 1) + # god_map.debug_expression_manager.add_debug_expression('mIndex', m) """ This goal maximizes the manipulability of the kinematic chain between root_link and tip_link. diff --git a/src/giskardpy/goals/task_critical_motion_pattern_goal.py b/src/giskardpy/goals/task_critical_motion_pattern_goal.py index 098d885193..f35c79ebcc 100644 --- a/src/giskardpy/goals/task_critical_motion_pattern_goal.py +++ b/src/giskardpy/goals/task_critical_motion_pattern_goal.py @@ -36,9 +36,11 @@ def __init__(self, tip_link: str, root_link: str, name: str = None, name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' super().__init__(name) + # -------------- Approach ------------------------------------------------------- # collect approach constraints and monitor their success # approach_task = self.create_and_add_task(task_name='approach task') + # -------------- TCMP ----------------------------------------------------------- # define the task critical movement using the movement function or constraints and monitor their success critical_task = self.create_and_add_task(task_name='critial task') @@ -53,10 +55,13 @@ def select_movement_function(function_description: str, params: Dict[str, float] task_expression=root_P_tip[:3], names=['sdf', 'gdf', 'hgj']) + # ------------- release --------------------------------------------------------- # collect release constraints and monitor their success # release_task = self.create_and_add_task(task_name="release task") + # ------------ monitoring ------------------------------------------------------- # monitor additional values throughout the motion execution # for monitoring_request in monitoring_list: # pass + self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) From 906e13927bba9793f9cc68c7572d82ec47bd6ef8 Mon Sep 17 00:00:00 2001 From: malte Date: Wed, 24 Jul 2024 11:44:58 +0200 Subject: [PATCH 08/43] comments --- src/giskardpy/goals/task_critical_motion_pattern_goal.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/giskardpy/goals/task_critical_motion_pattern_goal.py b/src/giskardpy/goals/task_critical_motion_pattern_goal.py index f35c79ebcc..b2025579c9 100644 --- a/src/giskardpy/goals/task_critical_motion_pattern_goal.py +++ b/src/giskardpy/goals/task_critical_motion_pattern_goal.py @@ -26,6 +26,9 @@ def __init__(self, tip_link: str, root_link: str, name: str = None, movement_function: str = None, reference_frame: str = None, monitoring_list: List[str] = None, + # Tuple for approach functions + # Tuple for release functions + # some kind of tuple for 3 dimensions of the movement function? start_condition: cas.Expression = cas.TrueSymbol, hold_condition: cas.Expression = cas.FalseSymbol, end_condition: cas.Expression = cas.TrueSymbol From dcddb466a8605e5a27837a7cd7943238051fa29f Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 1 Aug 2024 14:00:16 +0200 Subject: [PATCH 09/43] adapted feature function tests --- .../task_critical_motion_pattern_goal.py | 70 ------- test/test_integration_pr2.py | 185 +----------------- 2 files changed, 1 insertion(+), 254 deletions(-) delete mode 100644 src/giskardpy/goals/task_critical_motion_pattern_goal.py diff --git a/src/giskardpy/goals/task_critical_motion_pattern_goal.py b/src/giskardpy/goals/task_critical_motion_pattern_goal.py deleted file mode 100644 index b2025579c9..0000000000 --- a/src/giskardpy/goals/task_critical_motion_pattern_goal.py +++ /dev/null @@ -1,70 +0,0 @@ -from __future__ import division - -from geometry_msgs.msg import PointStamped, PoseStamped, QuaternionStamped -from geometry_msgs.msg import Vector3Stamped -from giskardpy import casadi_wrapper as cas -from giskardpy.goals.goal import Goal -from giskardpy.god_map import god_map -from giskardpy.symbol_manager import symbol_manager -from giskardpy.tasks.task import Task, WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE -from giskardpy.goals.feature_functions import DistanceFeatureFunction, PointingFeatureFunction, \ - PerpendicularFeatureFunction, HeightFeatureFunction - -from typing import Optional, List, Dict - - -class TCMPGoal(Goal): - """ - A Task Critical Motion Pattern models the motions that are essential to successfully execute a task. - For everyday activities of household robots it is assumed that they are always composed of an approach movement - followed by a general movement function and a release movement. - This is more or less in line with the Flanagan model and the movement function could also be further divided - following the Flanagan model. - """ - - def __init__(self, tip_link: str, root_link: str, name: str = None, - movement_function: str = None, - reference_frame: str = None, - monitoring_list: List[str] = None, - # Tuple for approach functions - # Tuple for release functions - # some kind of tuple for 3 dimensions of the movement function? - start_condition: cas.Expression = cas.TrueSymbol, - hold_condition: cas.Expression = cas.FalseSymbol, - end_condition: cas.Expression = cas.TrueSymbol - ): - self.root_link = god_map.world.search_for_link_name(root_link, None) - self.tip_link = god_map.world.search_for_link_name(tip_link, None) - if name is None: - name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' - super().__init__(name) - - # -------------- Approach ------------------------------------------------------- - # collect approach constraints and monitor their success - # approach_task = self.create_and_add_task(task_name='approach task') - - # -------------- TCMP ----------------------------------------------------------- - # define the task critical movement using the movement function or constraints and monitor their success - critical_task = self.create_and_add_task(task_name='critial task') - - def select_movement_function(function_description: str, params: Dict[str, float] = None): - return cas.sin(symbol_manager.get_symbol(f'god_map.time') * 3) * 0.05 - - function = select_movement_function(function_description=movement_function) - root_P_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link).to_position() - critical_task.add_equality_constraint_vector(reference_velocities=[0.3] * 3, - equality_bounds=(cas.Vector3([2, function, 0.9]) - root_P_tip)[:3], - weights=[WEIGHT_BELOW_CA] * 3, - task_expression=root_P_tip[:3], - names=['sdf', 'gdf', 'hgj']) - - # ------------- release --------------------------------------------------------- - # collect release constraints and monitor their success - # release_task = self.create_and_add_task(task_name="release task") - - # ------------ monitoring ------------------------------------------------------- - # monitor additional values throughout the motion execution - # for monitoring_request in monitoring_list: - # pass - - self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 1267afe2aa..9d17423ebb 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -4312,68 +4312,7 @@ def test_manip2(self, zero_pose: PR2TestWrapper): zero_pose.execute(add_local_minimum_reached=True) -class TestTCMPs: - def test_tcmp_pouring(self, zero_pose: PR2TestWrapper): - # TODO: Parameters - angle = 1.7 - velocity = 0.2 - - goal_pose = PoseStamped() - goal_pose.header.frame_id = 'map' - goal_pose.pose.orientation = Quaternion(*quaternion_from_matrix(np.array([[1, 0, 0, 0], - [0, 1, 0, 0], - [0, 0, 1, 0], - [0, 0, 0, 1]]))) - goal_pose.pose.position = Point(2, 0, 0.8) - - goal_rot = PoseStamped() - goal_rot.header.frame_id = zero_pose.r_tip - - rotation_axis = Vector3Stamped() - rotation_axis.header.frame_id = zero_pose.r_tip - rotation_axis.vector = Vector3(1, 0, 0) - - goal_quat = QuaternionStamped() - goal_quat.header.frame_id = zero_pose.r_tip - goal_quat.quaternion = Quaternion( - *quaternion_about_axis(angle, [rotation_axis.vector.x, rotation_axis.vector.y, rotation_axis.vector.z])) - goal_rot.pose.orientation = goal_quat.quaternion - - goal_quat2 = QuaternionStamped() - goal_quat2.header.frame_id = zero_pose.r_tip - goal_quat2.quaternion = Quaternion( - *quaternion_about_axis(-angle, [rotation_axis.vector.x, rotation_axis.vector.y, rotation_axis.vector.z])) - - pose_monitor = zero_pose.monitors.add_cartesian_pose(root_link='map', tip_link=zero_pose.r_tip, - goal_pose=goal_pose) - rot_monitor = zero_pose.monitors.add_cartesian_orientation(root_link='map', tip_link=zero_pose.r_tip, - goal_orientation=goal_quat, - start_condition=pose_monitor) - rot_monitor2 = zero_pose.monitors.add_cartesian_orientation(root_link='map', tip_link=zero_pose.r_tip, - goal_orientation=goal_quat2, - start_condition=rot_monitor) - - zero_pose.motion_goals.add_cartesian_pose(goal_pose=goal_pose, tip_link=zero_pose.r_tip, root_link='map', - end_condition=pose_monitor) - - zero_pose.motion_goals.add_cartesian_pose(goal_rot, zero_pose.r_tip, 'map', - reference_angular_velocity=velocity, - start_condition=pose_monitor, end_condition=rot_monitor) - goal_rot.pose.orientation = goal_quat2.quaternion - zero_pose.motion_goals.add_cartesian_pose(goal_rot, zero_pose.r_tip, 'map', - reference_angular_velocity=velocity * 2, - start_condition=rot_monitor, end_condition=rot_monitor2) - zero_pose.monitors.add_end_motion(rot_monitor2) - zero_pose.allow_all_collisions() - zero_pose.execute(add_local_minimum_reached=False) - - def test_tcmp_goal(self, zero_pose: PR2TestWrapper): - zero_pose.motion_goals.add_motion_goal(motion_goal_class='TCMPGoal', - name='tcmpTest', - root_link='map', - tip_link=zero_pose.r_tip) - zero_pose.execute() - +class TestFeatureFunctions: def test_feature_perpendicular(self, zero_pose: PR2TestWrapper): world_feature = Vector3Stamped() world_feature.header.frame_id = 'map' @@ -4468,128 +4407,6 @@ def test_feature_pointing(self, zero_pose: PR2TestWrapper): zero_pose.add_default_end_motion_conditions() zero_pose.execute() - def test_tcmp_mixing(self, zero_pose: PR2TestWrapper): - # -------------- world definition --------------- - spoon_pose = PoseStamped() - spoon_pose.header.frame_id = zero_pose.r_tip - spoon_pose.pose.orientation.w = 1 - spoon_pose.pose.position.z = -0.1 - zero_pose.add_box(name='spoon', size=(0.03, 0.03, 0.20), pose=spoon_pose, parent_link=zero_pose.r_tip) - pot_pose = PoseStamped() - pot_pose.header.frame_id = 'map' - pot_pose.pose.orientation.w = 1 - pot_pose.pose.position.x = 2 - pot_pose.pose.position.y = 0 - pot_pose.pose.position.z = 0.8 - zero_pose.add_box(name='pot', size=(0.2, 0.2, 0.1), pose=pot_pose, parent_link='map') - - # --------------------------------- object feature definition ------------------------------------------- - spoon_tip_point = PointStamped() - spoon_tip_point.header.frame_id = 'spoon' - spoon_tip_point.point.z = -0.1 - spoon_tool_vector = Vector3Stamped() - spoon_tool_vector.header.frame_id = 'spoon' - spoon_tool_vector.vector.z = -1 - - pot_center_point = PointStamped() - pot_center_point.header.frame_id = 'pot' - pot_vector_x = Vector3Stamped() - pot_vector_x.header.frame_id = 'pot' - pot_vector_x.vector.x = 1 - pot_vector_y = Vector3Stamped() - pot_vector_y.header.frame_id = 'pot' - pot_vector_y.vector.y = 1 - pot_vector_z = Vector3Stamped() - pot_vector_z.header.frame_id = 'pot' - pot_vector_z.vector.z = -1 - - # ------------------------------- motion code ------------------------------------------------------------- - monitor = zero_pose.monitors.add_pointing_at(goal_point=pot_center_point, tip_link='spoon', - pointing_axis=spoon_tool_vector, root_link='map') - time_monitor = zero_pose.monitors.add_time_above(10, start_condition=monitor) - monitor2 = zero_pose.monitors.add_monitor(monitor_class=HeightFeatureMonitor.__name__, - robot_feature=spoon_tip_point, - world_feature=pot_center_point, - lower_limit=0.09, - upper_limit=0.2, - tip_link='spoon', - root_link='map', - start_condition=time_monitor - ) - - zero_pose.motion_goals.add_motion_goal(motion_goal_class=HeightFeatureFunction.__name__, - robot_feature=spoon_tip_point, - world_feature=pot_center_point, - lower_limit=0.1, - upper_limit=0.1, - tip_link='spoon', - root_link='map', - end_condition=monitor) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=DistanceFeatureFunction.__name__, - robot_feature=spoon_tip_point, - world_feature=pot_center_point, - lower_limit=0.0, - upper_limit=0.0, - tip_link='spoon', - root_link='map', - max_vel=0.3, - end_condition=monitor) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=AlignFeatureFunction.__name__, - robot_feature=spoon_tool_vector, - world_feature=pot_vector_z, - tip_link='spoon', - root_link='map', - end_condition=monitor) - # --------------------- second phase ---------------------------------------------------------- - zero_pose.motion_goals.add_motion_goal(motion_goal_class='TCMPGoal', - name='tcmpTest', - root_link='map', - tip_link='spoon', - start_condition=monitor, - end_condition=time_monitor) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=AlignFeatureFunction.__name__, - robot_feature=spoon_tool_vector, - world_feature=pot_vector_z, - tip_link='spoon', - root_link='map', - start_condition=monitor, - end_condition=time_monitor - ) - # -------------------- third phase --------------------------------------------------------- - zero_pose.motion_goals.add_motion_goal(motion_goal_class=HeightFeatureFunction.__name__, - robot_feature=spoon_tip_point, - world_feature=pot_center_point, - lower_limit=0.1, - upper_limit=0.1, - tip_link='spoon', - root_link='map', - start_condition=time_monitor, - end_condition=monitor2) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=DistanceFeatureFunction.__name__, - robot_feature=spoon_tip_point, - world_feature=pot_center_point, - lower_limit=-0.1, - upper_limit=-0.1, - tip_link='spoon', - root_link='map', - max_vel=0.3, - start_condition=time_monitor, - end_condition=monitor2) - zero_pose.motion_goals.add_motion_goal(motion_goal_class=AlignFeatureFunction.__name__, - robot_feature=spoon_tool_vector, - world_feature=pot_vector_z, - tip_link='spoon', - root_link='map', - start_condition=time_monitor, - end_condition=monitor2) - # -------------------- secondary tasks ----------------------------------------------------- - zero_pose.motion_goals.add_motion_goal(motion_goal_class=MaxManipulability.__name__, - root_link='torso_lift_link', - tip_link=zero_pose.r_tip) - - zero_pose.monitors.add_end_motion(monitor2) - zero_pose.allow_all_collisions() - zero_pose.execute(add_local_minimum_reached=False) # kernprof -lv py.test -s test/test_integration_pr2.py # time: [1-9][1-9]*.[1-9]* s From f2009bf8c79ded522f9992288b979296e983dde0 Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 1 Aug 2024 14:18:29 +0200 Subject: [PATCH 10/43] finished merge --- test/test_integration_pr2.py | 1 + 1 file changed, 1 insertion(+) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 54938a5003..b71590fad6 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -11,6 +11,7 @@ import rospy from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, QuaternionStamped, Pose, \ Vector3 +from nav_msgs.msg import Path from numpy import pi from shape_msgs.msg import SolidPrimitive from tf.transformations import quaternion_from_matrix, quaternion_about_axis From d6ec9cefd20c05ed182a9a723907752096a45618 Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 5 Aug 2024 14:25:05 +0200 Subject: [PATCH 11/43] giskard example notebook --- scripts/giskard_examples.ipynb | 555 +++++++++++++++++++++++++++++++++ 1 file changed, 555 insertions(+) create mode 100644 scripts/giskard_examples.ipynb diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb new file mode 100644 index 0000000000..6780e5b093 --- /dev/null +++ b/scripts/giskard_examples.ipynb @@ -0,0 +1,555 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Set parameter ServerPassword\n", + "Set parameter ServerTimeout to value 10\n", + "Set parameter TokenServer to value \"134.102.206.102\"\n", + "[/unnamed]: Found these qp solvers: ['gurobi', 'qpalm', 'qpSWIFT']\n" + ] + } + ], + "source": [ + "from giskardpy.python_interface.python_interface import GiskardWrapper\n", + "import numpy as np\n", + "import pytest\n", + "import rospy\n", + "from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, QuaternionStamped, Pose, Vector3\n", + "from nav_msgs.msg import Path\n", + "from numpy import pi\n", + "from shape_msgs.msg import SolidPrimitive\n", + "from tf.transformations import quaternion_from_matrix, quaternion_about_axis\n", + "\n", + "import giskardpy.utils.tfwrapper as tf\n", + "from giskard_msgs.msg import WorldBody, CollisionEntry, WorldGoal, GiskardError\n", + "from giskardpy.configs.behavior_tree_config import StandAloneBTConfig\n", + "from giskardpy.configs.giskard import Giskard\n", + "from giskardpy.configs.iai_robots.pr2 import PR2CollisionAvoidance, PR2StandaloneInterface, WorldWithPR2Config\n", + "from giskardpy.configs.qp_controller_config import SupportedQPSolver, QPControllerConfig\n", + "from giskardpy.goals.base_traj_follower import FollowNavPath\n", + "from giskardpy.goals.cartesian_goals import RelativePositionSequence\n", + "from giskardpy.goals.caster import Circle, Wave\n", + "from giskardpy.goals.collision_avoidance import CollisionAvoidanceHint\n", + "from giskardpy.goals.goals_tests import DebugGoal, CannotResolveSymbol\n", + "from giskardpy.goals.joint_goals import JointVelocityLimit, UnlimitedJointGoal\n", + "from giskardpy.monitors.set_prediction_horizon import SetQPSolver\n", + "from giskardpy.goals.tracebot import InsertCylinder\n", + "from giskardpy.god_map import god_map\n", + "from giskardpy.model.better_pybullet_syncer import BetterPyBulletSyncer\n", + "from giskardpy.model.collision_world_syncer import CollisionWorldSynchronizer\n", + "from giskardpy.model.utils import make_world_body_box, hacky_urdf_parser_fix\n", + "from giskardpy.model.world import WorldTree\n", + "from giskardpy.data_types import PrefixName\n", + "from giskardpy.tasks.task import WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE\n", + "from giskardpy.python_interface.old_python_interface import OldGiskardWrapper\n", + "from giskardpy.utils.utils import launch_launchfile, suppress_stderr, resolve_ros_iris\n", + "from giskardpy.utils.math import compare_points\n", + "from giskardpy.goals.weight_scaling_goals import MaxManipulabilityLinWeight, BaseArmWeightScaling\n", + "from copy import deepcopy" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 2, + "outputs": [], + "source": [ + "rospy.init_node('giskard_examples')" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 3, + "outputs": [], + "source": [ + "gs = GiskardWrapper()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 7, + "outputs": [], + "source": [ + "def reset_giskard():\n", + " gs.clear_motion_goals_and_monitors()\n", + " default_pose = {\n", + " 'r_elbow_flex_joint': -0.15,\n", + " 'r_forearm_roll_joint': 0,\n", + " 'r_shoulder_lift_joint': 0,\n", + " 'r_shoulder_pan_joint': 0,\n", + " 'r_upper_arm_roll_joint': 0,\n", + " 'r_wrist_flex_joint': -0.10001,\n", + " 'r_wrist_roll_joint': 0,\n", + " 'l_elbow_flex_joint': -0.15,\n", + " 'l_forearm_roll_joint': 0,\n", + " 'l_shoulder_lift_joint': 0,\n", + " 'l_shoulder_pan_joint': 0,\n", + " 'l_upper_arm_roll_joint': 0,\n", + " 'l_wrist_flex_joint': -0.10001,\n", + " 'l_wrist_roll_joint': 0,\n", + " 'torso_lift_joint': 0.2,\n", + " 'head_pan_joint': 0,\n", + " 'head_tilt_joint': 0,\n", + " 'l_gripper_l_finger_joint': 0.55,\n", + " 'r_gripper_l_finger_joint': 0.55\n", + " }\n", + " done = gs.monitors.add_set_seed_configuration(default_pose)\n", + " base_pose = PoseStamped()\n", + " base_pose.header.frame_id = 'map'\n", + " base_pose.pose.position = Point(0, 0, 0)\n", + " base_pose.pose.orientation.w = 1\n", + " done2 = gs.monitors.add_set_seed_odometry(base_pose=base_pose)\n", + " gs.motion_goals.allow_all_collisions()\n", + " gs.monitors.add_end_motion(start_condition=done and done2)\n", + " gs.execute()\n", + " gs.clear_motion_goals_and_monitors()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "Giskard is a constraint- and optimization-based whole-body motion planning/control framework.\n", + "In short explain the QP...\n", + "Explain a constraint and how it influences the QP...\n", + "When using the python wrapper you do not specify constraints directly but rather a Motion Goal to parameterize a predefined set of constraints.\n", + "Additionally, the python interface allows to specify monitors that monitor a mathematical expression against a threshold and evaluate into a binary value.\n", + "They are used to start, stop or interrupt motion goals. More complex motion goals might specify their own monitors to chain constraints together.\n", + "Show picture of PR2 TF Tree..." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "The simplest possible motion goal call follows the following schema:\n", + "\n", + " - Define a motion goal.\n", + " - Define a monitor that checks if the goal was reached.\n", + " - Define an end motion monitor, which has as start_condition the goal reached monitor.\n" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 8, + "outputs": [ + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995223908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044781599804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990447611174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044740634857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985671730117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044823788993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2025998089584906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044823788988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976119968005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134408695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966568205893, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961792324837, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2058495701644378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952240562724, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20714947464681668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20779942688800612, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20844937912919556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209099331370385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20974928361157444, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21039923585276388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21104918809395332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21169914033514275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2123490925763322, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21299904481752163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21364899705871107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2142989492999005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21494890154108995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2155988537822794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624880602346883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21689875826465826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2175487105058477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21819866274703714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21884861498822658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21949856722941602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22014851947060546, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2207984717117949, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22144842395298434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22209837619417377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2227483284353632, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22339828067655265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2240482329177421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22469818515893153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22534813740012097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2259980896413104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22664804188249985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22729799412368928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22794794636487872, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22859789860606816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2292478508472576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22989780308844704, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23054775532963648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23119770757082592, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23184765981201536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2324976120532048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23314756429439423, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23379751653558367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2344474687767731, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23509742101796255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.235747373259152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23639732550034143, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23704727774153087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2376972299827203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23834718222390974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23899713446509918, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23964708670628862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24029703894747806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2409469911886675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24159694342985694, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24224689567104637, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2428968479122358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24354680015342525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2441967523946147, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24484670463580413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24549665687699357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.246146609118183, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24679656135937245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24744651360056188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24809646584175132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24874641808294076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2493963703241302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25004632256531967, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25069627480650913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2513462270476986, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25199617928888807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25264613153007753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.253296083771267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25394603601245647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25459598825364593, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2552459404948354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25589589273602487, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25654584497721433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2571957972184038, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25784574945959327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25849570170078273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2591456539419722, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25979560618316166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26044555842435113, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2610955106655406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26174546290673006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26239541514791953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.263045367389109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26369531963029846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26434527187148793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2649952241126774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26564517635386686, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26629512859505633, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2669450808362458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26759503307743526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26824498531862473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2688949375598142, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26954488980100366, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27019484204219313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2708447942833826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27149474652457206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27214469876576153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.272794651006951, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27344460324814046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2740945554893299, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2747445077305194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27539445997170886, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2760444122128983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2766943644540878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27734431669527726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2779942689364667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2786442211776562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27929417341884566, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2799441256600351, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2805940779012246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28124403014241406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2818939823836035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.282543934624793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28319388686598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2838438391071719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2844937913483614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28514374358955086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2857936958307403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2864436480719298, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28709360031311926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2877435525543087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2883935047954982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28904345703668766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2896934092778771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2903433615190666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0" + }, + "execution_count": 8, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "reset_giskard()\n", + "\n", + "joint_goal = {'torso_lift_joint': 0.3}\n", + "joint_monitor = gs.monitors.add_joint_position(goal_state=joint_goal)\n", + "gs.motion_goals.add_joint_position(goal_state=joint_goal)\n", + "gs.monitors.add_end_motion(start_condition=joint_monitor)\n", + "gs.execute()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "A commonly used goal is a cartesian pose goal. It is used to move a link of the robot to a specific pose. Frequently used links are the endeffector links or the base link." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 9, + "outputs": [ + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995224128082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.003749999998426497, 0.0037500000000161406, -0.0037499999999998975, -0.14999999999982933, 0.0009726135623061073, -0.10000999999993533, 0.003749999999999878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529551367, -0.0006253905029042516, -0.0006250000000005031]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825616084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999996852993, 0.07500000000009105, -0.07499999999999783, 3.413413898528338e-12, 0.019452271246122144, 1.2934985057206626e-12, 0.07499999999999801, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059102733, -0.012507810058085031, -0.012500000000000719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999044865274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.010874000462810094, 0.014999999121785897, -0.014999999999929904, -0.15000000000052507, 0.00249685109396703, -0.10001000000022002, 0.014999999999935657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.002494915898464792, -0.0025050721386444116, -0.002499999999906253]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044904931787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1424800092876719, 0.2249999824353951, -0.22499999999860015, -1.3914817577019912e-11, 0.030484750633218455, -5.693777305049226e-12, 0.22499999999871556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0374061329101931, -0.0375936327148032, -0.0374999999999795]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985673060278, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.019214385627334598, 0.03214772656204189, -0.03562499999935418, -0.15000000000054162, 0.004003912303603865, -0.10001000000023216, 0.03562499999940766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005911945269440533, -0.005962921582434169, -0.005937499999840859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881507441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1668077032904901, 0.3429545488051197, -0.4124999999884855, -3.3086328286054907e-13, 0.030141224192736706, -2.427690312094603e-13, 0.4124999999894401, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06834058741951482, -0.06915698887579515, -0.06874999999869214]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2025998089745868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.027332611693070694, 0.05225635205961038, -0.06406249999670444, -0.15000000000063227, 0.00509351329647851, -0.1000100000002995, 0.06406249999708183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010600654477185504, -0.010752838725563377, -0.010677083330842652]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487968028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.16236452131472193, 0.40217250995136977, -0.5687499999470049, -1.8132440942715141e-12, 0.021792019857492892, -1.3466319672723584e-12, 0.5687499999534835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09377418415489941, -0.09579834286258415, -0.09479166662003588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2032497612186043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.03465601580721158, 0.07338202302242261, -0.09881249999420641, -0.15000000000064317, 0.005562151157030444, -0.10001000000030755, 0.09881249999494346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016296158549235513, -0.016639097200595834, -0.016468749995204174]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880350157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1464680822828177, 0.4225134192562447, -0.6949999999500392, -2.1797790610805456e-13, 0.009372757211038677, -1.6105727900585533e-13, 0.6949999999572325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11391008144100016, -0.11772516950064911, -0.1158333332872304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134620561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04107639227844112, 0.09452901507328197, -0.13861249997290648, -0.15000000000198216, 0.005347532109568132, -0.10001000000140058, 0.13861249995264174, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022774491634322096, -0.023423890671478025, -0.023102083324553664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869035943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.12840752942459085, 0.42293984101718723, -0.7959999995740012, -2.677979323697273e-11, -0.004292380949246234, -2.1860605853446573e-11, 0.7959999991539658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12956666170173162, -0.1356958694176438, -0.1326666665869898]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966570582583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04666118591631699, 0.11525153479943673, -0.18245249994872562, -0.15000000000228894, 0.004470968152595306, -0.10001000000169422, 0.18245249991166518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029855627973834894, -0.030949331744835305, -0.030408749986253168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044875394872, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.11169587275751738, 0.4144503945230952, -0.8767999995163827, -6.1357932112318646e-12, -0.01753127913945652, -5.8727073376287276e-12, 0.8767999991804688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14162272679025595, -0.1505088214671456, -0.1461333332339901]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961794978372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05152178527779883, 0.1353647889149822, -0.22952449992876367, -0.15000000000234268, 0.0029953253590808606, -0.10001000000174005, 0.2295244998783314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03739517881513101, -0.03908896828573813, -0.0382540833152034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879157857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09721198722963685, 0.402265082310909, -0.9414399996007609, -1.0748467169952566e-12, -0.029512855870288908, -9.167461066347978e-13, 0.9414399993333245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15079101682592239, -0.16279273081805654, -0.15690666657900465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966648689288, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05576265608289525, 0.15399602312200017, -0.2791820999128309, -0.1500000000017874, 0.0010285471017613223, -0.10001000000065693, 0.2791820998517253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04527752908108162, -0.047741235841549406, -0.04653034997789501]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999029257817154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08481741610192829, 0.3726246841403596, -0.9931519996813443, 1.1105360308673324e-11, -0.039335565146390764, 2.166230133870735e-11, 0.993151999467878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15764700531901213, -0.17304535111622546, -0.16552533325383217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20389971424308817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05942678249747326, 0.17116549308609977, -0.32918212496676713, -0.15000000000206704, -0.001336658350849851, -0.10001000000106844, 0.3291820998507171, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05341021492784108, -0.05682436098581435, -0.055151363307386986]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044876094263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07328252829156022, 0.3433893992819922, -1.0000005010787243, -5.592900813623596e-12, -0.04730410905222346, -8.230135473705073e-12, 0.9999999999798355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16265371693518918, -0.1816625028852989, -0.1724202665898396]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976199901068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06254927332067894, 0.18720822280178823, -0.3791821500200128, -0.15000000000220307, -0.0040210550792610135, -0.10001000000208868, 0.3791820998487869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.061719348735855044, -0.06627236474911988, -0.06404817396991841]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488154993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.062449816464113767, 0.32085459431376934, -1.000000501064914, -2.720657585222056e-12, -0.053687934568223246, -2.0404835988778344e-11, 0.9999999999613957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16618267616027926, -0.18896007526611042, -0.17793621325062856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980975502256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06530334246783995, 0.20274448077030074, -0.42918217507376827, -0.150000000002362, -0.006981139353238399, -0.10169702523622634, 0.42918209984579514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07014591555267684, -0.07603190914626919, -0.07316562249855446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879762176, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05508138294321995, 0.31072515937025036, -1.0000005010751092, -3.178670627095961e-12, -0.059201685479547704, -0.03374050468275326, 0.9999999999401649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16853133633643577, -0.1951908879429861, -0.18234897057272118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985751100356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06790328523509014, 0.21824311964802745, -0.47918220012370066, -0.1500000000023791, -0.010200549301847222, -0.10666265915696402, 0.479182099845268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07864278700313587, -0.0860597960924229, -0.0824595813214565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880380298, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05199885534500379, 0.30997277755453384, -1.0000005009986477, -3.419628306111715e-13, -0.06438819897217644, -0.09931267841475351, 0.9999999999894567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1699374290091808, -0.20055773892307413, -0.18587917645804092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999052667752, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0698257236356248, 0.23421513254549522, -0.525432225169826, -0.1500000000023803, -0.017429254760860668, -0.1153266305046296, 0.5257753718839405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08717232125632797, -0.09632097536722978, -0.09189474837977776]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884567195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.038448768010693184, 0.31944025794935554, -0.9250005009225063, -2.4558949901505577e-14, -0.14457410918026892, -0.17327942695331155, 0.9318654407734511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17059068506384195, -0.20522358549613762, -0.18870334116642523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995302277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07072955470746402, 0.2508652922059786, -0.5641822502121976, -0.1500000000023839, -0.024917259070361825, -0.12713418211536878, 0.5652119159618963, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09570443891067591, -0.10678695264977467, -0.10144288202640352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880103793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018076621436784384, 0.3330031932096672, -0.7750005008474314, -7.163789731263766e-14, -0.1497600861900231, -0.23615103221478356, 0.7887308815591166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17064235308695888, -0.20931954565089778, -0.19096267293251507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000000007787679, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07051671251909349, 0.268156085445879, -0.5916822752530768, -0.15000000000252947, -0.030483560079777795, -0.1410550519159715, 0.5937417320800253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10421508353998447, -0.11743451382759128, -0.11108138894132084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880041834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004256843767410735, 0.3458158647980082, -0.5500005008175851, -2.9113963874629762e-12, -0.11132602018831939, -0.2784173960120548, 0.5705963223625797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17021289258617123, -0.21295122355633223, -0.19277013829834663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935004853499577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06914440590006907, 0.2860034411792493, -0.6041823002928683, -0.1500000000025775, -0.034551304873879134, -0.15604040622717463, 0.6076148202386424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11268499205073444, -0.12824470059199697, -0.12079219447249467]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875442563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027446132380488278, 0.3569471146674063, -0.2500005007958297, -9.603601719665634e-13, -0.08135489588202678, -0.2997070862240625, 0.2774617631723428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16939817021499945, -0.21620373528811399, -0.1942161106234766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009629126512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06662506364786523, 0.3043069196152068, -0.6033489878269833, -0.15000000000261468, -0.0377013785949796, -0.17129104770331385, 0.6079257270381646, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12109871381632487, -0.1392019864674616, -0.1305608388964588]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044874612967, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0503868450440767, 0.3660695687191493, 0.016666249317699444, -7.435904150903004e-13, -0.0630014744220093, -0.3050128295227844, 0.006218135990444407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1682744353118084, -0.21914571750929274, -0.19537288847928289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980501440472577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06301180850687928, 0.3229607227779738, -0.5914045607766345, -0.15000000000275565, -0.0404202259926186, -0.18633468310182805, 0.5969348160408071, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12944382915393812, -0.15029361321615042, -0.14037575443354122]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880148077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07226510281971905, 0.37307606325533976, 0.23888854100697743, -2.8192075957799583e-12, -0.05437694795278004, -0.300872707970284, -0.21981821994715087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16690230675226528, -0.22183253497377647, -0.19629831074164802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019180376744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05835369809320081, 0.3418781576483917, -0.5702008715717964, -0.15000000000280575, -0.042984091717350646, -0.2009783937928531, 0.5765257235469713, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1377103272166334, -0.16150905591226594, -0.1502276868616847]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869805191, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0931622082735693, 0.37834869740835814, 0.42407378409676216, -1.0021247626099497e-12, -0.05127731449464091, -0.2928742138205009, -0.40818184987671735, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1653299612539053, -0.2243088539223104, -0.19703864856286932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023955960436, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05283808113905355, 0.3608647472264093, -0.541281130567749, -0.15000000000280686, -0.049142975769148396, -0.2151847073040153, 0.5504484495566567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14589011117262793, -0.17283959141676142, -0.1601092328042018]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044883261575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11031233908294522, 0.37973179156035275, 0.5783948200809502, -2.2256829060496475e-14, -0.12317768103595497, -0.28412627022324377, -0.5215454798062913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16359567911989042, -0.22661071008990966, -0.19763091885034242]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028731554044, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0468828881752113, 0.37881810371212465, -0.5083953377571927, -0.15000000000280925, -0.05955011904709216, -0.22854789099420542, 0.5224529940698626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1539766048967487, -0.18427795010648435, -0.17001446955819063]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044881278357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11910385927684494, 0.3590671297143069, 0.6577158562111252, -4.777915898499416e-14, -0.20814286555887532, -0.26726367380380267, -0.559909109735883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16172987448241521, -0.2287671737944585, -0.19810473507977652]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033507151394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.039489176492562186, 0.39434308050261524, -0.47401288993818014, -0.15000000000280894, -0.07605884905722497, -0.24014598372470913, 0.49628935708658883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1619644405443123, -0.19581803469267806, -0.17993865896138403]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880529788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1478742336529823, 0.31049953580981204, 0.6876489563802516, 6.001150630434665e-15, -0.3301746002026562, -0.23196185461007457, -0.5232727396654748, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597567129512723, -0.23080169172387394, -0.19848378806386788]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19480038282762216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.02912803671121529, 0.40700369900793454, -0.4347193541259278, -0.15000000000282587, -0.10106612406230406, -0.24950232708356584, 0.47570753856798886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16984921049433546, -0.2074546931553055, -0.1898780104834433]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487783569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2072227956269379, 0.25321237010638586, 0.785870716245046, -3.383971651076609e-13, -0.5001455001015817, -0.1871268671771344, -0.4116363703719989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15769539900046325, -0.23273316925254883, -0.19878703044118534]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415043058362855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.015160346642552938, 0.41691035843029217, -0.39128452547647374, -0.15000000000282784, -0.13178511024205766, -0.256619368591889, 0.4624542279061011, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17762727049736116, -0.2191835353580724, -0.19982949170094993]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879871994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27935380137324706, 0.19813318844715294, 0.8686965729890815, -3.967496378540561e-14, -0.6143797235950719, -0.1423408301664627, -0.26506621323775525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555612000605141, -0.23457684405533777, -0.19902962435013272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1935004783396239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0010544919765346963, 0.4244440260482049, -0.34478616097160525, -0.15000000000306368, -0.16836029912447867, -0.2623223432269921, 0.45640264438867295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18542523778181494, -0.2303918611023138, -0.20979067667094325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880092969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.32429677238175264, 0.1506733523582546, 0.92996729009737, -4.717020045662648e-12, -0.7315037776484199, -0.11405949270206249, -0.12103167034856235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15595934568907588, -0.22416651488482797, -0.19922369939986634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052609584238, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.017990172499795433, 0.43002769747145114, -0.29745313055942657, -0.15000000000306685, -0.20962045022955575, -0.2673301636176097, 0.45645726789410673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19338851010814545, -0.240470959076024, -0.2197596246463134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875630292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3387136104652147, 0.11167342846492416, 0.9466606082435739, -6.305298277255488e-14, -0.8252030221015414, -0.1001564078123521, 0.0010924701086751226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15926544652661026, -0.20158195947420426, -0.1993789595074029]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057385268532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.034633937661149736, 0.43408397522487135, -0.2509924394712505, -0.15000000000307334, -0.254628571111664, -0.2720775054129418, 0.4612372135474278, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20168110604227568, -0.2488164766271966, -0.22973478302476968]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904486314135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3328753032270861, 0.08112555506840465, 0.929213821763521, -1.2973782201901264e-13, -0.9001624176421646, -0.0949468359066419, 0.09559891306642167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16585191868260477, -0.166910351023452, -0.19950316756912542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062160885408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05038109109233241, 0.43698377827011203, -0.2062769560467902, -0.1500000000030303, -0.3026350678164349, -0.27680439306808935, 0.46963702328319196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21048551165906207, -0.25482878655505964, -0.23971490972753168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487662466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.31494306862365334, 0.05799606090481324, 0.894309668489206, 8.61057110298199e-13, -0.9601299340954177, -0.09453775310295114, 0.16799619471528346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17608811233572796, -0.12024619855726101, -0.19960253405524014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1909006693655404, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06480739276910497, 0.4390182074893643, -0.16374552838281367, -0.15000000000310118, -0.352635067796133, -0.28165835998037597, 0.48107232232329783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21985108412303236, -0.2585072145199832, -0.2496990110867917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044866273417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28852603353545125, 0.04068858438504559, 0.8506285532795304, -1.4178771870427743e-12, -0.9999999995939625, -0.0970793382457321, 0.2287059808021172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18731144927940593, -0.07356855929847182, -0.19968202718520056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071712154568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0778639865331052, 0.4403986943985648, -0.12341388476288026, -0.15000000000342525, -0.40263506778443214, -0.28661976031327846, 0.4947352979582852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22971747857223404, -0.2602663301864443, -0.2596862921686938]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879894287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2611318752800045, 0.027609738184010073, 0.8066328723986682, -6.481603995935989e-12, -0.9999999997659831, -0.09922800665805001, 0.2732595126997477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1973278889840334, -0.03518231332922182, -0.19974562163804244]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076487878388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08960632613335213, 0.4412786820272664, -0.08518470788416493, -0.15000000000342903, -0.45263506778363916, -0.29165174474811223, 0.5100567329315848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24003079304811664, -0.2604512344466754, -0.26967611703273203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044855235719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2348467920049388, 0.017599752574031128, 0.7645835375743064, -7.556952870580749e-14, -0.9999999999841401, -0.10063968869667546, 0.30642869946599255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626628951765177, -0.00369808520462251, -0.19979649728076374]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081263595057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10012538049733546, 0.4417707391744566, -0.048900642422342884, -0.15000000002090327, -0.502635058468305, -0.2967397921520137, 0.5266874660851547, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2507430585638294, -0.25934918989534483, -0.2796679768159551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044856666147, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21038108727966653, 0.009841142943803444, 0.7256813092364408, -3.494851173489374e-10, -0.9999998136933174, -0.10176094807802873, 0.33261466307139687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21424531031425448, 0.02204089102661109, -0.19983719566446229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1883008603919477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10954847526776193, 0.4419571883966162, -0.014367997310744396, -0.1500000000211803, -0.5526350580449824, -0.301882594912368, 0.5443458263067931, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26180919034589345, -0.25720781352688615, -0.2896614646336549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880057178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18846189540852917, 0.0037289844431916365, 0.6906529022319696, -5.540833742186225e-12, -0.9999999915335459, -0.10285605520708724, 0.3531672044327671, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22132263564128063, 0.04282752736917327, -0.1998697563539953]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090814794783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1179706381381946, 0.4418935075813233, 0.016964069596627884, -0.15000000002149855, -0.6011411559440306, -0.3069730171706668, 0.562211777117165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2731800344558688, -0.2542627868713367, -0.29965625483496033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879997514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684432574086534, -0.0012736163058581565, 0.6266413381474456, -6.365140340883624e-12, -0.9701219579809645, -0.10180844516597544, 0.3573190162074384, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2274168821995075, 0.05890053311098942, -0.19989580402610851]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095590393237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12525915448078667, 0.441634097401911, 0.04134555911688437, -0.15000000002160307, -0.6444033522273456, -0.311744073252931, 0.5787944038885866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28481413906839403, -0.2507023858354849, -0.3096520869762748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880308914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14577032685184171, -0.005188203588245912, 0.48762979040512955, -2.0907089903838952e-12, -0.8652439256662979, -0.09542112164528489, 0.3316525354284317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2326820922505048, 0.0712080207170367, -0.19991664282628832]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100365980284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1313513205464919, 0.44124386808255134, 0.05502647125002504, -0.1500000000215953, -0.6786716468949271, -0.3159972693498794, 0.5932267019823172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.296676588895923, -0.24667702213022927, -0.31964875268938886]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488259057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12184332131410458, -0.007804586387193758, 0.27361824266281354, 1.551690204954065e-13, -0.6853658933516314, -0.08506392193896672, 0.28864596187461183, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2372489965505798, 0.08050727410511217, -0.19993331426228184]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18570105288280192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.136339795663082, 0.44078078485635436, 0.05678283755996691, -0.15000000002383843, -0.7001960410986275, -0.31967707647770316, 0.6054562781240743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3087380042495055, -0.24230687045644275, -0.3296460832366151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999015540018491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09976950233180201, -0.009261664523939889, 0.035127326198837294, -4.4862169923335214e-11, -0.4304878840740096, -0.073596142556476, 0.24459152283514315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24122830707164972, 0.08740303347573053, -0.1999466109445247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1850511006577185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1403739775991099, 0.4402826726247442, 0.04822745343402488, -0.1500000000248627, -0.7070023962496585, -0.3227923508163898, 0.615743208675111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32097365668102484, -0.23768794898686268, -0.3396439476590971]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044501668429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08068363872055852, -0.00996224463220329, -0.17110768251884048, -2.048503143121075e-11, -0.13612710302062075, -0.06230548677373299, 0.2057386110207331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2447130486303871, 0.09237842939160111, -0.1999572884496409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18440114841725014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14361877299200565, 0.43976236018285114, 0.030859130217651836, -0.15000000007348846, -0.7014558226299935, -0.325386575019998, 0.6244399697182978, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3333623537966084, -0.23289685232547214, -0.34964223930107513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044809367193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06489590785791459, -0.010406248837861082, -0.347366464327461, -9.725154651936012e-10, 0.11093147239330017, -0.05188448407216407, 0.17393522086373578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24777394231167094, 0.09582193322781084, -0.1999658328395606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1837511961730274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14627042200302473, 0.4392113408282703, 0.006404764233721889, -0.15000000007347383, -0.6860884467169129, -0.32756334470320386, 0.6319844357652927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34588706173631506, -0.22799509062665366, -0.35964087261484745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884454658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05303298022038146, -0.011020387091616967, -0.489087319678599, 2.9241916106869966e-13, 0.30734751826161155, -0.04353539366411645, 0.1508893209398978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25049415879413317, 0.09803523397636962, -0.19997266627544694]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1831012439345092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14862707827098026, 0.43860818028500903, -0.02173736102535413, -0.15000000014852674, -0.6646502246800632, -0.3295430435189884, 0.6391345243792194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3585326942824072, -0.22303158384386015, -0.3696397804257587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904477036431, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04713312535911083, -0.012063210865225656, -0.5628425051815203, -1.5010581625509328e-09, 0.42876444073699455, -0.039593976315690504, 0.14300177227853184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25291265092184284, 0.09927013565586996, -0.19997815621822487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18245129169918597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15098847092079548, 0.4379392198459649, -0.04981810865727518, -0.15000000026691218, -0.640891128792935, -0.3315558760481963, 0.6466499899032134, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37128685024476943, -0.21804557905289973, -0.379638908852616]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044706464295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04722785299630441, -0.013379208780883091, -0.561614952638421, -2.3677085608208317e-09, 0.4751819177425639, -0.04025665058415828, 0.1503093104798807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25508311924724514, 0.09972009581920824, -0.19998256853714594]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1818013394551751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15361201681855424, 0.43720934477050205, -0.07408748067813539, -0.1500000002671049, -0.6185611590246747, -0.3337869304114391, 0.6551798549509213, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3841390359567358, -0.2130684844543532, -0.3896382065770143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880217258, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05247091795517526, -0.014597501509257033, -0.4853874404172041, -3.854006702048701e-12, 0.4465993953652055, -0.0446210872648559, 0.17059730095415865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2570437142393276, 0.09954189197093079, -0.1999859544879673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18115138721169452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15662255869767946, 0.4364369383321497, -0.0920694808987948, -0.15000000027445468, -0.6014103142061942, -0.3362952775264959, 0.6649603634477795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.397080345227432, -0.20812544943908332, -0.39963753810742575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869611545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.060210837582504284, -0.015448128767046605, -0.3596400044131882, -1.469960216966954e-10, 0.34301689636960914, -0.05016694230113629, 0.19561016993716446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2588261854139236, 0.09886070030539758, -0.19998663060822866]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1805014350126715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16008291407614098, 0.4356489459658702, -0.10314522137853752, -0.15000000032117652, -0.5931885821525483, -0.33908849694302806, 0.6760465483809904, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4101032854431277, -0.2032366709928696, -0.4096370032096144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043980460383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0692071075692303, -0.0157598473255898, -0.22151480959485437, -9.344371551251991e-10, 0.16443464107291708, -0.05586438833064317, 0.22172369866421882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2604588043139138, 0.09777556892427441, -0.19998930204377258]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1798514827691054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16401294489847063, 0.4348714362378778, -0.10753469435180923, -0.15000000032734015, -0.5975871337098351, -0.34215296203903756, 0.6883404490796959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42320155524855735, -0.19841840351592052, -0.41963654416424745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044871322005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0786006164465928, -0.015550194559849573, -0.08778945946543423, -1.2327224208445614e-10, -0.08797103114573582, -0.06128930192019008, 0.2458780139741103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26196539610859304, 0.09636534953898135, -0.1999908190926619]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920153096651503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16842268819552575, 0.43412433950386115, -0.1055752963965853, -0.15000000033161018, -0.6125025899562251, -0.34549028722149383, 0.7016691044491477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4363694132846129, -0.19368356624971556, -0.42963617662216164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999036051807536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08819486594110235, -0.014941934680332796, 0.03918795910447867, -8.540031090567923e-11, -0.2983091249278011, -0.06674650364912567, 0.2665731073890347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2633571607211105, 0.0946967453240995, -0.1999926491582839]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17855157872250568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17331802755472506, 0.4334179287139158, -0.0975812186810684, -0.15000000033179423, -0.6361821365552746, -0.34911534860963317, 0.7158289013827932, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4496018800625285, -0.18904253417637906, -0.43963580915140527]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880187185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09790678718398627, -0.014128215798906118, 0.15988155431033824, -3.6808962678137926e-12, -0.4735909319809897, -0.07250122776278717, 0.28319593867291154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2646493355583121, 0.09282064146672975, -0.19999265058487298]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1779016264791473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17869609412867896, 0.43275193474447343, -0.08392009559487104, -0.15000000034070904, -0.667125762956517, -0.3530451215191956, 0.7305939301272426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46289473446551743, -0.18450371494238038, -0.449635500706733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044867167265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10756133147907815, -0.013319879388847785, 0.27322246172394715, -1.7829622625670783e-10, -0.6188725280248493, -0.07859545819124866, 0.2953005748889871, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2658570880597793, 0.09077638467997386, -0.19999383110655497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17725167440045553, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.18453115721617097, 0.43211523433246785, -0.06524891141117733, -0.15000000034465547, -0.7038806581320318, -0.35727900048734473, 0.7456873303840093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4762442785668876, -0.18007389979051477, -0.4596351940869579]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999041573835425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11670126174984043, -0.012734008240111524, 0.37342368367387413, -7.892855084053905e-11, -0.7350979035102958, -0.08467757936298281, 0.30186800513533224, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2669908820274035, 0.08859630303731199, -0.1999938676044979]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17660172216076417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19079802755817085, 0.4314907022762652, -0.04215205093421874, -0.15000000034476055, -0.7452845739857905, -0.3618144847762589, 0.7608675803120775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48964721418125357, -0.17575857342243134, -0.46963488782734575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044793826978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12533740683999753, -0.012490641124053342, 0.4619372095391718, -2.1019064209754778e-12, -0.8280783170751729, -0.09070968577828255, 0.30360499856136425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2680587122873189, 0.08630652736166854, -0.19999387480775682]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517699244491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19745101062421855, 0.4308566390532984, -0.015492942956834833, -0.15000000034476255, -0.7900402369587985, -0.3666237761353134, 0.77586579024628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5031005933238065, -0.17156218657241754, -0.47963458157272865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044726300965, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13305966132095415, -0.012681264459336034, 0.5331821595476781, -4.0180088471313993e-14, -0.8951132594601598, -0.09618582718108987, 0.2999641986840513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26906758285105886, 0.08392773700027627, -0.19999387490765777]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181768817774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20429869235524203, 0.43018921136363203, 0.011561347760489393, -0.15000000034476443, -0.8343976472426254, -0.37152096901653797, 0.7900397479780699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5166017544224925, -0.16748836223703867, -0.4896342753243602]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044725427596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13695363462046975, -0.013348553793327129, 0.5410858143464845, -3.7792526309170664e-14, -0.8871482056765386, -0.09794385762449165, 0.28347915463579826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27002322197371964, 0.08147648670757757, -0.19999387503263136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1746518654441957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21106084470780176, 0.4294803101746147, 0.0352608928338347, -0.15000000034517985, -0.8746068060921408, -0.37619829009713696, 0.8026129679991686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5301482652130773, -0.16354005805248029, -0.4996339690953167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879640693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13524304705119453, -0.014178023780347321, 0.473990901466906, -8.30845163949667e-12, -0.8041831769903062, -0.09354642161197935, 0.2514644004219742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27093021581169674, 0.07896608369116766, -0.19999387541912966]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019132011054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21749362887568768, 0.42874615824902884, 0.05185571625630446, -0.15000000035758476, -0.9069177194520512, -0.38035397080865707, 0.8130482911599413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5437378890087027, -0.1597197019726948, -0.5096336628697844]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044861806194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12865568335771865, -0.014683038511717254, 0.33189646844939513, -2.4809823421677747e-10, -0.6462182671982093, -0.0831136142304018, 0.20870646321545439, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2717924759125063, 0.07640712159570982, -0.1999938754893533]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335196100720662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22347858144976765, 0.4280164038517146, 0.057595844541327545, -0.15000000035872857, -0.9275803879420003, -0.38380293119513265, 0.8212329860775145, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.55736854367625, -0.1560292951668711, -0.5196333570732884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043877975163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11969905148159951, -0.014595087946284972, 0.11480256570046177, -2.287588752736056e-11, -0.4132533697989808, -0.06897920772951133, 0.16369389835146378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.272613093350947, 0.07380813611647408, -0.19999388407008045]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17270200876325248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22903896123748255, 0.4273127643816033, 0.05281121453470389, -0.15000000035912384, -0.9337932462575385, -0.38651038616964434, 0.8274220686663509, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5710384625195986, -0.15247060578652985, -0.5296330516281241]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879083075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11120759575429769, -0.014072789402225436, -0.09569260013247319, -7.90507323970248e-12, -0.12425716631076489, -0.054149099490233436, 0.12378165177672848, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2733983768669711, 0.0711737876068251, -0.19999389109671545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205657711464, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23424798762539437, 0.42664004522457366, 0.03911764779982529, -0.15000000037087663, -0.9278394097171462, -0.388504668153933, 0.8319573036278338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5847456086236841, -0.1490449097966328, -0.5396327464411657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043722756851, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10418052775823633, -0.013454383140593051, -0.273871334697572, -2.3505569851564733e-10, 0.11907673080784495, -0.03988563968577311, 0.090704699229657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2741429220817115, 0.0685139197979413, -0.19999389626082975]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.171402104293002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23923205457061464, 0.4259849324500342, 0.018436482219367036, -0.15000000038710556, -0.9121962383179879, -0.38989717997876316, 0.8352322850001218, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5984882262442217, -0.14575337320288173, -0.5496324508246603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045682252472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09968133890440528, -0.013102255490789031, -0.413623311609165, -3.2457882062231604e-10, 0.3128634279831657, -0.027850236496603883, 0.06549962744575973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27485235241075223, 0.06583073187502111, -0.19999408766989268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1707521520575697, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24422583156991662, 0.42532246530660345, -0.00555031856739973, -0.15000000039537445, -0.8906137167302688, -0.39094491140178245, 0.8378212028767753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6122646120201827, -0.14259697251217773, -0.5596321903973148]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044708646441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09987553998603985, -0.013249342868614945, -0.47973601573533525, -1.6537752932253542e-10, 0.43165043175438333, -0.020954628460386107, 0.0517783575330693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27552771551922034, 0.0631280138140797, -0.19999479145309051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1701021998135605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24946920468951667, 0.42463385227151207, -0.0290929572713701, -0.1500000003954848, -0.8668418448440921, -0.391918157720855, 0.8402813655859216, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6260731200792969, -0.1395765383470203, -0.5696319299797198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880183804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10486746239200077, -0.013772260701827965, -0.4708527740794074, -2.2072549929455032e-12, 0.4754374377235345, -0.019464926381450327, 0.04920325418292578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2761701611822855, 0.06040868330314855, -0.19999479164810025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16945224757237884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.25516944595905977, 0.4239162479926318, -0.04844312282407755, -0.15000000043275608, -0.8446306110731324, -0.3930446651772077, 0.8431031605815192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6399121558868406, -0.1366927854017676, -0.5796316852796015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044823633524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11400482539086217, -0.014352085577606042, -0.387003311054149, -7.454253047135546e-10, 0.44422467541919314, -0.022530149127054505, 0.056435899911953635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27678071615087274, 0.057675058905053825, -0.19999510599763426]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1688022953287255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26148853125727184, 0.4231836791111797, -0.060789854106602766, -0.15000000043759532, -0.8277300140474624, -0.3944924301177664, 0.8466983395970097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6537801601809091, -0.13394633015859936, -0.5896314532712005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044873066662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12638170596424136, -0.01465137762904124, -0.24693462565050434, -9.678469925604596e-11, 0.3380119405133998, -0.028955298811174205, 0.07190358030980874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2773600858813717, 0.05492910486336483, -0.19999535983197894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16815234297802745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2684807220246036, 0.4224558112324561, -0.06527087640309061, -0.15000000044036302, -0.8198900525499863, -0.39630701670632307, 0.8512295378511465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6676756117913564, -0.13133771393422394, -0.5996312235102744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999047013961484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13984381534663498, -0.01455735757447166, -0.08962044592975674, -5.5353837964381035e-11, 0.15679922994952317, -0.03629173177113289, 0.09062396508273715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2779090322089457, 0.05217232448750808, -0.19999540478147848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16750239073409937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27614697321489, 0.42174948917047583, -0.06193103118282252, -0.15000000044160214, -0.8245069658850457, -0.39848145497101634, 0.8567077699898648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6815969967026524, -0.1288673997502389, -0.6096309937908481]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878561702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15332502380572785, -0.014126441239606031, 0.06679690440536179, -2.4782191290981817e-11, -0.09233826670118767, -0.043488765293864876, 0.10956464277436537, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27842769822592073, 0.049406283679700846, -0.19999540561147325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1668524384899788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2844465507766662, 0.4210712187078201, -0.051505170525520734, -0.15000000044159464, -0.8394566359819176, -0.40097652166045167, 0.8629874285847511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6955429647403144, -0.1265358978511637, -0.6196308100153683]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882411426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16599155123552348, -0.013565409253114235, 0.20851721314603572, 1.4991957751880736e-13, -0.29899340193743756, -0.04990133378870636, 0.12559317189772634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2789193607532412, 0.04663003798150395, -0.19999632449040627]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16620248624597564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2933122644070877, 0.420415030496474, -0.03515432002112065, -0.1500000004418532, -0.8626926246928943, -0.4037341684422625, 0.8698200492138377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7095119089558011, -0.1243434784644009, -0.6296306274970043]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880063123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17731427260842994, -0.0131237642269218, 0.32701701008800155, -5.170628356396471e-12, -0.4647197742195341, -0.05515293563621632, 0.13665241258173166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27937888430973296, 0.04384838773525608, -0.1999963496327175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16555253391705643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3026181788739974, 0.41976420895689087, -0.014978721143549367, -0.1500000004418538, -0.891460497569343, -0.4066365402930106, 0.8768026569294196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.723502369979279, -0.12229046517566407, -0.6396304449791188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046578384271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18611828933819452, -0.013016430791661975, 0.40351197755142554, -1.2462032528120356e-14, -0.5753574575289726, -0.05804743701496184, 0.13965215431163894, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2798092204695588, 0.04106026577473655, -0.19999634964229177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16490258171661942, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3121654776012759, 0.41910003045659716, 0.005768785606304252, -0.1500000010063125, -0.922012071867307, -0.4094790751062277, 0.8833874117322497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7375128954617187, -0.12037714548959577, -0.6496302625646709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044008740433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19094597454556977, -0.01328357000587474, 0.41495013499707234, -1.1289173866109095e-08, -0.6110314859592819, -0.05685069626434171, 0.13169509605660054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2802105096487961, 0.03826639372136595, -0.19999635171104427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16425262949838296, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3217501446312281, 0.4184137763516962, 0.023756242031074543, -0.15000000100699085, -0.9505973482429387, -0.4120344603183687, 0.889079025091563, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7515420490451525, -0.11860378060434715, -0.6596300808050813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044364729578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19169334059904425, -0.01372508209801955, 0.3597491284954058, -1.3566967215285644e-11, -0.5717055275126331, -0.051107704242819414, 0.11383226718626614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2805830716686754, 0.035467297704972534, -0.19999636480820776]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16360267725436375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3312160963493463, 0.4177101509579465, 0.036441879827668465, -0.1500000010070652, -0.9734663268738926, -0.4141099510282917, 0.8935656432049074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.765588387967712, -0.1169705968368372, -0.6696298990489231]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880384279, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1893190343623644, -0.01407250787499421, 0.2537127559318784, -1.4870587345468537e-12, -0.4573795726190772, -0.0415098141984595, 0.08973236226688744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28092677845118896, 0.032663675350198915, -0.1999963648768364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16295272503000652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34045122145829243, 0.41700320072593433, 0.04199829933138077, -0.1500000012604679, -0.98686937459093, -0.41554827645050274, 0.8966911639083539, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.779650480775944, -0.11547779865077691, -0.6796297173345924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044487144661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18470250217892253, -0.014139004640243704, 0.11112839007424605, -5.0680535637459815e-09, -0.2680609543407494, -0.028766508444221496, 0.0625104140689295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2812418561646397, 0.029855963721205997, -0.19999636571338647]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1623027728560306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34940779051471443, 0.4163070350890156, 0.03963894085804336, -0.15000000216132275, -0.9887506532601159, -0.4162627949531472, 0.8984580034112469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7937269090741327, -0.11412555641960652, -0.6896295357220649]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043479518585, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17913138112844024, -0.013923312738374397, -0.04718716946674814, -1.8017097340678524e-08, -0.03762557338371636, -0.014290370052889648, 0.03533679005785974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2815285659637734, 0.027044844623407754, -0.19999636774944918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1616528206248878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3581518793422042, 0.41562502524976, 0.03040854207971421, -0.1500000023266479, -0.9811168629168205, -0.41630805453785746, 0.8990774586984458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8078162020289991, -0.11291408594252392, -0.6996293542013194]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044622855765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17488177654979614, -0.013640196785111983, -0.18460797556658298, -3.3065028712482224e-09, 0.15267580686590637, -0.000905191694204931, 0.012389105743977936, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2817858590973277, 0.02422940954165209, -0.19999636958509107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16100286860474192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.36683814399089076, 0.41494932978245186, 0.016791047158609428, -0.15000000233139915, -0.9672604094286987, -0.4158573868782251, 0.8988949537723698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8219169783238547, -0.11184347849608633, -0.7096291726825542]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999040402917607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1737252929737304, -0.0135139093461632, -0.27234989842209567, -9.502527628821921e-11, 0.27712906976243656, 0.009013353192647712, -0.0036500985215188533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2820155258971129, 0.021412148928751623, -0.1999963696246956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16035291636084198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.37565199692650764, 0.4142681915220035, 0.0017704865311310557, -0.15000000233297325, -0.9509312760383858, -0.4151295764964091, 0.8982852091036574, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8360278130418554, -0.11091386318945841, -0.7196290871132098]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877998677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17627705871233754, -0.01362276520896731, -0.30041121254956743, -3.148181310187109e-11, 0.32658266780625916, 0.01455620763632064, -0.012194893374249496, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2822166943600131, 0.01859230613255855, -0.19999828861311156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597029641054135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38477356728157597, 0.413573864833353, -0.011751701041473297, -0.15000000233447416, -0.9358684895014033, -0.414339180377886, 0.8976053179857624, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8501472410013078, -0.11012540169420493, -0.7296290015439164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045108569954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18243140710136713, -0.013886533773010225, -0.27044375145208704, -3.001811950312277e-11, 0.3012557307396483, 0.01580792237046159, -0.013597822357900403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.282388559189048, 0.015769229905069737, -0.19999828861413183]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15905301186612078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3943368375518594, 0.4128662350367365, -0.0216176214153116, -0.15000000239470182, -0.9246739086281888, -0.41364298228573787, 0.8971290144816123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8642738498644776, -0.10947816784407297, -0.7396289159888139]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044785854006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1912654054056681, -0.014152595932330626, -0.19731840747676604, -1.2045532684839895e-09, 0.2238916174642921, 0.013923961842962605, -0.009526070083000996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2825321772633965, 0.012944677002639349, -0.1999982888979484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15840305962283643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4044110203318332, 0.41215062586806545, -0.02671711065464472, -0.1500000024040879, -0.9186368863218698, -0.4131173882028494, 0.8970071123576946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8784062257347984, -0.10897222992276581, -0.7496288304344958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044865686753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20148365559947534, -0.014312183373420013, -0.10198978478666233, -1.877212490486867e-10, 0.12074044612637919, 0.010511881657769598, -0.002438042478354072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2826475174064151, 0.010118758426143043, -0.1999982889136382]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1577531073795327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4150009398790707, 0.41143282726694963, -0.026980896743165308, -0.15000000241320874, -0.9178303362352256, -0.41276157757055115, 0.8972580567428706, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8925429552865868, -0.10860763845610524, -0.7596287448809615]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044866074807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2117983909447511, -0.014355972022315864, -0.005275721770411815, -1.8241671742023178e-10, 0.016131001732883385, 0.007116212645965018, 0.005018887703520919, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28273459103576676, 0.0072918293332112916, -0.19999828892931584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1571031552310847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42606057332026326, 0.41071544382001746, -0.023162411784850838, -0.1500000024172626, -0.9213909734385273, -0.41251651291158736, 0.897786530768351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9066826395283155, -0.10838444412318145, -0.7696286593278352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999042968959765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22119266882385127, -0.01434766893864394, 0.07636969916628941, -8.107725467604547e-11, -0.07121274406603273, 0.004901293179276219, 0.0105694805096089, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28279368483457484, 0.0044638866584759684, -0.19999828893747326]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15645320299499907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4375125887474659, 0.4099971824867863, -0.01651819588450112, -0.1500000025175087, -0.9278917672140191, -0.41228946009830386, 0.8984228252051683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9208239241721221, -0.10830259038966102, -0.7796285737965195]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044721712429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22904030854405294, -0.014365226664622758, 0.13288431800699432, -2.004921525197925e-09, -0.13001587550983743, 0.00454105626567, 0.012725888736344181, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28282569287613213, 0.001637074670408717, -0.1999982893736866]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15580325075262905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4492691490475536, 0.40927445246525385, -0.008478541292157178, -0.1500000025383453, -0.9357159754064021, -0.411976559107681, 0.8989690144961375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9349653347446999, -0.10836216460543051, -0.7896284882699679]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044847400273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23513120600175405, -0.014454600430649008, 0.16079309184687887, -4.1673232323514666e-10, -0.15648416384765856, 0.006258019812457218, 0.010923785819384938, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28282821145155623, -0.001191484315389929, -0.19999828946896772]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1551532985148693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46076131544665866, 0.40901940151850263, -0.0006917309894316666, -0.1500000026006494, -0.9424039884510108, -0.4128829364921251, 0.8984783134747968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9490961824832114, -0.10857105562200238, -0.7995380570906596]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044755194974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22984332798210136, -0.005101018935023901, 0.15573620605451022, -1.2460820955087846e-09, -0.13376026089217463, -0.01812754768888189, -0.009814020426814092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2826169547702303, -0.004177820331437487, -0.19819137641383358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555145238280864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47096715224414104, 0.4106079014453873, 0.005696702386158525, -0.15177230053417393, -0.947791859057749, -0.414470402709686, 0.8979476120693357, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9623315073122183, -0.10889833642320842, -0.8087322802605562]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007224506264341943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20411673594964805, 0.031769998537693356, 0.12776866751180382, -0.035445958670490066, -0.1077574121347639, -0.03174932435121752, -0.010614028109221452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647064965801379, -0.006545616024120793, -0.18388446339793205]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559622285363817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47935611938647094, 0.4135600558680854, 0.01039157724486683, -0.15507830959517818, -0.9521240364140472, -0.4161240576463237, 0.897959088412057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9737875128557731, -0.10928345774917339, -0.8165861577807516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00895409416590626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1677793428465979, 0.059043088453962486, 0.09389749717416611, -0.06612018122008523, -0.0866435471259647, -0.0330730987327541, 0.00022952685442462033, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22912011087109677, -0.007702426519299421, -0.15707755040390856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15626972429192462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48583971617289884, 0.4170186538535224, 0.013574255442026166, -0.15907263807012129, -0.9556288292022793, -0.41753373643148595, 0.89858277425084, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9825816991430995, -0.10964764272810736, -0.8225806362586835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006149915110858642, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12967193572855762, 0.06917195970873892, 0.06365356394318669, -0.0798865694988621, -0.07009585576464157, -0.02819357570324453, 0.012473716775659595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17588372574652622, -0.00728369957867929, -0.11988956955863715]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15646031271119484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49062116893678387, 0.42033676314481344, 0.015578696220181416, -0.16303111141273574, -0.9584747093524285, -0.41861206895941794, 0.8996635203797246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9883718736968895, -0.10969375634680667, -0.8269125185940361]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000" + }, + "execution_count": 9, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "reset_giskard()\n", + "\n", + "# Define a goal pose in the map coordinate system\n", + "goal_pose = PoseStamped()\n", + "goal_pose.header.frame_id = 'map'\n", + "goal_pose.pose.orientation = Quaternion(*quaternion_from_matrix([[1, 0, 0, 0],\n", + " [0, 1, 0, 0],\n", + " [0, 0, 1, 0],\n", + " [0, 0, 0, 1]]))\n", + "goal_pose.pose.position.x = 2.01\n", + "goal_pose.pose.position.y = -0.2\n", + "goal_pose.pose.position.z = 0.7\n", + "# specify the cartesian pose goal to move 'l_gripper_tool_frame' towards goal_pose by using the kinematic chain between 'l_gripper_tool_frame' and 'map'\n", + "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", + "# specify monitor that is active when it is below the given thresholds and use it to end the motion\n", + "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01, orientation_threshold=0.01)\n", + "gs.monitors.add_end_motion(pose_monitor)\n", + "# in the case that there is nos specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum\n", + "# gs.add_default_end_motion_conditions()\n", + "gs.execute()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "When adding an object to the world of giskard one can specify goal poses also in its coordinate frame. This is true for all links that are part of giskards world representation." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 10, + "outputs": [ + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995224128082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.003749999998426497, 0.0037500000000161406, -0.0037499999999998975, -0.14999999999982933, 0.0009726135623061073, -0.10000999999993533, 0.003749999999999878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529551367, -0.0006253905029042516, -0.0006250000000005031]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825616084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999996852993, 0.07500000000009105, -0.07499999999999783, 3.413413898528338e-12, 0.019452271246122144, 1.2934985057206626e-12, 0.07499999999999801, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059102733, -0.012507810058085031, -0.012500000000000719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999044865274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.010874000462810094, 0.014999999121785897, -0.014999999999929904, -0.15000000000052507, 0.00249685109396703, -0.10001000000022002, 0.014999999999935657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.002494915898464792, -0.0025050721386444116, -0.002499999999906253]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044904931787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1424800092876719, 0.2249999824353951, -0.22499999999860015, -1.3914817577019912e-11, 0.030484750633218455, -5.693777305049226e-12, 0.22499999999871556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0374061329101931, -0.0375936327148032, -0.0374999999999795]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985673060278, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.019214385627334598, 0.03214772656204189, -0.03562499999935418, -0.15000000000054162, 0.004003912303603865, -0.10001000000023216, 0.03562499999940766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005911945269440533, -0.005962921582434169, -0.005937499999840859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881507441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1668077032904901, 0.3429545488051197, -0.4124999999884855, -3.3086328286054907e-13, 0.030141224192736706, -2.427690312094603e-13, 0.4124999999894401, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06834058741951482, -0.06915698887579515, -0.06874999999869214]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2025998089745868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.027332611693070694, 0.05225635205961038, -0.06406249999670444, -0.15000000000063227, 0.00509351329647851, -0.1000100000002995, 0.06406249999708183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010600654477185504, -0.010752838725563377, -0.010677083330842652]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487968028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.16236452131472193, 0.40217250995136977, -0.5687499999470049, -1.8132440942715141e-12, 0.021792019857492892, -1.3466319672723584e-12, 0.5687499999534835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09377418415489941, -0.09579834286258415, -0.09479166662003588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2032497612186043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.03465601580721158, 0.07338202302242261, -0.09881249999420641, -0.15000000000064317, 0.005562151157030444, -0.10001000000030755, 0.09881249999494346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016296158549235513, -0.016639097200595834, -0.016468749995204174]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880350157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1464680822828177, 0.4225134192562447, -0.6949999999500392, -2.1797790610805456e-13, 0.009372757211038677, -1.6105727900585533e-13, 0.6949999999572325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11391008144100016, -0.11772516950064911, -0.1158333332872304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134620561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04107639227844112, 0.09452901507328197, -0.13861249997290648, -0.15000000000198216, 0.005347532109568132, -0.10001000000140058, 0.13861249995264174, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022774491634322096, -0.023423890671478025, -0.023102083324553664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869035943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.12840752942459085, 0.42293984101718723, -0.7959999995740012, -2.677979323697273e-11, -0.004292380949246234, -2.1860605853446573e-11, 0.7959999991539658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12956666170173162, -0.1356958694176438, -0.1326666665869898]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966570582583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04666118591631699, 0.11525153479943673, -0.18245249994872562, -0.15000000000228894, 0.004470968152595306, -0.10001000000169422, 0.18245249991166518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029855627973834894, -0.030949331744835305, -0.030408749986253168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044875394872, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.11169587275751738, 0.4144503945230952, -0.8767999995163827, -6.1357932112318646e-12, -0.01753127913945652, -5.8727073376287276e-12, 0.8767999991804688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14162272679025595, -0.1505088214671456, -0.1461333332339901]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961794978372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05152178527779883, 0.1353647889149822, -0.22952449992876367, -0.15000000000234268, 0.0029953253590808606, -0.10001000000174005, 0.2295244998783314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03739517881513101, -0.03908896828573813, -0.0382540833152034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879157857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09721198722963685, 0.402265082310909, -0.9414399996007609, -1.0748467169952566e-12, -0.029512855870288908, -9.167461066347978e-13, 0.9414399993333245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15079101682592239, -0.16279273081805654, -0.15690666657900465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966648689288, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05576265608289525, 0.15399602312200017, -0.2791820999128309, -0.1500000000017874, 0.0010285471017613223, -0.10001000000065693, 0.2791820998517253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04527752908108162, -0.047741235841549406, -0.04653034997789501]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999029257817154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08481741610192829, 0.3726246841403596, -0.9931519996813443, 1.1105360308673324e-11, -0.039335565146390764, 2.166230133870735e-11, 0.993151999467878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15764700531901213, -0.17304535111622546, -0.16552533325383217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20389971424308817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05942678249747326, 0.17116549308609977, -0.32918212496676713, -0.15000000000206704, -0.001336658350849851, -0.10001000000106844, 0.3291820998507171, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05341021492784108, -0.05682436098581435, -0.055151363307386986]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044876094263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07328252829156022, 0.3433893992819922, -1.0000005010787243, -5.592900813623596e-12, -0.04730410905222346, -8.230135473705073e-12, 0.9999999999798355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16265371693518918, -0.1816625028852989, -0.1724202665898396]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976199901068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06254927332067894, 0.18720822280178823, -0.3791821500200128, -0.15000000000220307, -0.0040210550792610135, -0.10001000000208868, 0.3791820998487869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.061719348735855044, -0.06627236474911988, -0.06404817396991841]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488154993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.062449816464113767, 0.32085459431376934, -1.000000501064914, -2.720657585222056e-12, -0.053687934568223246, -2.0404835988778344e-11, 0.9999999999613957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16618267616027926, -0.18896007526611042, -0.17793621325062856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980975502256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06530334246783995, 0.20274448077030074, -0.42918217507376827, -0.150000000002362, -0.006981139353238399, -0.10169702523622634, 0.42918209984579514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07014591555267684, -0.07603190914626919, -0.07316562249855446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879762176, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05508138294321995, 0.31072515937025036, -1.0000005010751092, -3.178670627095961e-12, -0.059201685479547704, -0.03374050468275326, 0.9999999999401649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16853133633643577, -0.1951908879429861, -0.18234897057272118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985751100356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06790328523509014, 0.21824311964802745, -0.47918220012370066, -0.1500000000023791, -0.010200549301847222, -0.10666265915696402, 0.479182099845268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07864278700313587, -0.0860597960924229, -0.0824595813214565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880380298, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05199885534500379, 0.30997277755453384, -1.0000005009986477, -3.419628306111715e-13, -0.06438819897217644, -0.09931267841475351, 0.9999999999894567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1699374290091808, -0.20055773892307413, -0.18587917645804092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999052667752, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0698257236356248, 0.23421513254549522, -0.525432225169826, -0.1500000000023803, -0.017429254760860668, -0.1153266305046296, 0.5257753718839405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08717232125632797, -0.09632097536722978, -0.09189474837977776]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884567195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.038448768010693184, 0.31944025794935554, -0.9250005009225063, -2.4558949901505577e-14, -0.14457410918026892, -0.17327942695331155, 0.9318654407734511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17059068506384195, -0.20522358549613762, -0.18870334116642523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995302277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07072955470746402, 0.2508652922059786, -0.5641822502121976, -0.1500000000023839, -0.024917259070361825, -0.12713418211536878, 0.5652119159618963, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09570443891067591, -0.10678695264977467, -0.10144288202640352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880103793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018076621436784384, 0.3330031932096672, -0.7750005008474314, -7.163789731263766e-14, -0.1497600861900231, -0.23615103221478356, 0.7887308815591166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17064235308695888, -0.20931954565089778, -0.19096267293251507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000000007787679, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07051671251909349, 0.268156085445879, -0.5916822752530768, -0.15000000000252947, -0.030483560079777795, -0.1410550519159715, 0.5937417320800253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10421508353998447, -0.11743451382759128, -0.11108138894132084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880041834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004256843767410735, 0.3458158647980082, -0.5500005008175851, -2.9113963874629762e-12, -0.11132602018831939, -0.2784173960120548, 0.5705963223625797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17021289258617123, -0.21295122355633223, -0.19277013829834663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935004853499577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06914440590006907, 0.2860034411792493, -0.6041823002928683, -0.1500000000025775, -0.034551304873879134, -0.15604040622717463, 0.6076148202386424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11268499205073444, -0.12824470059199697, -0.12079219447249467]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875442563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027446132380488278, 0.3569471146674063, -0.2500005007958297, -9.603601719665634e-13, -0.08135489588202678, -0.2997070862240625, 0.2774617631723428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16939817021499945, -0.21620373528811399, -0.1942161106234766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009629126512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06662506364786523, 0.3043069196152068, -0.6033489878269833, -0.15000000000261468, -0.0377013785949796, -0.17129104770331385, 0.6079257270381646, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12109871381632487, -0.1392019864674616, -0.1305608388964588]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044874612967, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0503868450440767, 0.3660695687191493, 0.016666249317699444, -7.435904150903004e-13, -0.0630014744220093, -0.3050128295227844, 0.006218135990444407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1682744353118084, -0.21914571750929274, -0.19537288847928289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980501440472577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06301180850687928, 0.3229607227779738, -0.5914045607766345, -0.15000000000275565, -0.0404202259926186, -0.18633468310182805, 0.5969348160408071, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12944382915393812, -0.15029361321615042, -0.14037575443354122]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880148077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07226510281971905, 0.37307606325533976, 0.23888854100697743, -2.8192075957799583e-12, -0.05437694795278004, -0.300872707970284, -0.21981821994715087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16690230675226528, -0.22183253497377647, -0.19629831074164802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019180376744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05835369809320081, 0.3418781576483917, -0.5702008715717964, -0.15000000000280575, -0.042984091717350646, -0.2009783937928531, 0.5765257235469713, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1377103272166334, -0.16150905591226594, -0.1502276868616847]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869805191, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0931622082735693, 0.37834869740835814, 0.42407378409676216, -1.0021247626099497e-12, -0.05127731449464091, -0.2928742138205009, -0.40818184987671735, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1653299612539053, -0.2243088539223104, -0.19703864856286932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023955960436, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05283808113905355, 0.3608647472264093, -0.541281130567749, -0.15000000000280686, -0.049142975769148396, -0.2151847073040153, 0.5504484495566567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14589011117262793, -0.17283959141676142, -0.1601092328042018]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044883261575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11031233908294522, 0.37973179156035275, 0.5783948200809502, -2.2256829060496475e-14, -0.12317768103595497, -0.28412627022324377, -0.5215454798062913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16359567911989042, -0.22661071008990966, -0.19763091885034242]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028731554044, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0468828881752113, 0.37881810371212465, -0.5083953377571927, -0.15000000000280925, -0.05955011904709216, -0.22854789099420542, 0.5224529940698626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1539766048967487, -0.18427795010648435, -0.17001446955819063]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044881278357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11910385927684494, 0.3590671297143069, 0.6577158562111252, -4.777915898499416e-14, -0.20814286555887532, -0.26726367380380267, -0.559909109735883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16172987448241521, -0.2287671737944585, -0.19810473507977652]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033507151394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.039489176492562186, 0.39434308050261524, -0.47401288993818014, -0.15000000000280894, -0.07605884905722497, -0.24014598372470913, 0.49628935708658883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1619644405443123, -0.19581803469267806, -0.17993865896138403]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880529788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1478742336529823, 0.31049953580981204, 0.6876489563802516, 6.001150630434665e-15, -0.3301746002026562, -0.23196185461007457, -0.5232727396654748, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597567129512723, -0.23080169172387394, -0.19848378806386788]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19480038282762216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.02912803671121529, 0.40700369900793454, -0.4347193541259278, -0.15000000000282587, -0.10106612406230406, -0.24950232708356584, 0.47570753856798886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16984921049433546, -0.2074546931553055, -0.1898780104834433]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487783569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2072227956269379, 0.25321237010638586, 0.785870716245046, -3.383971651076609e-13, -0.5001455001015817, -0.1871268671771344, -0.4116363703719989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15769539900046325, -0.23273316925254883, -0.19878703044118534]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415043058362855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.015160346642552938, 0.41691035843029217, -0.39128452547647374, -0.15000000000282784, -0.13178511024205766, -0.256619368591889, 0.4624542279061011, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17762727049736116, -0.2191835353580724, -0.19982949170094993]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879871994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27935380137324706, 0.19813318844715294, 0.8686965729890815, -3.967496378540561e-14, -0.6143797235950719, -0.1423408301664627, -0.26506621323775525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555612000605141, -0.23457684405533777, -0.19902962435013272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1935004783396239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0010544919765346963, 0.4244440260482049, -0.34478616097160525, -0.15000000000306368, -0.16836029912447867, -0.2623223432269921, 0.45640264438867295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18542523778181494, -0.2303918611023138, -0.20979067667094325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880092969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.32429677238175264, 0.1506733523582546, 0.92996729009737, -4.717020045662648e-12, -0.7315037776484199, -0.11405949270206249, -0.12103167034856235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15595934568907588, -0.22416651488482797, -0.19922369939986634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052609584238, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.017990172499795433, 0.43002769747145114, -0.29745313055942657, -0.15000000000306685, -0.20962045022955575, -0.2673301636176097, 0.45645726789410673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19338851010814545, -0.240470959076024, -0.2197596246463134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875630292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3387136104652147, 0.11167342846492416, 0.9466606082435739, -6.305298277255488e-14, -0.8252030221015414, -0.1001564078123521, 0.0010924701086751226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15926544652661026, -0.20158195947420426, -0.1993789595074029]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057385268532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.034633937661149736, 0.43408397522487135, -0.2509924394712505, -0.15000000000307334, -0.254628571111664, -0.2720775054129418, 0.4612372135474278, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20168110604227568, -0.2488164766271966, -0.22973478302476968]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904486314135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3328753032270861, 0.08112555506840465, 0.929213821763521, -1.2973782201901264e-13, -0.9001624176421646, -0.0949468359066419, 0.09559891306642167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16585191868260477, -0.166910351023452, -0.19950316756912542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062160885408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05038109109233241, 0.43698377827011203, -0.2062769560467902, -0.1500000000030303, -0.3026350678164349, -0.27680439306808935, 0.46963702328319196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21048551165906207, -0.25482878655505964, -0.23971490972753168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487662466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.31494306862365334, 0.05799606090481324, 0.894309668489206, 8.61057110298199e-13, -0.9601299340954177, -0.09453775310295114, 0.16799619471528346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17608811233572796, -0.12024619855726101, -0.19960253405524014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1909006693655404, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06480739276910497, 0.4390182074893643, -0.16374552838281367, -0.15000000000310118, -0.352635067796133, -0.28165835998037597, 0.48107232232329783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21985108412303236, -0.2585072145199832, -0.2496990110867917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044866273417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28852603353545125, 0.04068858438504559, 0.8506285532795304, -1.4178771870427743e-12, -0.9999999995939625, -0.0970793382457321, 0.2287059808021172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18731144927940593, -0.07356855929847182, -0.19968202718520056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071712154568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0778639865331052, 0.4403986943985648, -0.12341388476288026, -0.15000000000342525, -0.40263506778443214, -0.28661976031327846, 0.4947352979582852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22971747857223404, -0.2602663301864443, -0.2596862921686938]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879894287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2611318752800045, 0.027609738184010073, 0.8066328723986682, -6.481603995935989e-12, -0.9999999997659831, -0.09922800665805001, 0.2732595126997477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1973278889840334, -0.03518231332922182, -0.19974562163804244]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076487878388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08960632613335213, 0.4412786820272664, -0.08518470788416493, -0.15000000000342903, -0.45263506778363916, -0.29165174474811223, 0.5100567329315848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24003079304811664, -0.2604512344466754, -0.26967611703273203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044855235719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2348467920049388, 0.017599752574031128, 0.7645835375743064, -7.556952870580749e-14, -0.9999999999841401, -0.10063968869667546, 0.30642869946599255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626628951765177, -0.00369808520462251, -0.19979649728076374]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081263595057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10012538049733546, 0.4417707391744566, -0.048900642422342884, -0.15000000002090327, -0.502635058468305, -0.2967397921520137, 0.5266874660851547, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2507430585638294, -0.25934918989534483, -0.2796679768159551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044856666147, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21038108727966653, 0.009841142943803444, 0.7256813092364408, -3.494851173489374e-10, -0.9999998136933174, -0.10176094807802873, 0.33261466307139687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21424531031425448, 0.02204089102661109, -0.19983719566446229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1883008603919477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10954847526776193, 0.4419571883966162, -0.014367997310744396, -0.1500000000211803, -0.5526350580449824, -0.301882594912368, 0.5443458263067931, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26180919034589345, -0.25720781352688615, -0.2896614646336549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880057178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18846189540852917, 0.0037289844431916365, 0.6906529022319696, -5.540833742186225e-12, -0.9999999915335459, -0.10285605520708724, 0.3531672044327671, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22132263564128063, 0.04282752736917327, -0.1998697563539953]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090814794783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1179706381381946, 0.4418935075813233, 0.016964069596627884, -0.15000000002149855, -0.6011411559440306, -0.3069730171706668, 0.562211777117165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2731800344558688, -0.2542627868713367, -0.29965625483496033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879997514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684432574086534, -0.0012736163058581565, 0.6266413381474456, -6.365140340883624e-12, -0.9701219579809645, -0.10180844516597544, 0.3573190162074384, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2274168821995075, 0.05890053311098942, -0.19989580402610851]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095590393237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12525915448078667, 0.441634097401911, 0.04134555911688437, -0.15000000002160307, -0.6444033522273456, -0.311744073252931, 0.5787944038885866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28481413906839403, -0.2507023858354849, -0.3096520869762748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880308914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14577032685184171, -0.005188203588245912, 0.48762979040512955, -2.0907089903838952e-12, -0.8652439256662979, -0.09542112164528489, 0.3316525354284317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2326820922505048, 0.0712080207170367, -0.19991664282628832]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100365980284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1313513205464919, 0.44124386808255134, 0.05502647125002504, -0.1500000000215953, -0.6786716468949271, -0.3159972693498794, 0.5932267019823172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.296676588895923, -0.24667702213022927, -0.31964875268938886]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488259057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12184332131410458, -0.007804586387193758, 0.27361824266281354, 1.551690204954065e-13, -0.6853658933516314, -0.08506392193896672, 0.28864596187461183, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2372489965505798, 0.08050727410511217, -0.19993331426228184]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18570105288280192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.136339795663082, 0.44078078485635436, 0.05678283755996691, -0.15000000002383843, -0.7001960410986275, -0.31967707647770316, 0.6054562781240743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3087380042495055, -0.24230687045644275, -0.3296460832366151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999015540018491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09976950233180201, -0.009261664523939889, 0.035127326198837294, -4.4862169923335214e-11, -0.4304878840740096, -0.073596142556476, 0.24459152283514315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24122830707164972, 0.08740303347573053, -0.1999466109445247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1850511006577185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1403739775991099, 0.4402826726247442, 0.04822745343402488, -0.1500000000248627, -0.7070023962496585, -0.3227923508163898, 0.615743208675111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32097365668102484, -0.23768794898686268, -0.3396439476590971]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044501668429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08068363872055852, -0.00996224463220329, -0.17110768251884048, -2.048503143121075e-11, -0.13612710302062075, -0.06230548677373299, 0.2057386110207331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2447130486303871, 0.09237842939160111, -0.1999572884496409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18440114841725014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14361877299200565, 0.43976236018285114, 0.030859130217651836, -0.15000000007348846, -0.7014558226299935, -0.325386575019998, 0.6244399697182978, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3333623537966084, -0.23289685232547214, -0.34964223930107513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044809367193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06489590785791459, -0.010406248837861082, -0.347366464327461, -9.725154651936012e-10, 0.11093147239330017, -0.05188448407216407, 0.17393522086373578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24777394231167094, 0.09582193322781084, -0.1999658328395606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1837511961730274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14627042200302473, 0.4392113408282703, 0.006404764233721889, -0.15000000007347383, -0.6860884467169129, -0.32756334470320386, 0.6319844357652927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34588706173631506, -0.22799509062665366, -0.35964087261484745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884454658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05303298022038146, -0.011020387091616967, -0.489087319678599, 2.9241916106869966e-13, 0.30734751826161155, -0.04353539366411645, 0.1508893209398978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25049415879413317, 0.09803523397636962, -0.19997266627544694]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1831012439345092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14862707827098026, 0.43860818028500903, -0.02173736102535413, -0.15000000014852674, -0.6646502246800632, -0.3295430435189884, 0.6391345243792194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3585326942824072, -0.22303158384386015, -0.3696397804257587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904477036431, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04713312535911083, -0.012063210865225656, -0.5628425051815203, -1.5010581625509328e-09, 0.42876444073699455, -0.039593976315690504, 0.14300177227853184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25291265092184284, 0.09927013565586996, -0.19997815621822487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18245129169918597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15098847092079548, 0.4379392198459649, -0.04981810865727518, -0.15000000026691218, -0.640891128792935, -0.3315558760481963, 0.6466499899032134, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37128685024476943, -0.21804557905289973, -0.379638908852616]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044706464295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04722785299630441, -0.013379208780883091, -0.561614952638421, -2.3677085608208317e-09, 0.4751819177425639, -0.04025665058415828, 0.1503093104798807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25508311924724514, 0.09972009581920824, -0.19998256853714594]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1818013394551751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15361201681855424, 0.43720934477050205, -0.07408748067813539, -0.1500000002671049, -0.6185611590246747, -0.3337869304114391, 0.6551798549509213, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3841390359567358, -0.2130684844543532, -0.3896382065770143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880217258, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05247091795517526, -0.014597501509257033, -0.4853874404172041, -3.854006702048701e-12, 0.4465993953652055, -0.0446210872648559, 0.17059730095415865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2570437142393276, 0.09954189197093079, -0.1999859544879673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18115138721169452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15662255869767946, 0.4364369383321497, -0.0920694808987948, -0.15000000027445468, -0.6014103142061942, -0.3362952775264959, 0.6649603634477795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.397080345227432, -0.20812544943908332, -0.39963753810742575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869611545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.060210837582504284, -0.015448128767046605, -0.3596400044131882, -1.469960216966954e-10, 0.34301689636960914, -0.05016694230113629, 0.19561016993716446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2588261854139236, 0.09886070030539758, -0.19998663060822866]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1805014350126715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16008291407614098, 0.4356489459658702, -0.10314522137853752, -0.15000000032117652, -0.5931885821525483, -0.33908849694302806, 0.6760465483809904, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4101032854431277, -0.2032366709928696, -0.4096370032096144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043980460383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0692071075692303, -0.0157598473255898, -0.22151480959485437, -9.344371551251991e-10, 0.16443464107291708, -0.05586438833064317, 0.22172369866421882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2604588043139138, 0.09777556892427441, -0.19998930204377258]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1798514827691054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16401294489847063, 0.4348714362378778, -0.10753469435180923, -0.15000000032734015, -0.5975871337098351, -0.34215296203903756, 0.6883404490796959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42320155524855735, -0.19841840351592052, -0.41963654416424745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044871322005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0786006164465928, -0.015550194559849573, -0.08778945946543423, -1.2327224208445614e-10, -0.08797103114573582, -0.06128930192019008, 0.2458780139741103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26196539610859304, 0.09636534953898135, -0.1999908190926619]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920153096651503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16842268819552575, 0.43412433950386115, -0.1055752963965853, -0.15000000033161018, -0.6125025899562251, -0.34549028722149383, 0.7016691044491477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4363694132846129, -0.19368356624971556, -0.42963617662216164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999036051807536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08819486594110235, -0.014941934680332796, 0.03918795910447867, -8.540031090567923e-11, -0.2983091249278011, -0.06674650364912567, 0.2665731073890347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2633571607211105, 0.0946967453240995, -0.1999926491582839]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17855157872250568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17331802755472506, 0.4334179287139158, -0.0975812186810684, -0.15000000033179423, -0.6361821365552746, -0.34911534860963317, 0.7158289013827932, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4496018800625285, -0.18904253417637906, -0.43963580915140527]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880187185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09790678718398627, -0.014128215798906118, 0.15988155431033824, -3.6808962678137926e-12, -0.4735909319809897, -0.07250122776278717, 0.28319593867291154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2646493355583121, 0.09282064146672975, -0.19999265058487298]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1779016264791473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17869609412867896, 0.43275193474447343, -0.08392009559487104, -0.15000000034070904, -0.667125762956517, -0.3530451215191956, 0.7305939301272426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46289473446551743, -0.18450371494238038, -0.449635500706733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044867167265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10756133147907815, -0.013319879388847785, 0.27322246172394715, -1.7829622625670783e-10, -0.6188725280248493, -0.07859545819124866, 0.2953005748889871, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2658570880597793, 0.09077638467997386, -0.19999383110655497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17725167440045553, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.18453115721617097, 0.43211523433246785, -0.06524891141117733, -0.15000000034465547, -0.7038806581320318, -0.35727900048734473, 0.7456873303840093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4762442785668876, -0.18007389979051477, -0.4596351940869579]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999041573835425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11670126174984043, -0.012734008240111524, 0.37342368367387413, -7.892855084053905e-11, -0.7350979035102958, -0.08467757936298281, 0.30186800513533224, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2669908820274035, 0.08859630303731199, -0.1999938676044979]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17660172216076417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19079802755817085, 0.4314907022762652, -0.04215205093421874, -0.15000000034476055, -0.7452845739857905, -0.3618144847762589, 0.7608675803120775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48964721418125357, -0.17575857342243134, -0.46963488782734575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044793826978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12533740683999753, -0.012490641124053342, 0.4619372095391718, -2.1019064209754778e-12, -0.8280783170751729, -0.09070968577828255, 0.30360499856136425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2680587122873189, 0.08630652736166854, -0.19999387480775682]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517699244491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19745101062421855, 0.4308566390532984, -0.015492942956834833, -0.15000000034476255, -0.7900402369587985, -0.3666237761353134, 0.77586579024628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5031005933238065, -0.17156218657241754, -0.47963458157272865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044726300965, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13305966132095415, -0.012681264459336034, 0.5331821595476781, -4.0180088471313993e-14, -0.8951132594601598, -0.09618582718108987, 0.2999641986840513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26906758285105886, 0.08392773700027627, -0.19999387490765777]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181768817774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20429869235524203, 0.43018921136363203, 0.011561347760489393, -0.15000000034476443, -0.8343976472426254, -0.37152096901653797, 0.7900397479780699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5166017544224925, -0.16748836223703867, -0.4896342753243602]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044725427596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13695363462046975, -0.013348553793327129, 0.5410858143464845, -3.7792526309170664e-14, -0.8871482056765386, -0.09794385762449165, 0.28347915463579826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27002322197371964, 0.08147648670757757, -0.19999387503263136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1746518654441957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21106084470780176, 0.4294803101746147, 0.0352608928338347, -0.15000000034517985, -0.8746068060921408, -0.37619829009713696, 0.8026129679991686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5301482652130773, -0.16354005805248029, -0.4996339690953167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879640693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13524304705119453, -0.014178023780347321, 0.473990901466906, -8.30845163949667e-12, -0.8041831769903062, -0.09354642161197935, 0.2514644004219742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27093021581169674, 0.07896608369116766, -0.19999387541912966]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019132011054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21749362887568768, 0.42874615824902884, 0.05185571625630446, -0.15000000035758476, -0.9069177194520512, -0.38035397080865707, 0.8130482911599413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5437378890087027, -0.1597197019726948, -0.5096336628697844]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044861806194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12865568335771865, -0.014683038511717254, 0.33189646844939513, -2.4809823421677747e-10, -0.6462182671982093, -0.0831136142304018, 0.20870646321545439, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2717924759125063, 0.07640712159570982, -0.1999938754893533]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335196100720662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22347858144976765, 0.4280164038517146, 0.057595844541327545, -0.15000000035872857, -0.9275803879420003, -0.38380293119513265, 0.8212329860775145, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.55736854367625, -0.1560292951668711, -0.5196333570732884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043877975163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11969905148159951, -0.014595087946284972, 0.11480256570046177, -2.287588752736056e-11, -0.4132533697989808, -0.06897920772951133, 0.16369389835146378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.272613093350947, 0.07380813611647408, -0.19999388407008045]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17270200876325248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22903896123748255, 0.4273127643816033, 0.05281121453470389, -0.15000000035912384, -0.9337932462575385, -0.38651038616964434, 0.8274220686663509, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5710384625195986, -0.15247060578652985, -0.5296330516281241]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879083075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11120759575429769, -0.014072789402225436, -0.09569260013247319, -7.90507323970248e-12, -0.12425716631076489, -0.054149099490233436, 0.12378165177672848, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2733983768669711, 0.0711737876068251, -0.19999389109671545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205657711464, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23424798762539437, 0.42664004522457366, 0.03911764779982529, -0.15000000037087663, -0.9278394097171462, -0.388504668153933, 0.8319573036278338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5847456086236841, -0.1490449097966328, -0.5396327464411657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043722756851, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10418052775823633, -0.013454383140593051, -0.273871334697572, -2.3505569851564733e-10, 0.11907673080784495, -0.03988563968577311, 0.090704699229657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2741429220817115, 0.0685139197979413, -0.19999389626082975]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.171402104293002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23923205457061464, 0.4259849324500342, 0.018436482219367036, -0.15000000038710556, -0.9121962383179879, -0.38989717997876316, 0.8352322850001218, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5984882262442217, -0.14575337320288173, -0.5496324508246603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045682252472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09968133890440528, -0.013102255490789031, -0.413623311609165, -3.2457882062231604e-10, 0.3128634279831657, -0.027850236496603883, 0.06549962744575973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27485235241075223, 0.06583073187502111, -0.19999408766989268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1707521520575697, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24422583156991662, 0.42532246530660345, -0.00555031856739973, -0.15000000039537445, -0.8906137167302688, -0.39094491140178245, 0.8378212028767753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6122646120201827, -0.14259697251217773, -0.5596321903973148]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044708646441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09987553998603985, -0.013249342868614945, -0.47973601573533525, -1.6537752932253542e-10, 0.43165043175438333, -0.020954628460386107, 0.0517783575330693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27552771551922034, 0.0631280138140797, -0.19999479145309051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1701021998135605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24946920468951667, 0.42463385227151207, -0.0290929572713701, -0.1500000003954848, -0.8668418448440921, -0.391918157720855, 0.8402813655859216, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6260731200792969, -0.1395765383470203, -0.5696319299797198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880183804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10486746239200077, -0.013772260701827965, -0.4708527740794074, -2.2072549929455032e-12, 0.4754374377235345, -0.019464926381450327, 0.04920325418292578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2761701611822855, 0.06040868330314855, -0.19999479164810025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16945224757237884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.25516944595905977, 0.4239162479926318, -0.04844312282407755, -0.15000000043275608, -0.8446306110731324, -0.3930446651772077, 0.8431031605815192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6399121558868406, -0.1366927854017676, -0.5796316852796015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044823633524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11400482539086217, -0.014352085577606042, -0.387003311054149, -7.454253047135546e-10, 0.44422467541919314, -0.022530149127054505, 0.056435899911953635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27678071615087274, 0.057675058905053825, -0.19999510599763426]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1688022953287255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26148853125727184, 0.4231836791111797, -0.060789854106602766, -0.15000000043759532, -0.8277300140474624, -0.3944924301177664, 0.8466983395970097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6537801601809091, -0.13394633015859936, -0.5896314532712005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044873066662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12638170596424136, -0.01465137762904124, -0.24693462565050434, -9.678469925604596e-11, 0.3380119405133998, -0.028955298811174205, 0.07190358030980874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2773600858813717, 0.05492910486336483, -0.19999535983197894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16815234297802745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2684807220246036, 0.4224558112324561, -0.06527087640309061, -0.15000000044036302, -0.8198900525499863, -0.39630701670632307, 0.8512295378511465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6676756117913564, -0.13133771393422394, -0.5996312235102744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999047013961484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13984381534663498, -0.01455735757447166, -0.08962044592975674, -5.5353837964381035e-11, 0.15679922994952317, -0.03629173177113289, 0.09062396508273715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2779090322089457, 0.05217232448750808, -0.19999540478147848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16750239073409937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27614697321489, 0.42174948917047583, -0.06193103118282252, -0.15000000044160214, -0.8245069658850457, -0.39848145497101634, 0.8567077699898648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6815969967026524, -0.1288673997502389, -0.6096309937908481]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878561702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15332502380572785, -0.014126441239606031, 0.06679690440536179, -2.4782191290981817e-11, -0.09233826670118767, -0.043488765293864876, 0.10956464277436537, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27842769822592073, 0.049406283679700846, -0.19999540561147325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1668524384899788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2844465507766662, 0.4210712187078201, -0.051505170525520734, -0.15000000044159464, -0.8394566359819176, -0.40097652166045167, 0.8629874285847511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6955429647403144, -0.1265358978511637, -0.6196308100153683]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882411426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16599155123552348, -0.013565409253114235, 0.20851721314603572, 1.4991957751880736e-13, -0.29899340193743756, -0.04990133378870636, 0.12559317189772634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2789193607532412, 0.04663003798150395, -0.19999632449040627]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16620248624597564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2933122644070877, 0.420415030496474, -0.03515432002112065, -0.1500000004418532, -0.8626926246928943, -0.4037341684422625, 0.8698200492138377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7095119089558011, -0.1243434784644009, -0.6296306274970043]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880063123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17731427260842994, -0.0131237642269218, 0.32701701008800155, -5.170628356396471e-12, -0.4647197742195341, -0.05515293563621632, 0.13665241258173166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27937888430973296, 0.04384838773525608, -0.1999963496327175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16555253391705643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3026181788739974, 0.41976420895689087, -0.014978721143549367, -0.1500000004418538, -0.891460497569343, -0.4066365402930106, 0.8768026569294196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.723502369979279, -0.12229046517566407, -0.6396304449791188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046578384271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18611828933819452, -0.013016430791661975, 0.40351197755142554, -1.2462032528120356e-14, -0.5753574575289726, -0.05804743701496184, 0.13965215431163894, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2798092204695588, 0.04106026577473655, -0.19999634964229177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16490258171661942, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3121654776012759, 0.41910003045659716, 0.005768785606304252, -0.1500000010063125, -0.922012071867307, -0.4094790751062277, 0.8833874117322497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7375128954617187, -0.12037714548959577, -0.6496302625646709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044008740433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19094597454556977, -0.01328357000587474, 0.41495013499707234, -1.1289173866109095e-08, -0.6110314859592819, -0.05685069626434171, 0.13169509605660054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2802105096487961, 0.03826639372136595, -0.19999635171104427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16425262949838296, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3217501446312281, 0.4184137763516962, 0.023756242031074543, -0.15000000100699085, -0.9505973482429387, -0.4120344603183687, 0.889079025091563, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7515420490451525, -0.11860378060434715, -0.6596300808050813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044364729578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19169334059904425, -0.01372508209801955, 0.3597491284954058, -1.3566967215285644e-11, -0.5717055275126331, -0.051107704242819414, 0.11383226718626614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2805830716686754, 0.035467297704972534, -0.19999636480820776]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16360267725436375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3312160963493463, 0.4177101509579465, 0.036441879827668465, -0.1500000010070652, -0.9734663268738926, -0.4141099510282917, 0.8935656432049074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.765588387967712, -0.1169705968368372, -0.6696298990489231]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880384279, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1893190343623644, -0.01407250787499421, 0.2537127559318784, -1.4870587345468537e-12, -0.4573795726190772, -0.0415098141984595, 0.08973236226688744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28092677845118896, 0.032663675350198915, -0.1999963648768364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16295272503000652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34045122145829243, 0.41700320072593433, 0.04199829933138077, -0.1500000012604679, -0.98686937459093, -0.41554827645050274, 0.8966911639083539, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.779650480775944, -0.11547779865077691, -0.6796297173345924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044487144661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18470250217892253, -0.014139004640243704, 0.11112839007424605, -5.0680535637459815e-09, -0.2680609543407494, -0.028766508444221496, 0.0625104140689295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2812418561646397, 0.029855963721205997, -0.19999636571338647]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1623027728560306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34940779051471443, 0.4163070350890156, 0.03963894085804336, -0.15000000216132275, -0.9887506532601159, -0.4162627949531472, 0.8984580034112469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7937269090741327, -0.11412555641960652, -0.6896295357220649]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043479518585, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17913138112844024, -0.013923312738374397, -0.04718716946674814, -1.8017097340678524e-08, -0.03762557338371636, -0.014290370052889648, 0.03533679005785974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2815285659637734, 0.027044844623407754, -0.19999636774944918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1616528206248878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3581518793422042, 0.41562502524976, 0.03040854207971421, -0.1500000023266479, -0.9811168629168205, -0.41630805453785746, 0.8990774586984458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8078162020289991, -0.11291408594252392, -0.6996293542013194]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044622855765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17488177654979614, -0.013640196785111983, -0.18460797556658298, -3.3065028712482224e-09, 0.15267580686590637, -0.000905191694204931, 0.012389105743977936, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2817858590973277, 0.02422940954165209, -0.19999636958509107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16100286860474192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.36683814399089076, 0.41494932978245186, 0.016791047158609428, -0.15000000233139915, -0.9672604094286987, -0.4158573868782251, 0.8988949537723698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8219169783238547, -0.11184347849608633, -0.7096291726825542]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999040402917607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1737252929737304, -0.0135139093461632, -0.27234989842209567, -9.502527628821921e-11, 0.27712906976243656, 0.009013353192647712, -0.0036500985215188533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2820155258971129, 0.021412148928751623, -0.1999963696246956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16035291636084198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.37565199692650764, 0.4142681915220035, 0.0017704865311310557, -0.15000000233297325, -0.9509312760383858, -0.4151295764964091, 0.8982852091036574, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8360278130418554, -0.11091386318945841, -0.7196290871132098]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877998677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17627705871233754, -0.01362276520896731, -0.30041121254956743, -3.148181310187109e-11, 0.32658266780625916, 0.01455620763632064, -0.012194893374249496, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2822166943600131, 0.01859230613255855, -0.19999828861311156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597029641054135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38477356728157597, 0.413573864833353, -0.011751701041473297, -0.15000000233447416, -0.9358684895014033, -0.414339180377886, 0.8976053179857624, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8501472410013078, -0.11012540169420493, -0.7296290015439164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045108569954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18243140710136713, -0.013886533773010225, -0.27044375145208704, -3.001811950312277e-11, 0.3012557307396483, 0.01580792237046159, -0.013597822357900403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.282388559189048, 0.015769229905069737, -0.19999828861413183]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15905301186612078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3943368375518594, 0.4128662350367365, -0.0216176214153116, -0.15000000239470182, -0.9246739086281888, -0.41364298228573787, 0.8971290144816123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8642738498644776, -0.10947816784407297, -0.7396289159888139]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044785854006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1912654054056681, -0.014152595932330626, -0.19731840747676604, -1.2045532684839895e-09, 0.2238916174642921, 0.013923961842962605, -0.009526070083000996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2825321772633965, 0.012944677002639349, -0.1999982888979484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15862762370758512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.40336755535140295, 0.41340607693608517, -0.0281417745480004, -0.15056065624380852, -0.9158851234555722, -0.4147688123198622, 0.8954882412787241, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8777409739113674, -0.1091985760415698, -0.749003830450675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00850776317071313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1806143559908712, 0.010796837986974256, -0.130483062653776, -0.011213076982133769, 0.17577570345233196, -0.022516600682486506, -0.032815464057764435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26934248093779445, 0.005591836050063553, -0.18749828923722325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15866397467095064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41120634123183086, 0.41524304262477346, -0.032422882310377946, -0.15213246733544894, -0.9090773270695434, -0.4168751986923581, 0.8933873651445428, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8896595776911644, -0.10928316141749454, -0.7571287475162742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007270192673103013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15677571760855868, 0.03673931377376621, -0.08562215524755097, -0.03143622183280849, 0.13615592772057628, -0.04212772744991837, -0.0420175226836258, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2383720755959403, -0.001691707518494845, -0.1624983413119849]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1588003517278768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41757497128040044, 0.41779023609231675, -0.035314351568069974, -0.154423409678742, -0.9039497222098302, -0.4191124837784526, 0.8914320019333295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8991418356088946, -0.10970790054089162, -0.7635050977073535]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002727541138523093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12737260097139155, 0.05094386935086524, -0.05782938515384049, -0.04581884686586117, 0.10255209719426467, -0.04474570172189043, -0.03910726422426541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18964515835460338, -0.008494782467941539, -0.12752700382158688]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15891866914771227, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.422458909698806, 0.42044679063717627, -0.03738836557092126, -0.15692689937591378, -0.9002174207846231, -0.4210719777976021, 0.8899399717272123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9058713832796049, -0.11001163766274924, -0.7682529106805343]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023663483967094855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0976787683681114, 0.05313109089719014, -0.041480280057025795, -0.050069793943436025, 0.07464602850414166, -0.03918988038298938, -0.029840604122345193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1345909534142064, -0.0060747424371524195, -0.09495625946361337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15901219306706263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4260259400394143, 0.42284212067648425, -0.03898148106632429, -0.15928328389903323, -0.8975956193402806, -0.4226101795595985, 0.8889916251372522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9102745008821276, -0.11009953125758494, -0.7716770084735937]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000" + }, + "execution_count": 10, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "reset_giskard()\n", + "\n", + "# adding a box to the world\n", + "box_pose = PoseStamped()\n", + "box_pose.header.frame_id = 'map'\n", + "box_pose.pose.orientation.w = 1\n", + "box_pose.pose.position.x = 2\n", + "box_pose.pose.position.y = -0.2\n", + "box_pose.pose.position.z = 0.7\n", + "gs.world.add_box('mybox', size=(0.1, 0.05, 0.2), pose=box_pose, parent_link='map')\n", + "\n", + "# specfy a goal pose 8cm in front of the box origin frame\n", + "goal_pose = PoseStamped()\n", + "goal_pose.header.frame_id = 'mybox'\n", + "goal_pose.pose.orientation.w = 1\n", + "goal_pose.pose.position.x = -0.08\n", + "goal_pose.pose.position.y = 0\n", + "goal_pose.pose.position.z = 0\n", + "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", + "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01, orientation_threshold=0.01)\n", + "gs.monitors.add_end_motion(pose_monitor)\n", + "gs.execute()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "When using the cartesian goals all degrees of freedom of the link are fully constrained. One Advantage of constraint-based control is that one can only constrain neccessary constraints.\n", + "The unconstrained DOF can then be exploited during the motion, for example in the collision avoidance or other secondary tasks.\n", + "To use this in the python interface one can use motion goals that constrain only a singualar value (sometimes called constraints on feature functions)." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "Combination of constraints and cost function augmentations to\n", + "- place both grippers at specific poses (2 6D Pose Constraints)\n", + "- keep the line of sight on the left gripper (Pointing Constraint)\n", + "- prefer using base movements if the grippers are further away from their goal poses and avoid base movements if they are close to their goals (Quadratic Weight Scaling)\n", + "- maximize the manipulability in each arm (Linear weight term in the cost function)" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 34, + "outputs": [ + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999943677873273, 0.036489651127809095, -0.34861191507695366, 0.0, -1.0029954720697876, 0.48869320376572917, -0.9525215184807941, -1.3886278121725906, -2.334452544500386, -0.4558788900739724, 0.11051798980155325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424639103, 0.01537723122151193, 1.7420423753144298, -2.031187242709937, -1.4888851823925482, -0.10085496898309822, 0.2189845498620707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529550045, -0.0006253905029041468, -0.0006249999999543101]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011264425345431811, -0.10782259036973244, 0.24007968118780842, 0.0, 0.03470669267139551, 0.02650595782943679, -0.0749999999999986, 0.07499999999999744, -0.06632406743743047, -0.02018751168584966, -0.07499999999999926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999737, 0.074999999999998, 0.07499999999999606, -0.012777139263307391, -0.04774843784840461, -2.521049782918791e-13, -0.04371418946734415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059100089, -0.012507810058082935, -0.012499999999997631]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998925805181444, 0.0267630596697571, -0.3278931585753566, 0.0, -1.0000224659428705, 0.49049653362158574, -0.9619301047404497, -1.379593523733744, -2.3410342122554755, -0.4572018850649818, 0.10116315485063393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8674174204432588, 0.025183583202972704, 1.751384115653074, -2.0317932410205013, -1.493464451596551, -0.10085496898310194, 0.21493079853658995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024960475280989564, -0.0025039454747618935, -0.0018977869579240155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00010219471025693422, -0.1945318291610399, 0.4143751300319408, 0.0, 0.05946012253834131, 0.03606659711713095, -0.1881717251931117, 0.18068576877693243, -0.13163335510178822, -0.026459899820186556, -0.18709669901838655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.17671844041302845, 0.19612703962921552, 0.18683480677288364, -0.012119966211281892, -0.09158538408005376, -7.442134995683418e-14, -0.0810750265096152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742876550287904, -0.037571099437154934, -0.025455739159394107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998493688783553, 0.014583839048681577, -0.30283958239639125, 0.0, -0.9965298716413223, 0.4921355227464133, -0.9760200982822472, -1.36680060810211, -2.349875174327609, -0.45803239691922115, 0.08685564365031923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8549868214394558, 0.03999234575967991, 1.7648047375765166, -2.0314752473307713, -1.4992752177285162, -0.10085496898347529, 0.20999822574163152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005922552841754735, -0.005952405107086799, -0.003193360879578438]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.642327957848494e-05, -0.2435844124215104, 0.5010715235793077, 0.0, 0.06985188603096355, 0.03277978249655097, -0.2817998708359508, 0.25585831263267966, -0.17681924144267328, -0.016610237084787073, -0.2861502240062941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24861198007606106, 0.2961752511341441, 0.26841243846885016, 0.006359873794598259, -0.11621532263930487, -7.467089435582319e-12, -0.09865145589916838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853010627311555, -0.06896919264649809, -0.025911478433088442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999809068351237, 0.0014335378704646243, -0.2761944917194697, 0.0, -0.9929074957979815, 0.49347927487126664, -0.9934337460668297, -1.3521735729677822, -2.3599662038298526, -0.457824273575296, 0.06884865106772532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8406534822932354, 0.058139594719090186, 1.7805125395519898, -2.029647170337682, -1.505313962569741, -0.10102857327294908, 0.20517189543805536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010643678979208298, -0.010710374037979753, -0.0038867220396985465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.06010542364428e-05, -0.26300602356433905, 0.5329018135384308, 0.0, 0.07244751686681615, 0.02687504249706601, -0.34827295569164807, 0.29254070268655696, -0.2018205900448637, 0.004162466878503277, -0.3601398516518781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2866667829244086, 0.3629449791882055, 0.31415603950946397, 0.0365615398617862, -0.12077489682449417, -0.0034720857894756426, -0.09652660607152291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09442252274907126, -0.09515937861785909, -0.013867223202402175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997690652879782, -0.011702002331867939, -0.24928874587665734, 0.0, -0.989246276057703, 0.49468681123771097, -1.0130856680342577, -1.3371594841759553, -2.370582763613108, -0.45628347991271506, 0.04830253205125776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8255901082630048, 0.07823517963514391, 1.7972253898468225, -2.026066250201851, -1.510779505665099, -0.10158468126685208, 0.20121590048948146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01641292307501113, -0.01652437680067441, -0.0038640671749981628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.000612651748077e-05, -0.26271080404665126, 0.5381149168562469, 0.0, 0.0732243948055711, 0.024150727328886127, -0.39303843934856075, 0.3002817758365387, -0.21233119566511, 0.030815873251618307, -0.41092238032935124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30126748060461117, 0.40191169832107443, 0.3342570058966499, 0.07161840271662138, -0.10931086190716179, -0.01112215987806014, -0.07911989897147827, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11538488191605661, -0.1162800552538931, 0.00045309729400767884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997283474068714, -0.02422006317593057, -0.22265032601038354, 0.0, -0.9854888087372059, 0.4959988791581555, -1.0342328168154162, -1.3226446897264197, -2.381293431749223, -0.45328812762035114, 0.026100264362257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8104723735088248, 0.09932762778084879, 1.8141873846479377, -2.020712517349157, -1.5151246688409317, -0.10266626822918933, 0.1986374242225254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023024727213398023, -0.023179169679737342, -0.003240362997743023]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.143576221380755e-05, -0.2503612168812526, 0.532768397325476, 0.0, 0.07514934640994225, 0.026241358408890046, -0.42294297562316907, 0.2902958889907117, -0.21421336272229458, 0.05990704584727803, -0.4440453537800151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3023546950835998, 0.42184896291409757, 0.3392398960223039, 0.10707465705388071, -0.08690326351665349, -0.021631739246744976, -0.05156952533912154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13223608276773788, -0.13309585758125864, 0.0124740835451028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996865980793582, -0.03577252767613231, -0.19642956701394904, 0.0, -0.9815406337022685, 0.4976208882400833, -1.056396033113364, -1.3090816174212576, -2.3918853969091396, -0.4488199833015818, 0.0028533308283817463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7956428661300832, 0.12084202839815208, 1.831009251468635, -2.013679421858163, -1.5180326510469635, -0.10435473103804188, 0.19771778927297087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030315445650636933, -0.03050174984173772, -0.002180320475781348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.349865502641323e-05, -0.2310492900040347, 0.5244151799286898, 0.0, 0.07896350069874844, 0.032440181638556685, -0.44326432595895465, 0.271261446103241, -0.21183930319833585, 0.08936288637538736, -0.4649386706775051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.29659014757483493, 0.43028801234606573, 0.3364373364139436, 0.14066190981987875, -0.058159644120635956, -0.03376925617705119, -0.018392698991090466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1458143687447782, -0.14645160324000756, 0.02120085043923349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996442330373115, -0.04616995896947086, -0.17062210968011732, 0.0, -0.9773194217804638, 0.49955824438821456, -1.07920000541233, -1.2966864109287906, -2.402273896109887, -0.44290888219037877, -0.021025607826192387, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7812463341514053, 0.1424741886154075, 1.8475146134884695, -2.0051054194168927, -1.519369528373308, -0.10669360940779955, 0.1985627728675731, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03815425881537758, -0.03835359792954218, -0.0008307438256598999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.473008409361587e-05, -0.20794862586677107, 0.5161491466766346, 0.0, 0.08442423843609374, 0.03874712296262459, -0.45607944597932065, 0.24790412984934107, -0.20776998401494684, 0.11822202222406095, -0.47757877309148267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2879306395735574, 0.4326432043451085, 0.3301072403966928, 0.17148004882540202, -0.02673754652688798, -0.04677756739515352, 0.016899671892044166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1567762632948129, -0.15703696175608922, 0.026991533002428958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996040725524014, -0.055314282637708795, -0.14516865212623695, 0.0, -0.9727456966265481, 0.5009982242991801, -1.1019427606501693, -1.2858660976682268, -2.412379732756123, -0.4355618582535085, -0.04519470760038505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.767324519208989, 0.1640966399781355, 1.8636348863947714, -1.9951358832689376, -1.5191345486479253, -0.10970712890896582, 0.20115281807469315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04643623664364146, -0.046624149490955655, 0.0006903032687336236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.0320969820218e-05, -0.1828864733647586, 0.5090691510776074, 0.0, 0.0914745030783143, 0.028799598219310777, -0.4548551047567852, 0.216406265211273, -0.202116732924724, 0.14694047873740462, -0.48338199548385324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2784362988483254, 0.43244902725455975, 0.3224054581260395, 0.19939072295909918, 0.004699594507654364, -0.060270390023325224, 0.05180090414240096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656395565652775, -0.1654110312282694, 0.03042094188787047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995656080170937, -0.06315356264304221, -0.1199941524971841, 0.0, -0.9677747180971222, 0.5012873611605031, -1.1241369183257128, -1.2768487140584996, -2.422146155899913, -0.42689116470085037, -0.06940616153652623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753877220547299, 0.18568829153512362, 1.8793483881907975, -1.983904792192392, -1.517416586876193, -0.11341034879709012, 0.20538601171981455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.055076911032641694, -0.05522545682713539, 0.002283205327204916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.692907061534153e-05, -0.15678560010666837, 0.5034899925810568, 0.0, 0.09941957058851723, 0.005782737226461488, -0.44388315351087204, 0.18034767219454395, -0.19532846287580571, 0.1734138710531634, -0.4842290787228237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26894597323380076, 0.43183303113976196, 0.3142700359205242, 0.22462182153091065, 0.03435923543464532, -0.07406439776248616, 0.08466387290242797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17281348778000474, -0.17202614672359462, 0.03185804116942584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995281641503582, -0.06966866451748287, -0.09502117513016206, 0.0, -0.9624003387814247, 0.500116271030617, -1.1455779972015496, -1.269654870766623, -2.431548357049536, -0.4170777138025503, -0.09350309815341745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7408879145352454, 0.2072870992331846, 1.8946485238828072, -1.9715281295513343, -1.5143590200051038, -0.11781302443341707, 0.21111215767328254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06400807277254862, -0.0640877832741035, 0.003868547243061622]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.488773347092766e-05, -0.13030203748881303, 0.4994595473404408, 0.0, 0.10748758631395008, -0.023421802597722835, -0.42882157751673766, 0.14387686583753134, -0.1880440229924549, 0.1962690179660015, -0.4819387323378244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2597861202410735, 0.43197615396121986, 0.3060027138401966, 0.24753325282115302, 0.06115133742178465, -0.08805351272653884, 0.11452291906935952, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17862323479813863, -0.17724652893936235, 0.03170683831713413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994913107957552, -0.07486978452803561, -0.07017347678394761, 0.0, -0.9566474214950237, 0.4974535442189808, -1.1662723818940892, -1.2641571779351852, -2.4405939888037196, -0.406312552106569, -0.11740332790066152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7283317732074577, 0.22895947583181858, 1.9095291082817134, -1.9581026453043, -1.5101332014272366, -0.12292019476310419, 0.21815816901528123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07317453423226578, -0.07315595397288652, 0.005390281978841689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.370670920623152e-05, -0.1040224002110549, 0.4969539669242888, 0.0, 0.11505834572802173, -0.0532545362327229, -0.4138876938507903, 0.10995385662875751, -0.1809126350836694, 0.2153032339196265, -0.4780045949448813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25112282655575346, 0.43344753197267905, 0.29761168797812365, 0.2685096849406872, 0.08451637155734373, -0.10214340659374235, 0.1409202268399741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18332922919434316, -0.18136341397566022, 0.030434694715601344]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999454778588323, -0.0787932511944504, -0.04537638636620607, 0.0, -0.9505610930258132, 0.4934320662590068, -1.186347623731432, -1.2601449452411397, -2.4493170870303422, -0.394757933766431, -0.1410787049015602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7161772892543037, 0.2507809650795023, 1.9239788941423313, -1.9437069608164215, -1.504919569294214, -0.1287315809038877, 0.22634589764778879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08253162230411247, -0.0823863518059898, 0.006815783357143117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.306441486449107e-05, -0.07846933332829581, 0.49594180835483076, 0.0, 0.12172656938421006, -0.08042955919948017, -0.401504836746858, 0.08024465388091005, -0.1744619645324521, 0.23109236680276088, -0.4735075400179733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24308967906307802, 0.4364297849536748, 0.28899571721235584, 0.2879136897575728, 0.10427264266044811, -0.11622772281567015, 0.1637545726501511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18714176143693387, -0.1846079566620657, 0.028510027566028558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999418401004553, -0.08149615548172884, -0.020556340685526725, 0.0, -0.9441966043754932, 0.4882542696256191, -1.205982998975845, -1.2573734263664906, -2.457768988172567, -0.3825317687870865, -0.16453548044579352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7043869252787127, 0.27282430441754935, 1.9379806416962566, -1.9284037276933006, -1.4988950104392036, -0.13524091820649173, 0.2355038109280024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09204320725190959, -0.09174447697766148, 0.008132419216196427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.275516754014441e-05, -0.054058085745568765, 0.49640091361358685, 0.0, 0.12728977300639832, -0.10355593266775534, -0.39270750488825773, 0.05543037749298321, -0.16903802284449532, 0.24452329958688943, -0.4691355108846665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23580727951181774, 0.44086678676094054, 0.28003495107850934, 0.30606466246241537, 0.12049117710021234, -0.13018674605208075, 0.18315826560427226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19023169895594233, -0.1871625034334337, 0.026332717181066216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993820843096527, -0.08304951929192882, 0.004359732278485691, 0.0, -0.9376112471486444, 0.48212994460053066, -1.2253658774053524, -1.2555963712456997, -2.466009239976215, -0.36970820743538035, -0.18779826770983304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6929184906149766, 0.2951523694979101, 1.9515121768008965, -1.9122422732104816, -1.4922250618411221, -0.14243568346670238, 0.24547391998940069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10168012295086909, -0.10120299526375542, 0.009342140285319461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.263338980055095e-05, -0.031067276203999572, 0.4983214592802483, 0.0, 0.13170714453697593, -0.12248650050176803, -0.3876575685901491, 0.035541102415818024, -0.16480503607295707, 0.256471227034123, -0.4652557452807905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22936869327472115, 0.4465613016072156, 0.27063070209279794, 0.32322908965637986, 0.13339897196162795, -0.1438953052042129, 0.19940218122796569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19273831397919, -0.18917036572187879, 0.024194421382460668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999345787218696, -0.08353142067439112, 0.029445008079205522, 0.0, -0.9308586256850422, 0.47524219487126584, -1.244668886932497, -1.2545853835584841, -2.4740982777286065, -0.35632634252206563, -0.21089833098617597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6817271814852262, 0.31781441248440706, 1.9645481115374919, -1.8952614045937972, -1.4850596725245517, -0.15029731022491274, 0.2561152164303628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1114188792209438, -0.11074019912926589, 0.010455772812928171]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.259418191355444e-05, -0.009638027649246223, 0.5017055160143966, 0.0, 0.1350524292720445, -0.13775499458529636, -0.38606019054289176, 0.0202197537443123, -0.16178075504782638, 0.2676372982662945, -0.4620012655268586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22382618259500872, 0.4532408597299385, 0.26071869473190895, 0.33961737233368844, 0.14330778633140898, -0.1572325351642074, 0.2128259288192421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1947751254014942, -0.1907440773102094, 0.02227265055217421]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999310607111454, -0.08302938996233994, 0.05477321513919481, 0.0, -0.923991414112252, 0.46773330417573744, -1.2640402128919723, -1.2541392907820497, -2.482092733130743, -0.34240177658041, -0.23386587648540366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.670773099558801, 0.3407370161374479, 1.9768575873766403, -1.877623985725392, -1.4775504600158724, -0.1588547607254304, 0.2672813611253824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12124067996820441, -0.12033872601129876, 0.011496409058730188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.036021448414886e-05, 0.010040614241023614, 0.5065641411997858, 0.0, 0.13734423145580163, -0.1501778139105684, -0.38742651918950577, 0.00892185552869019, -0.15988910804273, 0.2784913188331126, -0.459350909984554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21908163852850127, 0.4584520730608169, 0.24618951678296816, 0.3527483773681055, 0.1501842501735842, -0.17114901001035326, 0.2233228939003923, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19643601494521215, -0.19197053764065736, 0.020812724916040352]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992804213393903, -0.08165764022566474, 0.08041948891832457, 0.0, -0.9170770735508773, 0.45970313497894394, -1.283601065526524, -1.254086813416885, -2.490043326135137, -0.3279381466345287, -0.2567255882798957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6600365308914813, 0.3634496468522489, 1.9875244374976193, -1.859987029478487, -1.4699013151136944, -0.1682919919079088, 0.2787573864212014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13113083499134293, -0.12998432922857048, 0.012517509370653924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0371544126995355e-05, 0.027434994733504064, 0.512925475582595, 0.0, 0.13828681122749548, -0.16060338393586998, -0.3912170526910351, 0.0010495473032916588, -0.15901186008788104, 0.28927259891762647, -0.4571942358898413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21473137334639292, 0.45425261429602043, 0.21333700241957979, 0.35273912493810033, 0.15298289804356144, -0.1887446236495683, 0.2295205059163795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1978031004627706, -0.19291206434543448, 0.020422006238474722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992545743305098, -0.0795159245272511, 0.10646074018709453, 0.0, -0.9101708458552307, 0.45121181250340664, -1.3034525260914236, -1.254290785018126, -2.4979930325894326, -0.31293292071170853, -0.2794942992600252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6494984100499197, 0.38552614818554565, 1.995875388686491, -1.842962512642937, -1.4623139445105957, -0.1786552829958554, 0.2903352443415077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14107795986408048, -0.13966523005111176, 0.013562634334371814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.169401776087522e-05, 0.04283431396827265, 0.5208250253753994, 0.0, 0.13812455391293332, -0.16982644951074582, -0.39702921129799257, -0.004079432024817522, -0.15899412908591287, 0.30010451845640373, -0.45537421960259006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2107624168312294, 0.44153002666593455, 0.16701902377743577, 0.340490336711002, 0.15174741206197195, -0.20726582175893182, 0.23155715840612628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19894249745475076, -0.19361801645082535, 0.02090249927435781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992322813680996, -0.07670867382958221, 0.1329763188290542, 0.0, -0.9032348264408785, 0.44214690901905485, -1.323493252842749, -1.254855348925615, -2.5059698634130587, -0.2980366560047832, -0.3021668847623032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.639108140516877, 0.40669613074814553, 2.001651537455167, -1.8269615651281002, -1.4549582247240107, -0.18982475365300422, 0.30184944505258826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15107350323247298, -0.14937142693135094, 0.014685286317639549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4585924820379004e-05, 0.05614501395337779, 0.5303115728391934, 0.0, 0.13872038828704258, -0.18129806968703563, -0.40081453502650954, -0.0112912781497776, -0.15953661647252596, 0.2979252941385066, -0.45345171004555895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20780539066085135, 0.42339965125199724, 0.11552297537352055, 0.32001895029673716, 0.1471143957317011, -0.22338941314297658, 0.23028401422161135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991086736785002, -0.19412393760478375, 0.02245303966535469]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992130626790985, -0.07340491572848924, 0.15994061314862004, 0.0, -0.8962724789649682, 0.4324964947242017, -1.3438263294093244, -1.2556221171898703, -2.514013184406461, -0.2835484250369043, -0.3247341376957751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6288354085764698, 0.42682450613392386, 2.0049347917272113, -1.8121833806064307, -1.4479642065666531, -0.20157012497956966, 0.31318554591657793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16111059208723302, -0.15909494212136988, 0.01586729616881353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8437378001899175e-05, 0.06607516202185941, 0.5392858863913167, 0.0, 0.13924694951820532, -0.19300828589706293, -0.4066615313315085, -0.015335365285106062, -0.1608664198680467, 0.28976461935757797, -0.4513450586694377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20545463880814627, 0.40256750771556626, 0.06566508544089172, 0.2955636904333909, 0.1398803631471516, -0.23490742653130897, 0.22672201727979394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007417770952007, -0.19447030380037839, 0.023640197023479626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991966840970793, -0.06977970537894607, 0.18726994136662176, 0.0, -0.8892701283554084, 0.42224521192470754, -1.3645891160146304, -1.256394921929232, -2.5221558967836404, -0.2696095747926342, -0.3471787210740257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6186465895692452, 0.4458749683982276, 2.0060105202825427, -1.7986622006434627, -1.4414223202292344, -0.21361339867696572, 0.32427683434982835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1711835067910226, -0.1688296131239169, 0.017074813798622437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.275716403852687e-05, 0.07250420699086339, 0.5465865643600344, 0.0, 0.14004701219119592, -0.20502565598988312, -0.4152557321061212, -0.015456094787236955, -0.16285424754359026, 0.27877700488540236, -0.44889166756501203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20377638014449317, 0.3810092452860746, 0.021514571106627384, 0.2704235992593596, 0.13083772674837285, -0.240865473947921, 0.22182576866500847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2014582940757915, -0.19469342005094056, 0.024150352596178155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991829704491304, -0.06595164889716351, 0.21486738391251042, 0.0, -0.8821869876742153, 0.4113580694793555, -1.3858915903241376, -1.2570265264617904, -2.5304170095375724, -0.25627574742973624, -0.36947639220324785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6085015888525278, 0.46387136236181853, 2.005249868742743, -1.7863216674809272, -1.4353896885281745, -0.22567821158055126, 0.3350945463214575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18128738829199612, -0.17857079626743272, 0.01827446757476247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.742729589774109e-05, 0.07656112963565102, 0.5519488509177736, 0.0, 0.14166281362386218, -0.21774284890704082, -0.4260494861901423, -0.012632090651166567, -0.165222255078642, 0.26667654725795925, -0.44595342258444315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.202900014334348, 0.3599278792718181, -0.015213030795990373, 0.24681066325070852, 0.12065263402119997, -0.24129625807171087, 0.21635423943258303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20207763001947027, -0.19482366287031647, 0.02399307552280062]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999171936687081, -0.06200489325961712, 0.24262760650810797, 0.0, -0.8749077381951124, 0.3997031550632148, -1.4076775335683605, -1.25758594128843, -2.5387972096710043, -0.24417857712991742, -0.391590489618162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.598342974240442, 0.48087099638066244, 2.003027721377976, -1.7750238484235246, -1.4298975236623708, -0.2375200347171883, 0.34563704259039363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19141825256944675, -0.1883148717070868, 0.019458676694438536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2067524098460056e-05, 0.07893511275092788, 0.555204451911951, 0.0, 0.1455849895820586, -0.23309828832281398, -0.43571886488445577, -0.011188296532793842, -0.16760400266863723, 0.24194340599637676, -0.4422819482982835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20317229224171607, 0.33999268037687863, -0.044442947295344856, 0.22595638114805344, 0.10984329731607509, -0.23683646273274064, 0.2108499253787216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20261728554901254, -0.19488150879308166, 0.023684182393521297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991632893154915, -0.057955381131714064, 0.27043383512585756, 0.0, -0.867367996397315, 0.3872512299726996, -1.429980287645491, -1.2580481042981049, -2.5472886953391627, -0.23334210046732623, -0.4134925815781258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.588134021490493, 0.49694044611680416, 1.9996814247534958, -1.7646048459974841, -1.4249597077185387, -0.24894317319441417, 0.3559190350014655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20157257289412323, -0.1980592924005522, 0.020596362724224826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7294743179113573e-05, 0.0809902425580611, 0.5561245723549918, 0.0, 0.1507948359559485, -0.24903850181030343, -0.4460550815426122, -0.009243260193495056, -0.16982971336316888, 0.21672953325182365, -0.43804183919927536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2041790549989801, 0.321388994722834, -0.06692593248960249, 0.20838004852081085, 0.09875631887663844, -0.2284627695445175, 0.2056398482214377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20308640649352938, -0.1948884138693078, 0.022753720595725828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991570323469426, -0.053798476309639034, 0.29815606018178514, 0.0, -0.8595176351390179, 0.37399993210151256, -1.4528474884205413, -1.2583752085214903, -2.5558745158296525, -0.22360631004274767, -0.43515990202702315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5778455511123288, 0.5121486757206983, 1.9954893594833063, -1.7549029483419794, -1.4205778231805546, -0.2598038304006368, 0.36596427551383576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21174720324770274, -0.20780235697116883, 0.0216640683540259]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2513937097453594e-05, 0.08313809644150058, 0.5544445011185514, 0.0, 0.1570072251659406, -0.2650259574237416, -0.4573440155010057, -0.006542084467708544, -0.17171640980979766, 0.19471580849157094, -0.4333464089779465, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2057694075632873, 0.30416459207788243, -0.08384130540378956, 0.19403795311009459, 0.08763769075968289, -0.2172131441244532, 0.2009048102474056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2034926070715904, -0.1948612914123327, 0.021354112596021484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991532140068302, -0.0495261124340122, 0.32565129367259676, 0.0, -0.8513100937361373, 0.3599504123409985, -1.4763174109024948, -1.2585407040120304, -2.564530809104911, -0.21478922970344114, -0.4565740300787786, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5674527919006813, 0.5265628008053821, 1.9906665842974844, -1.7457735158233119, -1.4167452974479746, -0.27000673079348886, 0.375800257381472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22193937709696854, -0.21754296453507113, 0.02265058158026335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.636680224744883e-06, 0.08544727751253674, 0.5499046698162328, 0.0, 0.16415082805761122, -0.28099039521028146, -0.4693984496390691, -0.0033099098108013477, -0.17312586550517142, 0.17634160678613053, -0.42828256103510925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20785518423294885, 0.288282501693675, -0.09645550371643657, 0.1825886503733485, 0.07665051465159964, -0.2040580078570406, 0.1967196373527248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20384347698531594, -0.19481215127804613, 0.019730264524749012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991519586375045, -0.04514634070765176, 0.3514006435865091, 0.0, -0.8426592115557481, 0.3450548782274425, -1.5003302905499343, -1.2586417207195475, -2.5732270149977454, -0.2073179997627597, -0.4777153494071629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569252279431307, 0.5402475213617974, 1.9853689104517105, -1.737095556272282, -1.41345007180058, -0.279497516553597, 0.3854550071751034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23214684001108826, -0.2272802767874083, 0.023568252139719102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.510738651493572e-06, 0.08759543452720886, 0.5149869982782466, 0.0, 0.1730176436077857, -0.2979106822711192, -0.4802575929487916, -0.002020334150341435, -0.17392411785668363, 0.1494245988136289, -0.42282638656768645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.210551279151014, 0.27369441112830695, -0.10595347691547766, 0.17355919102059403, 0.06590451294789099, -0.18981571520216345, 0.1930949958726276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2041492582823945, -0.19474624504674332, 0.018353411189115012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991531433682683, -0.040652203443944004, 0.3734640331474745, 0.0, -0.8335255223283966, 0.32932626206854554, -1.5248929540006286, -1.2586880015078965, -2.581930858881691, -0.20105999855085718, -0.498573411877532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5462492593169215, 0.5532608933159537, 1.9797051056484585, -1.7287711810021689, -1.4106774840942202, -0.28825605805658827, 0.3949547180241143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24236763948430182, -0.23701378075307267, 0.02441571502677804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.369461527810091e-06, 0.08988274527415509, 0.4412677912193081, 0.0, 0.18267378454702882, -0.3145723231779398, -0.4912532690138861, -0.0009256157669812709, -0.1740768776789138, 0.12516002423805006, -0.4171612494073814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2135193725241847, 0.26026743908312594, -0.11327609606504076, 0.16648750540226392, 0.055451754127197606, -0.17517083005982564, 0.18999421698021818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20441598946427111, -0.19467007931328703, 0.016949257741178766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991568038104338, -0.03604378387140768, 0.39102189623055855, 0.0, -0.8238822059508757, 0.3127923029678555, -1.5500276807358593, -1.2586642221456124, -2.5906074666517895, -0.19576593852907737, -0.5191436384328104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5354166890823266, 0.5656565402075744, 1.9737468833513334, -1.7207250504230756, -1.4084109998532808, -0.29628753156221943, 0.4043231753796419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25260010035560265, -0.24674318402336615, 0.02519559589684357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.320884331225334e-06, 0.09216839145072646, 0.35115726166168076, 0.0, 0.1928663275504183, -0.33067918201380153, -0.502694534704615, 0.0004755872456812329, -0.17353215540196934, 0.10588120043559658, -0.4114045311055688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21665140469189534, 0.2479129378324135, -0.11916444594250003, 0.16092261158186555, 0.045329684818788706, -0.1606294701126236, 0.1873691471105526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20464921742601713, -0.1945880654058694, 0.015597617401310607]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991629762965907, -0.0313301511200436, 0.4042356347770096, 0.0, -0.8137036635729823, 0.2954815505203647, -1.5757550714762791, -1.2585520824471372, -2.599220977602953, -0.19121333064802526, -0.539425331861611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5244213501439687, 0.5774842648355991, 1.9675384844805521, -1.7129005387961165, -1.4066329340866166, -0.30361497808066934, 0.41358166513866096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26284282183271745, -0.25646830713754026, 0.025915311458413366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2344972314041837e-05, 0.0942726550272815, 0.26427477092902024, 0.0, 0.2035708475578688, -0.3462150489498161, -0.5145478148083986, 0.0022427939695019595, -0.17227021902327067, 0.09105215762104218, -0.4056338685760125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21990677876715797, 0.2365544925604943, -0.12416797741562423, 0.15649023253918076, 0.03556131533328266, -0.14654893036899808, 0.18516979518038082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20485442954229588, -0.19450246228348259, 0.014394311231395939]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991716731154052, -0.026525558340783968, 0.41380240247527866, 0.0, -0.8029623156404427, 0.2774207428798835, -1.6020897913705852, -1.2583369909018103, -2.607736646785377, -0.1872381734880999, -0.5594203751179667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5132583434356306, 0.5887901948276059, 1.9611049586567002, -1.7052552910862158, -1.405324980846817, -0.3102732739851018, 0.42274918911505466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.273094660675004, -0.2661890497572536, 0.026584619763713735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.739363762884511e-05, 0.09609185558519262, 0.19133535396538198, 0.0, 0.21482695865079082, -0.36121615280962405, -0.5266943978861184, 0.0043018309065368885, -0.17031338364847823, 0.0795031431985073, -0.3999008651271129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2232601341667642, 0.22611859984013546, -0.12867051647703923, 0.15290495419801506, 0.026159064795992434, -0.13316591808864933, 0.1833504795278738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20503677684573077, -0.19441485239426728, 0.013386166106007354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991828863620853, -0.021645009132675964, 0.4205907108636889, 0.0, -0.791628159543138, 0.258635880996209, -1.6290408846014002, -1.2580090366093195, -2.6161224405769827, -0.18372994186970218, -0.5791323817827055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5019239113415281, 0.5996168454478135, 1.9544588074527132, -1.6977572570550705, -1.404468556059473, -0.31630444289788495, 0.4318428320375456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28335470022604436, -0.27590532282194086, 0.027213481376127325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.242649336002097e-05, 0.09761098416216009, 0.13576616776820377, 0.0, 0.22668312194609339, -0.3756972376734905, -0.5390218646163004, 0.006559085849813688, -0.16771587583211528, 0.07016463236795442, -0.39424013329477636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22668864188205057, 0.21653301240415293, -0.1329230240797412, 0.1499606806229051, 0.01712849574688053, -0.12062337825566287, 0.18187285844981813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2052007910208073, -0.19432546129374453, 0.01257723224827178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991965916541216, -0.016701056200382057, 0.4254225939679053, 0.0, -0.7796690759648334, 0.23915418238325292, -1.6566134421122871, -1.25756206611305, -2.624349893978199, -0.18061804771119994, -0.5985661845110753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904153737741563, 0.6100031613137556, 1.947604948074933, -1.6903814793287308, -1.404045026353251, -0.32175417684037083, 0.44087815263000113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29362221457316656, -0.285617048995376, 0.027810817361409907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7410584072310096e-05, 0.0988790586458781, 0.09663766208432883, 0.0, 0.23918167156609368, -0.3896339722591212, -0.5514511502177396, 0.008939409925390817, -0.16454906802433, 0.062237883170044736, -0.3886760545673955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23017075134743417, 0.20772631731884392, -0.1370771875556067, 0.1475155545267934, 0.008470594124443212, -0.10899467884971732, 0.18070641184911032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20535028694244367, -0.1942345234687028, 0.011946719705651644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992127501286358, -0.011702208613917686, 0.4289739422232274, 0.0, -0.7670512784878643, 0.21900591760066124, -1.684810411942989, -1.2569922982686135, -2.632394354661889, -0.17785914352096863, -0.617727581249097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787309925001368, 0.6199845755451108, 1.9405442054172986, -1.683107685070384, -1.4040358776467259, -0.3266693798282774, 0.44986952770788047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30389663225850994, -0.2953241545968568, 0.028383949432997407]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2316949028507026e-05, 0.09997695172928742, 0.0710269651064412, 0.0, 0.25235594953938256, -0.4029652956518339, -0.563939396614037, 0.011395356888729244, -0.1608892136737929, 0.0551780838046262, -0.3832279347604332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23368762548039063, 0.19962828462710325, -0.14121485315268698, 0.14547588516693374, 0.0001829741305017802, -0.09830405975813139, 0.17982750155758723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548835370686713, -0.1941421120296164, 0.01146264143174999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992313101318812, -0.006652692565644477, 0.4317498358492036, 0.0, -0.7537397487466786, 0.19822584140021687, -1.7136341431009776, -1.2562970072993924, -2.6402348296879428, -0.17542754335129496, -0.6366232662843543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4668697844299083, 0.6295930893252552, 1.933275611045951, -1.6759185806028578, -1.404422861464175, -0.33109652878027634, 0.458830413805529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31417750276953854, -0.30502657383305176, 0.02893846063414057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.712000649054735e-05, 0.10099032096546418, 0.05551787251952504, 0.0, 0.2662305948237139, -0.4156015240088871, -0.5764746231597715, 0.01390581938442012, -0.15680950052107492, 0.04863200339347323, -0.37791370070514646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2372241614045679, 0.19217027560288796, -0.1453718874269521, 0.14378208935052617, -0.00773967634898096, -0.08854297903997929, 0.1792177219529715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056174102205722, -0.1940483847238996, 0.011090224022863238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999252208256924, -0.0015530650799208427, 0.43409950235886813, 0.0, -0.7396986511357861, 0.17685419495564528, -1.7430875667126164, -1.255473436518051, -2.6478536261191183, -0.1733086480035227, -0.6552608821508061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4548313208956247, 0.638857379542875, 1.9257978066239203, -1.6687987189318956, -1.4051881357602882, -0.3350806539796887, 0.46777352030281205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32446446710359783, -0.3147242513390845, 0.02947827750528296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.179625008542345e-05, 0.10199254971447269, 0.04699333019329052, 0.0, 0.2808219522178488, -0.4274329288914317, -0.5890684722327764, 0.01647141562682765, -0.1523759286235147, 0.04237790695544556, -0.37275231732903635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24076927068567405, 0.1852858043523969, -0.14955608844061632, 0.14239723341924326, -0.015305485922267837, -0.07968250398824721, 0.17886212994566003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20573928668118585, -0.19395355012065485, 0.010796337422847802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992753700588597, 0.003598798511559146, 0.43624739217648045, 0.0, -0.724891741690841, 0.15493734916362287, -1.77317503344434, -1.2545179696671447, -2.65523591858819, -0.17149465918198545, -0.6736491402359694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4426155419967504, 0.6478029342278301, 1.9181098129680592, -1.6617337984280063, -1.4063144055645729, -0.33866476616335506, 0.4767109036375887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3347572324029258, -0.3244171475426142, 0.030005856709231834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6323603871767203e-05, 0.10303727182959976, 0.04295779635224643, 0.0, 0.2961381888989033, -0.43833691584044815, -0.6017493346344696, 0.01910933701812804, -0.1476458493814388, 0.036279776430745134, -0.36776516170326684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24431557797748968, 0.17891109369910227, -0.15375987311722422, 0.14129841007778507, -0.0225253960856932, -0.07168224367332676, 0.17874766669553313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20585530598655982, -0.19385792407059352, 0.010551584078977523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999300727479941, 0.008804094513933344, 0.43832674680155004, 0.0, -0.7092734812854777, 0.1325250230096199, -1.8038896617668416, -1.2534467156304505, -2.662369107290451, -0.170136386354041, -0.6917974923403458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4302206397529396, 0.656452392197265, 1.91021119496771, -1.654710318457212, -1.4077850093685291, -0.3418894014845274, 0.48565401651967277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34505557801701003, -0.3341052161568823, 0.03052500721608979]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.071484216269138e-05, 0.10410592004748395, 0.041587092501391226, 0.0, 0.3123652081072662, -0.4482465230800592, -0.6142925664500328, 0.02142508073388495, -0.14266377404522404, 0.02716545655888939, -0.3629670420875271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.247898044876214, 0.1729891593886999, -0.15797236000698112, 0.1404695994158832, -0.029412076079125125, -0.06449270642344677, 0.17886225764168148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596691228168415, -0.1937613722853621, 0.01038301013715913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993281607735924, 0.014069201764168223, 0.440554074676966, 0.0, -0.6928109809552064, 0.10967925831495132, -1.8352409943354022, -1.2522513346602826, -2.6692418402322686, -0.16918147937709843, -0.7097178193704274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4176478262465135, 0.6648252180781782, 1.9021025352490581, -1.6477151275537387, -1.4095841982762256, -0.3447930230988332, 0.4946136536266191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35535929515115294, -0.3437884526041532, 0.031034178355589064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.4866587303167144e-05, 0.10530214500469758, 0.044546557508319394, 0.0, 0.329250006605426, -0.4569152938933719, -0.627026651371214, 0.023907619403360444, -0.1374546588363505, 0.0190981395388514, -0.3584065406016334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2514562701285214, 0.1674565176182633, -0.16217319437304076, 0.13990381806946717, -0.035983778153928975, -0.05807243228611571, 0.17919274213892625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20607434268285799, -0.19366472894541778, 0.010183422789985429]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993575682648196, 0.019400616468993246, 0.44289768829019843, 0.0, -0.6754744605295335, 0.08646953830834081, -1.8672451722132992, -1.2509139006384626, -2.6758434597702183, -0.1685470814504019, -0.7274240181573949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4048984576701506, 0.6729382830732726, 1.8937852932352317, -1.640735717797071, -1.4116971315210167, -0.3474117904117522, 0.5035999569603018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3656681770246601, -0.3534668961450138, 0.031531318896992885]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.8814982454298406e-05, 0.10662829409650044, 0.04687227226464876, 0.0, 0.3467304085134582, -0.46419440013220997, -0.6400835575579383, 0.02674868043639765, -0.1320323907589963, 0.012687958533930593, -0.3541239757393488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2549873715272559, 0.16226129990188878, -0.16634484027652924, 0.1395881951333539, -0.04225866489582044, -0.05237534625838001, 0.17972606667365373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617763747014317, -0.1935688708172126, 0.009942810828076472]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993888393816484, 0.0248040893394555, 0.44529375356535134, 0.0, -0.657234770570855, 0.06297094490393922, -1.8999212050323753, -1.249412458692867, -2.682164551083141, -0.16816676905990524, -0.7449317767870256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3919731590322595, 0.6808061382983573, 1.8852615233704535, -1.6337601318767279, -1.4141099807966149, -0.3497796362304216, 0.5126224001403346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37598173324735323, -0.36314035844652015, 0.03201440817113183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.254223365770543e-05, 0.10806945740924509, 0.04792130550305777, 0.0, 0.3647937991735709, -0.4699718680880319, -0.6535206563815221, 0.03002883891191481, -0.12642182625846027, 0.007606247809932947, -0.35015517259261514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2585059727578234, 0.15735710450169496, -0.17047539729556585, 0.1395117184068595, -0.048256985511962884, -0.04735691637338743, 0.18044886360065446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20627112445386322, -0.19346924603012725, 0.00966178548277895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994218755304446, 0.03028111445937137, 0.4476983151298864, 0.0, -0.638051332776127, 0.03926257745153229, -1.9332743876008847, -1.2477508441344103, -2.688197452370262, -0.16810928445998144, -0.7622579496811501, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3788697670593844, 0.6884412863522363, 1.8765336079476393, -1.6267770578307548, -1.4168099483184164, -0.35192815298540625, 0.521689746529341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38629983835555937, -0.3728089685767702, 0.03248476983167084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.607229759236975e-05, 0.10954050239831736, 0.04809123129070107, 0.0, 0.3836687558945604, -0.4741673490481384, -0.6670636513701855, 0.03323229116913221, -0.12065802574241588, 0.001149691998475956, -0.3465234578824916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2620678394575032, 0.15270296107757883, -0.17455830845628348, 0.13966148091946143, -0.053999350436031546, -0.04297033509969325, 0.1813469277801277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063621021641231, -0.19337220260500151, 0.009407233210780217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994565462695438, 0.035833492498871876, 0.4500905981744083, 0.0, -0.6178842585120434, 0.015431057167064749, -1.9673061459951764, -1.2459416831053933, -2.6939362728567957, -0.16848615907127737, -0.7794214344100959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3655861790610817, 0.695854000809875, 1.8676041606193066, -1.6197754582617239, -1.4197854587358523, -0.35388704398114024, 0.5308099776510703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3966223687317779, -0.382472854002744, 0.03294257592190131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.934147819820369e-05, 0.11104756079001019, 0.04784566089043712, 0.0, 0.40334148528167124, -0.47663040568935083, -0.6806351678858344, 0.03618322058034058, -0.11477640973067882, -0.007537492225918648, -0.3432696945789163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26567175996605197, 0.1482542891527731, -0.1785889465666572, 0.14003199138061714, -0.05951020834871641, -0.03917781991467974, 0.18240462243458555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064506075243705, -0.1932777085194761, 0.009156121804609322]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994927114146885, 0.04146423281254037, 0.4524652423308594, 0.0, -0.5967002839762974, -0.008428315810264247, -2.002019540532723, -1.2439956941687156, -2.6993758339653144, -0.16940299491767172, -0.7964438610998594, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3521212162123777, 0.7030525069188116, 1.8584760797939717, -1.6127446918799009, -1.4230261952653138, -0.35568434019006, 0.539990275195647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4069491874556222, -0.3921321596665384, 0.0333861414163522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.233029028954226e-05, 0.1126148062733699, 0.04749288312902246, 0.0, 0.42367949071492217, -0.4771874595465799, -0.694267890750924, 0.038919778733553526, -0.10879122217037608, -0.018336716927886926, -0.3404485337952699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2692992569740784, 0.14397012217873117, -0.18256161650669792, 0.14061532763645895, -0.0648147305892294, -0.035945924178395046, 0.1836059508915353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20653637447688533, -0.19318611327588817, 0.008871309889017753]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995302292547737, 0.04717719163981723, 0.45482467173455715, 0.0, -0.5744743481247945, -0.03221191560342329, -2.0374207516577627, -1.2419173313528997, -2.704510349690118, -0.17094461988618306, -0.8133500607854194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.338474363592058, 0.710043323425046, 1.849152611281147, -1.6056747744240032, -1.4265230589240911, -0.3573465118464638, 0.5492370613052514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4172801236089696, -0.40178706148223914, 0.03381250417578785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.50356801704552e-05, 0.1142591765455371, 0.0471885880739552, 0.0, 0.4445187170300572, -0.47567199586318076, -0.7080242225007946, 0.041567256316315505, -0.10269031449607864, -0.030832499370226814, -0.3381239937112001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27293705240639565, 0.13981633012468742, -0.18646937025649496, 0.14139834911795557, -0.06993727317554597, -0.03324343312807645, 0.18493572219208787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2066187230669484, -0.1930980363140145, 0.008527255188713103]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995689562569696, 0.0529764013584553, 0.4571740315963459, 0.0, -0.5511892882837658, -0.05580878834381451, -2.0735186015691505, -1.2397038596385224, -2.70933229877117, -0.17317392474171134, -0.8301683189783522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3246456650861915, 0.716831383794669, 1.8396373038523934, -1.5985564082349324, -1.4302681534635762, -0.3588985346995499, 0.558555999158406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42761497664776876, -0.4114377704488579, 0.03421828106622663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.745400439178555e-05, 0.1159841943727615, 0.046987197235774894, 0.0, 0.4657011968205729, -0.4719374548078243, -0.7219569982277539, 0.04426943428754573, -0.09643898162103368, -0.044586097110565416, -0.33636516385865606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2765739701173271, 0.1357612073924629, -0.19030614857507142, 0.1423673237814152, -0.07490189078970134, -0.03104045706172176, 0.18637875706309256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20669706077598285, -0.1930141793323752, 0.008115537808775676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996089890845417, 0.05888883692989693, 0.4595184800629568, 0.0, -0.526901883015525, -0.07893182781676603, -2.110092321432455, -1.2373198520905968, -2.7134998146319544, -0.17613304333447521, -0.8465907922731724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.310653127481421, 0.7234196128227636, 1.8299352386537378, -1.5913806634700793, -1.4342550396317781, -0.36036587707562534, 0.5679520932180644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4379532912986751, -0.421084771078369, 0.03457703990224904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.006565514422405e-05, 0.11824871142883255, 0.046888969332218, 0.0, 0.485748105364817, -0.4624607894590302, -0.7314743972660956, 0.047680150958511774, -0.08335031721568739, -0.05918237185527777, -0.32844946589640434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27985075209540916, 0.13176458056189136, -0.19404130397311342, 0.14351489529706157, -0.07973772336403934, -0.029346847521508145, 0.18792188119316772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20676629301812666, -0.1929400125902228, 0.007175176720448172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999650598841945, 0.06497439219545284, 0.4618620525147836, 0.0, -0.5017975861345425, -0.10103100307083646, -2.1465184654326808, -1.234674623861658, -2.7161027121378716, -0.17985000619381897, -0.8617340947443358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2965438552155464, 0.7298096042905275, 1.8200545056691093, -1.5841400898195637, -1.4384785532693973, -0.36177571462075087, 0.5774299590274339, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4482940391134155, -0.43072916432052577, 0.034829289387686035]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.3219514806687e-05, 0.12171110531111831, 0.046871449036536506, 0.0, 0.5020859376196491, -0.4419835050814085, -0.7285228800045104, 0.05290456457877694, -0.052057950118340725, -0.07433925718687479, -0.30286604942326895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28218544531749395, 0.1277998293552787, -0.1976146596925673, 0.14481147301031166, -0.0844702727523845, -0.028196750902510892, 0.18955731618739077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2068149562948069, -0.19288786484313503, 0.0050449897087399016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996936354723793, 0.07126622309335441, 0.4642074181845505, 0.0, -0.4760551418039262, -0.12167984801784872, -2.1822476332991476, -1.2316783456747256, -2.716361757472941, -0.18434645519981743, -0.8748556332219445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.282349992373356, 0.7360038559743707, 1.8100036805633035, -1.5768306365002767, -1.4429338617451328, -0.36315222153362153, 0.5869939497017014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4586358746761437, -0.44037239127138705, 0.0349420811878866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.607326086861515e-05, 0.12583661795803136, 0.046907313395338227, 0.0, 0.5148488866123256, -0.4129768989402451, -0.7145833573293369, 0.05992556373864878, -0.005180906701383242, -0.08992898011996939, -0.26243076955217426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28387725684381143, 0.12388503367686289, -0.20101650211611713, 0.14618906638573945, -0.08910616951470839, -0.027530138257413045, 0.1912798134853488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683671125456485, -0.19286453901722592, 0.0022558360040113136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997379143001764, 0.07776899639084262, 0.46655600538470354, 0.0, -0.4498147428041323, -0.1406513385680828, -2.2169279753438587, -1.228267958933324, -2.7138063538676853, -0.18962681856315414, -0.8855349017778712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2680810973387941, 0.7420045623063706, 1.7997893976568422, -1.5694488605442787, -1.4476169525708655, -0.36451601216623863, 0.5966479672555021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46897740788126946, -0.4500159440950995, 0.03491072156614704]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.855765559401911e-05, 0.13005546594976414, 0.046971744003060124, 0.0, 0.5248079799958779, -0.3794298110046814, -0.6936068408942236, 0.0682077348280285, 0.05110807210511245, -0.1056072672667343, -0.21358537111853512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2853779006912345, 0.12001412663999692, -0.20428565812922733, 0.1476355191199587, -0.09366181651465605, -0.02727581265234201, 0.19308035107601457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683066410251555, -0.1928710564742491, -0.00062719243479135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997859488869993, 0.08449411927742755, 0.46890829058041245, 0.0, -0.423228987139392, -0.15802175540469443, -2.249987385598714, -1.2241457216270608, -2.7084187345750443, -0.1957180323196668, -0.893782711064083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.253748187745712, 0.7478123549353348, 1.7894169406863398, -1.5619896511407834, -1.4525252844554515, -0.36588689044702444, 0.6063954373352898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4793171384805335, -0.4596614333567058, 0.03472380389854716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.606917364578337e-05, 0.1345024577316986, 0.047045703914178304, 0.0, 0.5317151132948059, -0.3474083367322327, -0.6611882050971059, 0.08244474612526588, 0.10775238585281527, -0.12182427513025361, -0.1649561857242356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.286658191861644, 0.11615585257928451, -0.20744913941004678, 0.14918418806990458, -0.09816663769171755, -0.027417565615715768, 0.19494940159575466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2067946119852808, -0.19290978523212576, -0.0037383533519975355]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998346517918872, 0.09141406724463508, 0.4712641065329575, 0.0, -0.3963772718905486, -0.17371562945071847, -2.2814760175244753, -1.219360925440738, -2.7002327508410016, -0.20256769550311668, -0.8997134077907735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.239329617790521, 0.7534266524824335, 1.7788887401772873, -1.5544474328996274, -1.4576573351045903, -0.3672799495537857, 0.6162389829320788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48965387642560615, -0.4693104482638417, 0.03440900117209651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.740580977579372e-05, 0.13839895934415067, 0.047116319050902106, 0.0, 0.5370343049768674, -0.31387748092048084, -0.629772638515227, 0.0956959237264568, 0.16371967468085852, -0.13699326366899722, -0.11861393453380784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28837139910381737, 0.11228595094197273, -0.21056401018104937, 0.15084436482312133, -0.1026410129827759, -0.027861182135225065, 0.19687091193577935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20673475890145315, -0.19298029814271903, -0.006296054529012879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998837262983027, 0.0984876371474542, 0.4736228512128817, 0.0, -0.36931688053387773, -0.18773598357623295, -2.3116213955634004, -1.2140251347964188, -2.6893801310269607, -0.21009366952295444, -0.903551021511901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2247864723311725, 0.7588446208607488, 1.7682046484249256, -1.5468142979099502, -1.463013101024749, -0.3687074540384244, 0.6261802995106079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49998676525617464, -0.47896382469304655, 0.03400803337286887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.814901283098824e-05, 0.14147139805638256, 0.04717489359848419, 0.0, 0.5412078271334178, -0.2804070825102892, -0.6029075607785047, 0.1067158128863861, 0.21705239628081968, -0.15051948039675508, -0.07675227442255034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2908629091869693, 0.10835936756630725, -0.21368183504723234, 0.1526626997935423, -0.1071153184031709, -0.028550089692774814, 0.1988263315705836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20665777661136933, -0.19306752858409676, -0.008019355984552914]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999333034850686, 0.105673669795564, 0.4759836606629676, 0.0, -0.3420989319308359, -0.2001784404608327, -2.3406676079286513, -1.2082366255708006, -2.676068847338364, -0.2181991233110978, -0.9055950446480462, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.210074347685301, 0.7640609965663732, 1.7573630303574068, -1.53907990480734, -1.4685941695923914, -0.3701801278166298, 0.636220089338161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5103153663581976, -0.4886219727508629, 0.03356302377694085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.915437353183409e-05, 0.14372065296219605, 0.047216189001717875, 0.0, 0.5443589720608369, -0.2488491376919947, -0.5809242473050138, 0.11577018451236276, 0.2662256737719409, -0.16210907576286726, -0.04088046272290302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2942424929174305, 0.10432751411248795, -0.2168323613503749, 0.1546878620522016, -0.11162137135285063, -0.02945347556410772, 0.2007957965510602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20657202204046005, -0.19316296115632664, -0.00890019191856041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999985724046607, 0.11296025548712392, 0.47834557029358193, 0.0, -0.314801405808413, -0.21118625359244553, -2.3685314160903346, -1.2018226217381398, -2.660668603774185, -0.2268306392523497, -0.906272283081831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.195169438262761, 0.7690689721673792, 1.746363206779349, -1.531232376173149, -1.474403504951756, -0.3717100360535933, 0.6463583943527268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5206393882958547, -0.49828517094116875, 0.03308743223331075]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010484112307689969, 0.1457317138311984, 0.04723819261228707, 0.0, 0.5459505224484582, -0.22015626263225668, -0.5572761632336668, 0.12828007665321645, 0.3080048712835719, -0.17263031882503777, -0.013544768675696726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.298098188450805, 0.10015951202012112, -0.21999647156115473, 0.15695057268381932, -0.11618670718729492, -0.030598164739270173, 0.20276610029131695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20648043875314065, -0.19326396380611774, -0.00951183087260194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000386188984348, 0.1203205677287292, 0.48070759131574803, 0.0, -0.287474989770132, -0.22085635045821775, -2.3954222793204267, -1.1948892232481507, -2.643436904418872, -0.23587381765469737, -0.9059314193362062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.180038166023946, 0.7738608510681475, 1.7352056038860497, -1.5232611904860027, -1.4804446693925655, -0.3733069528951633, 0.6565944608268954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5309588079582727, -0.5079534101611066, 0.032609806416965675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010578970365539403, 0.14720624483210576, 0.04724042044332186, 0.0, 0.5465283207656204, -0.19340193731544422, -0.5378172646018428, 0.1386679697997807, 0.34463398710626403, -0.18086356804695347, 0.006817274912495987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30262544477629516, 0.09583757801536633, -0.22315205786598608, 0.15942371374292477, -0.12082328881618842, -0.031938336831399336, 0.20472132948337274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063883932483591, -0.1933647843987567, -0.009552516326901475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000916494083057, 0.12770763567726107, 0.4830687392069244, 0.0, -0.26019308643958283, -0.22931048175714647, -2.4215463400455506, -1.1875815492128718, -2.6246036628231084, -0.24515225513938024, -0.9048815573555332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1647218529199097, 0.7783765005428815, 1.723859375416625, -1.5150999797468971, -1.486737404398827, -0.37496984157688623, 0.6669070107583583, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5412740650655505, -0.5176261007453624, 0.03217890689697536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010606101974169083, 0.1477413589706372, 0.04722295782352715, 0.0, 0.5456380666109822, -0.16908262597857465, -0.522481214502478, 0.1461534807055757, 0.37666483191527816, -0.1855687496936574, 0.020997239613460877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30632626208072616, 0.09031298949467995, -0.22692456938849484, 0.16322421478210972, -0.12585470012523042, -0.03325777363445849, 0.20625099862925758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20630514214555695, -0.19345381168511577, -0.008617990399806234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001438740509397, 0.13491240604240237, 0.4854280578776173, 0.0, -0.23325017153039881, -0.23668803750654724, -2.4469621100956136, -1.180043409121759, -2.604441923727538, -0.2542616803190728, -0.9034046231800951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1500139995816223, 0.7820642540186723, 1.711999903987663, -1.5061554522402196, -1.4934494542740804, -0.37658879725504163, 0.6770756911532064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5515865469940715, -0.5272662582455687, 0.03200561485251141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444928526822455, 0.1440954073028262, 0.04718637341385814, 0.0, 0.5388582981836805, -0.14755111498801532, -0.5083154010012589, 0.15076280182225638, 0.4032347819114077, -0.18218850359385164, 0.029538683508763354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2941570667657477, 0.07375506951581443, -0.23718942857923855, 0.17889055013354835, -0.13424099750506613, -0.03237911356310805, 0.20337360789696188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2062496385704195, -0.1928031500041254, -0.0034658408892790024]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001956923917136, 0.14209490819490286, 0.48778483406484985, 0.0, -0.20719014955641507, -0.2431537045007487, -2.4717559018778976, -1.1723466381173246, -2.5832851837647595, -0.26272698890159707, -0.9018119287954139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1362925875347156, 0.7846942107354439, 1.6995945594881667, -1.4962533594938423, -1.500654434469294, -0.37804175814020746, 0.6869377230363743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5618772554935478, -0.5362481924237863, 0.03193009384487926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001036366815479113, 0.14365004305001008, 0.047135523744650826, 0.0, 0.5212004394796748, -0.12931333988402918, -0.4958758356456816, 0.15393542008868819, 0.42313479925557457, -0.16930617165048542, 0.031853887693621664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2744282409381327, 0.052599134335431535, -0.24810688998992422, 0.1980418549275443, -0.1440996039042721, -0.029059217703316893, 0.1972406376633577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20581416998952623, -0.17963868356435048, -0.001510420152642911]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20002491398495875, 0.1494178801698363, 0.49014213867983025, 0.0, -0.18248615642303045, -0.24874252779424932, -2.495791256850934, -1.1643342319297219, -2.561549609322388, -0.27017462278306265, -0.9004516927928198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1235910388524077, 0.7862627988346579, 1.686786930289798, -1.4854969415594632, -1.5083462475227143, -0.3792270963843562, 0.6964032961833078, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5721284937799476, -0.544042023523245, 0.03174277720679715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010689491574809543, 0.14645943949866824, 0.047146092299607985, 0.0, 0.494079862667692, -0.11177646587001251, -0.4807070994607294, 0.1602481237520551, 0.43471148884742883, -0.14895267762931144, 0.027204720051883843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25403097364615596, 0.031371761984279836, -0.2561525839673737, 0.21512835868758007, -0.15383626106840426, -0.023706764882974334, 0.1893114629386691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2050247657279953, -0.15587662198917399, -0.00374633276164229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000302436587149, 0.1568804363366327, 0.4925089959261279, 0.0, -0.15942620646426864, -0.2535716429058741, -2.5191037233799887, -1.1561081590561926, -2.5395311185199434, -0.2762882019431225, -0.8995733094187667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1117286539701878, 0.7868744141902151, 1.6737792940401723, -1.474100709544747, -1.5164731868474546, -0.3800749465354888, 0.705439711141863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.582334625025694, -0.5505038053914475, 0.031328551739566904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010659347512320952, 0.14925112333592852, 0.04733714492595309, 0.0, 0.46119899917523643, -0.09658230223249553, -0.4662493305810919, 0.16452145747058344, 0.4403698160488929, -0.12227158320119691, 0.017567667481062112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23724769764439968, 0.012232307111143079, -0.26015272499251113, 0.2279246402943277, -0.16253878649480763, -0.016957003022651775, 0.1807282991711045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.204122624914929, -0.12923563736404983, -0.008284509344604833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000355409762551, 0.1643493632969471, 0.4948989781480506, 0.0, -0.138134306608576, -0.25778286324663996, -2.541755761063006, -1.1478203450866038, -2.517453701537978, -0.2808626769029118, -0.8993496529219878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1004377528853015, 0.7866677740581992, 1.6607635289911855, -1.4622859299485154, -1.5249653079719356, -0.38055155981383115, 0.7140521457823096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5924971178994362, -0.5556901650508949, 0.03066177407118626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010594635080377414, 0.14937853920628794, 0.047799644438453984, 0.0, 0.42583799711385245, -0.08422440681531787, -0.45304075366034996, 0.16575627939177673, 0.4415483396393033, -0.09148949919578589, 0.00447312993557779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22581802169772486, -0.004132802640316704, -0.2603153009797381, 0.2362955919246301, -0.16984242248962297, -0.00953226556684723, 0.17224869280893232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324985747484237, -0.1037271931889466, -0.01333555336761289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004081292641204, 0.17163111684490254, 0.4973273540293955, 0.0, -0.11861098806654552, -0.261506003937954, -2.563792455725704, -1.1396190617008346, -2.4954889007469143, -0.2838319038624897, -0.8998890469110882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0894421809363275, 0.7857788657157315, 1.6478909021820578, -1.4502320834056803, -1.5337515051369732, -0.3806565744431942, 0.7222674722419069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6026210959822068, -0.559746501253625, 0.029776897416194534]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010543900313926698, 0.14563507095910855, 0.048567517626897164, 0.0, 0.3904663708406098, -0.0744628138262803, -0.44073389325396295, 0.1640256677153848, 0.4392960158212723, -0.059384539191558075, -0.010787879782008984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21991143897947918, -0.017778166849353613, -0.2574525361825549, 0.2410769308567017, -0.17572394330075108, -0.0021002925872602293, 0.16430652919194655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20247956165541275, -0.08112672405460414, -0.01769753309983457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004606432832564, 0.1785368757147403, 0.4998084022537411, 0.0, -0.10078082637104352, -0.264847160038961, -2.5852379440488384, -1.131630598596612, -2.4737657902986205, -0.28524416183276086, -0.9012452613483256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.078500262559309, 0.7843260714150962, 1.6352650158000486, -1.4380627524161154, -1.5427684175926506, -0.3804169066440311, 0.7301226067745017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6127129574718959, -0.5628429113478618, 0.028737698239593924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001050280382721323, 0.1381151773967553, 0.04962096448691232, 0.0, 0.35660323391003995, -0.06682312202014098, -0.4289097664626888, 0.15976926208445047, 0.43446220896587195, -0.02824515940542372, -0.027124288744748738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21883836754036934, -0.029055886012705798, -0.2525177276401867, 0.24338661979130038, -0.1803382491135461, 0.004793355983261567, 0.1571026906518956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20183722979378182, -0.06192820188473633, -0.020783983532012218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005129930180776, 0.1849245954383537, 0.5023535969404489, 0.0, -0.0845365476780033, -0.26789192708329723, -2.606108693073243, -1.1239444492086228, -2.452378330247755, -0.2852004259172213, -0.903428031037695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0674226840202274, 0.7824081342080057, 1.6229472251942958, -1.4258507451503226, -1.5519634683297958, -0.3798798984965973, 0.7376575659920607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6227788903479773, -0.5651382965458367, 0.027612209173982813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010469946964228746, 0.12775439447226813, 0.05090389373415543, 0.0, 0.32488557386080436, -0.06089534088672406, -0.4174149804880978, 0.1537229877597814, 0.42774920101731634, 0.0008747183107913163, -0.04365539378738713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22155157078163232, -0.038358744141811715, -0.24635581211505642, 0.24424014531585422, -0.18390101474290552, 0.010740162948676057, 0.15069918435117943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2013186575216267, -0.0459077039594976, -0.02250978131222222]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005652136933838, 0.1907115542078159, 0.5049708022133425, 0.0, -0.06976173780440523, -0.27070753685227544, -2.6264208198234114, -1.116616946684467, -2.4313907896673914, -0.2838218803566358, -0.906412585221189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0560736135802962, 0.7801058082827312, 1.6109657132036308, -1.4136290432962257, -1.5612950664604608, -0.37910605441542466, 0.7449113819247415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6328242153560852, -0.5667667343942321, 0.026461026087480004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444135061213921, 0.1157391753892438, 0.052344105457870035, 0.0, 0.29549619747196143, -0.05631219537956404, -0.40624253500336754, 0.14655005048311465, 0.4197508116072699, 0.02757091121170977, -0.05969108366987838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22698140879862486, -0.046046518505490075, -0.23963023981329837, 0.24443403708193845, -0.18663196261329876, 0.015476881623452673, 0.14507631865361617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200906500162158, -0.032568756967906835, -0.023023661730056176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006173377981204, 0.19586946360562876, 0.5076644609626558, 0.0, -0.05634179204398947, -0.27334548158613015, -2.646193322366273, -1.1096790839813315, -2.410842927702957, -0.2812329746831892, -0.9101485177967618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0443638223042633, 0.7774845919923008, 1.5993249042842526, -1.4014024614291, -1.570731417155611, -0.3781624858127281, 0.751920026015881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6428532286355354, -0.5678352846961159, 0.025332638215552584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010424820947313969, 0.10315818795625725, 0.05387317498626852, 0.0, 0.26839891520831505, -0.05275889467709448, -0.3954500508572305, 0.138757254062713, 0.4109572392886899, 0.051778113468932276, -0.07471865151145703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23419582552065923, -0.05242432580860899, -0.23281617838756566, 0.24453163734251182, -0.1887270139030052, 0.018871372053931603, 0.14017288182279053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005802655890033, -0.02137100603767564, -0.02256775743854842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006693974018563, 0.20041148659983554, 0.5104356354131638, 0.0, -0.04416856961827303, -0.2758444403769414, -2.6654490711305923, -1.103143801672166, -2.3907551627710806, -0.2775528776658062, -0.9145677909379701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.032240873995808, 0.7745974410638581, 1.588013709038981, -1.3891577880418844, -1.5802488161344124, -0.37711757562047643, 0.7587156306949181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6528692669109263, -0.5684268272253782, 0.024262524580118537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010411920747207684, 0.09084045988413576, 0.0554234890101607, 0.0, 0.24346444851432894, -0.049979175816224464, -0.3851149752863885, 0.1307056461833094, 0.4017552986375233, 0.07360194034765936, -0.08838546282416829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2424589661691047, -0.05774301856885468, -0.2262239049054323, 0.24489346774431225, -0.19034797957602634, 0.020898203845033683, 0.13591209358074058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032076550781866, -0.011830850585245457, -0.02140227270868092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007214257134473, 0.2043774343813399, 0.5132834444778108, 0.0, -0.033141879221293254, -0.27823311442357535, -2.684214783748266, -1.0970116831686958, -2.3711334911723347, -0.27289151361168223, -0.9195916030855968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0196792372387637, 0.7714870996542419, 1.577012080120262, -1.3768717128358068, -1.5898299178620672, -0.376037003117718, 0.7653264677326032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6628748614477549, -0.5686045085855391, 0.023274225345194223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010405662318178713, 0.07931895563008712, 0.05695618129293898, 0.0, 0.22053380793959546, -0.04777348093267944, -0.3753142523534738, 0.12264237006940129, 0.3924334319749157, 0.09322728108248012, -0.10047624295253367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.251232735140885, -0.06220682819232286, -0.22003257837437873, 0.24572150412155103, -0.191622034553094, 0.02161145005516844, 0.13221674075370154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001118907365725, -0.003553627203219339, -0.019765984698486314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007734580778586, 0.20782070618049545, 0.5162057356413299, 0.0, -0.02316952921589255, -0.2805327086574647, -2.7025206472294165, -1.0912751301891823, -2.3519738846130913, -0.26734808709481267, -0.9251359659670314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0066716891018626, 0.7681879876718668, 1.5662958363212114, -1.364516539676587, -1.5994622264425942, -0.3749810550619353, 0.7717773035049438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728719094996554, -0.5684161418783988, 0.022381311534141354]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010406472882246143, 0.06886543598311097, 0.0584458232703806, 0.0, 0.19944700010801403, -0.04599188467778787, -0.36611726962300406, 0.11473105959026818, 0.3831921311848679, 0.11086853033739165, -0.11088725762869056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26015096273802274, -0.06598223964750083, -0.21432487598101155, 0.24710346318439644, -0.19264617161054026, 0.021118961115654065, 0.1290167154468116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994096103801032, 0.003767334142805944, -0.017858276221057384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008255327007832, 0.2107984551058236, 0.5192101868201725, 0.0, -0.014166840177746965, -0.2827589651423013, -2.7203998728202277, -1.085921389661834, -2.333265997210729, -0.2610109256209237, -0.9311159707638332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.993222525276789, 0.76472770791297, 1.5558399599130788, -1.3520640084958147, -1.609136898369661, -0.3740030351449078, 0.7780898891731596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6828618146769264, -0.5678979208460078, 0.02158961746419203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010414924584927073, 0.059554978506562724, 0.060089023576853036, 0.0, 0.18005378076291173, -0.044525129696731926, -0.35758451181622114, 0.10707481054696666, 0.3741577480472417, 0.12674322947777925, -0.11960009593603711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2689832765014719, -0.06920559517793774, -0.2091175281626519, 0.24905062361544741, -0.19349343854133583, 0.01956039834054967, 0.12625171336431662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19979810354541996, 0.01036442064782242, -0.015833881398986463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008787845500087, 0.21333432017666262, 0.522278620524105, 0.0, -0.005963419259842758, -0.2847067784692105, -2.737706908660592, -1.0808938141815105, -2.3150267722676117, -0.25438667800412285, -0.9374635516762867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9793618168468088, 0.7611051078601969, 1.545609423592007, -1.3394608678986315, -1.6188542055022237, -0.3731361931769705, 0.784273511539081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6928467960164502, -0.5671346529160782, 0.02093020073211555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010650369845106335, 0.050717301416780575, 0.06136867407865102, 0.0, 0.16406841835808414, -0.038956266538184035, -0.34614071680728536, 0.10055150960646979, 0.3647844988623467, 0.13248495233601743, -0.12695161824906995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27721416859960457, -0.07245200105546167, -0.20461072642143427, 0.2520628119436626, -0.194346142651256, 0.01733683935874627, 0.12367244731842914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19969962679047468, 0.015265358598590295, -0.013188334641529539]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000932460772157, 0.2154911957901415, 0.5254075520960675, 0.0, 0.0015154044261366864, -0.28641516619292723, -2.7544320930412285, -1.076174171725622, -2.2972498271597006, -0.24759982073920533, -0.9441141009023792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9651278873460428, 0.757327427091728, 1.535580448860818, -1.326672138264618, -1.628612812424153, -0.37240896197700574, 0.7903376336523634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7028278828753675, -0.5661656331890602, 0.020389486558202795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010735244429674809, 0.04313751226957778, 0.0625786314392504, 0.0, 0.14957647371958888, -0.03416775447433472, -0.33450368761273663, 0.09439284911777152, 0.35553890215822376, 0.13573714529835043, -0.13301098452185098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2846785900153182, -0.07555361536937943, -0.20057949462378213, 0.25577459268027014, -0.19517213843858824, 0.01454462399929483, 0.12128244226564817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.199621737178345, 0.019380394540359974, -0.010814283478255146]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000986504638207, 0.2173348800863795, 0.5285963538711298, 0.0, 0.008311286985787932, -0.2879703140158385, -2.770613356296178, -1.071752895513645, -2.2799188962291113, -0.24064150349451635, -0.9510100879683961, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9505529498723302, 0.7534056826233598, 1.5257378740419243, -1.3136770586139697, -1.63841007581735, -0.37184397678607, 0.7962921332243709, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7128055169800916, -0.5650064298475672, 0.019945411914984862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010808773209972387, 0.036873685924759945, 0.06377603550124566, 0.0, 0.13591765119302487, -0.031102956458224976, -0.32362526509899225, 0.08842552423953609, 0.3466186186117867, 0.13916634489377944, -0.13791974132033838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2914987494742535, -0.07843488936736323, -0.19685149637787305, 0.25990159301296684, -0.19594526786394395, 0.011299703818714464, 0.11908999144014908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19955268209448396, 0.023184066829859785, -0.008881492864358671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001040952281578, 0.21892164502751066, 0.5318443998538492, 0.0, 0.014455434372994066, -0.2894449297458632, -2.7863038589103057, -1.0676217341506595, -2.263014026217533, -0.23346849295648808, -0.9581014231716674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9356598942300804, 0.7493518268839664, 1.5160721145437042, -1.3004642700198759, -1.6482428027961602, -0.37145864779806914, 0.8021471910765554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7227798395497232, -0.5636600458570635, 0.019578016659266558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010889528674247463, 0.03173529882262352, 0.0649609196543887, 0.0, 0.12288294774412264, -0.029492314600493903, -0.313810052282559, 0.08262322725971165, 0.33809740023156404, 0.14346021076056528, -0.14182670406542525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2978611128449939, -0.08107711478786886, -0.19331518996440414, 0.2642557718818771, -0.19665453957620216, 0.007706579760017614, 0.11710115704369055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19948645139263124, 0.026927679810074084, -0.007347905114366092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001095818476272, 0.2202943968225748, 0.535150869996002, 0.0, 0.019976112404964497, -0.2908868408754237, -2.801560742506763, -1.0637723948338313, -2.246514853532375, -0.2260387914595803, -0.9653442577370467, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9204627132754218, 0.7451771967137655, 1.5065767335510407, -1.2870279213106035, -1.6581079764407811, -0.3712661111733493, 0.8079130441774274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7327508384249672, -0.5621229025816208, 0.01927182718937029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010973238938801623, 0.027455035901282798, 0.06612940284305621, 0.0, 0.11041356063940856, -0.028838222591209578, -0.3051376719291418, 0.07698678633656415, 0.3299834537031666, 0.1485940299381555, -0.14485669130758602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3039436190931732, -0.08349260340401757, -0.189907619853269, 0.26872697418544794, -0.19730347289241743, 0.003850732494397405, 0.11531706201743988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19941997750488044, 0.030742865508854446, -0.0061237893979253916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20011511096299092, 0.2214825190671099, 0.5385151065100857, 0.0, 0.02490084713840034, -0.2923229338625861, -2.8164412711336357, -1.060196351782816, -2.2304025030501005, -0.21832156697497618, -0.9726993825050722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9049681306376484, 0.740891755553815, 1.4972467377444765, -1.2733648666517141, -1.6680033011218867, -0.3712761292836445, 0.8135997040895893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7427184266565153, -0.560388285861029, 0.019015717754810958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011058230727444141, 0.023762444890702263, 0.06728473028167319, 0.0, 0.09849469466871684, -0.028721859743248285, -0.2976105725374558, 0.07152086102030841, 0.32224700964548914, 0.15434448969208248, -0.14710249536050946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30989165275546887, -0.08570882319900835, -0.1865999161312844, 0.27326109317778985, -0.19790649362210908, -0.00020036220590430396, 0.11373319824323874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935176463096194, 0.03469233441183588, -0.0051221886911865955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012068354139295, 0.22250349531401678, 0.5419369045324964, 0.0, 0.029256928531896972, -0.29376602433815924, -2.8310013768663658, -1.0568847414431133, -2.2146607151661373, -0.21029745116627052, -0.9801307890007165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8891775148909307, 0.7365037811966567, 1.4880774850525833, -1.2594727666522887, -1.677927543943993, -0.37149579637202673, 0.8192166918784729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.752682486082162, -0.5584484377725315, 0.018802084615086322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011145156804087516, 0.020419524938137586, 0.06843596044821347, 0.0, 0.08712162786993259, -0.02886180951146266, -0.2912021146546042, 0.06623220679405235, 0.3148357576792621, 0.1604823161741131, -0.14862812991288768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3158123149343549, -0.08775948714316552, -0.18338505383786374, 0.2778419999885099, -0.19848485644212302, -0.00439334176764448, 0.112339755777672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19928118851293328, 0.0387969617699493, -0.004272662794492707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012628164617755, 0.22332134060079772, 0.54541662471814, 0.0, 0.03317120156856523, -0.29518464960895535, -2.8451380890300952, -1.053961604220274, -2.1992726208632316, -0.20265878664500153, -0.9876002580722529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8730997429735209, 0.7319946575093498, 1.4790548783712623, -1.2453195416574887, -1.687887002196704, -0.37191213155652425, 0.8247616904031708, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7626439397110358, -0.556356609092534, 0.018669902169850008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001119620956917603, 0.01635690573561878, 0.06959440371287186, 0.0, 0.07828546073336504, -0.02837250541592201, -0.282734243274592, 0.05846274445678641, 0.30776188605811694, 0.15277329042537996, -0.14938938143072922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32155543834819605, -0.0901824737461377, -0.18045213362641968, 0.28306449989600013, -0.1991891650542251, -0.00832670368995064, 0.11089997049395796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19922907257747532, 0.04183657359994846, -0.002643648904726283]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013192442139177, 0.2239482275425103, 0.5489548371269524, 0.0, 0.0366715792278375, -0.296586524353173, -2.8588493933976524, -1.0514203929343469, -2.184236114366281, -0.1954379262848652, -0.9950902730344263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8567527786674105, 0.7273588576734159, 1.4701719485389229, -1.230888881533351, -1.6978848911636142, -0.37251543196268055, 0.8302341701041117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7726029312808944, -0.5541258337645512, 0.018610119682379557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001128555042845191, 0.0125377388342514, 0.07076424817624641, 0.0, 0.07000755318544544, -0.028037494884353635, -0.27422608735114595, 0.050824225718544155, 0.3007301299390082, 0.14441720720272663, -0.1498002992434688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32693928612220846, -0.09271599671867779, -0.17765859664678813, 0.28861320248275546, -0.1999577793382039, -0.012066008123126602, 0.1094495940188172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917983139717088, 0.044615506559656834, -0.0011956497494090225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013761457522716, 0.22440734591479483, 0.5525510066268541, 0.0, 0.03975911638397082, -0.29798216934315713, -2.8721656295211786, -1.0492191300271183, -2.1695526216527776, -0.18848173123026996, -1.0025971718647806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8401509814292484, 0.7225974376254728, 1.461426296142665, -1.2161747018287186, -1.7079221563356972, -0.3732971774069232, 0.8356348772421495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7825592728935553, -0.5517519790258053, 0.018604268532772555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011380307670761093, 0.009182367445690917, 0.07192338999803456, 0.0, 0.06175074312266636, -0.027912899799682093, -0.2663247224705193, 0.044025258144572164, 0.29366985427007, 0.13912390109190506, -0.15013797660708325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3320359447632418, -0.09522840095886133, -0.17491304792515783, 0.2942835940926487, -0.20074530344166105, -0.01563490888485266, 0.1080141427607551, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19912683225321814, 0.04747709477491714, -0.00011702299214006178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014335289543783, 0.22472031035488813, 0.5562052394000923, 0.0, 0.042430718224349184, -0.2993775663249582, -2.885124494559544, -1.0473129015067846, -2.155222804147192, -0.1816201348745458, -1.01012474190697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8233031935612874, 0.7177142448998596, 1.4528175204778178, -1.2011759013625687, -1.7179983908228533, -0.374249479327445, 0.8409652330108597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925126832685195, -0.5492244957458804, 0.018635373875526565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011476640421320383, 0.006259288801865879, 0.07308465546476407, 0.0, 0.05343203680756739, -0.027907939636021756, -0.25917730076730283, 0.03812457040667647, 0.28659635011170964, 0.13723192711448282, -0.1505514008437909, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.33695575735921823, -0.09766385451226353, -0.17217551329694306, 0.2999760093229975, -0.2015246897431223, -0.019046038410436672, 0.10660711537420353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906820749928394, 0.05054966559849752, 0.0006221068550801514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014914122512492, 0.22490281905863652, 0.5599181172915517, 0.0, 0.044685009011025914, -0.3007746371064331, -2.897763192892381, -1.0456630527405861, -2.1412454289020606, -0.1747151974114972, -1.0176787139885983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8062133777782159, 0.7127138428914443, 1.4443454795666644, -1.1858927542576552, -1.7281125254817933, -0.37536492761112034, 0.8462267964200866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8024628663707979, -0.5465312346100106, 0.018690277971370874]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011576659374156097, 0.0036501740749680742, 0.0742575578291891, 0.0, 0.04508581573353464, -0.027941415629497295, -0.25277396665674096, 0.03299697532397076, 0.2795475049026293, 0.13809874926097254, -0.15107944163256468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3417963156614319, -0.100008040168305, -0.1694408182230674, 0.30566294209827055, -0.20228269317880074, -0.022308965673506504, 0.10523126818453868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1990036620455675, 0.05386522271739528, 0.0010980819168861728]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20015498241295324, 0.22496358788852341, 0.5636906952949815, 0.0, 0.046523124895129254, -0.30217304171259973, -2.910116870810712, -1.0442383548647112, -2.127617660175425, -0.16766711338600437, -1.025262800625812, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7888816327849963, 0.7076004604520697, 1.4360093419839672, -1.170324783273599, -1.7382632426248827, -0.3766364801543263, 0.8514208330493006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8124095464110179, -0.5436605129536562, 0.018759558823811803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011682375656639517, 0.0012153765977381483, 0.0754515600685947, 0.0, 0.036762317682066795, -0.027968092123332625, -0.2470735583666168, 0.028493957517499034, 0.2725553745327172, 0.1409616805098563, -0.15168173274427474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3466348998643898, -0.10226764878749364, -0.16672275165394146, 0.31135941968112435, -0.20301434286178807, -0.02543105086411955, 0.10388073258428018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19893360080440123, 0.05741443312708689, 0.0013856170488185833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001608631206162, 0.22486724977568132, 0.5675244651508963, 0.0, 0.04804091382447449, -0.3035412422848025, -2.922052328864245, -1.043124700167149, -2.114336383673618, -0.16144541042735452, -1.0328762966158225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7713251667984461, 0.7023538524834112, 1.4278003950431948, -1.1544406355268644, -1.7484541924423087, -0.3780359169281584, 0.8565366409104427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8223535527855577, -0.5406644830067112, 0.018874481121896925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011761415325926333, -0.0019267622568418198, 0.0766753971182944, 0.0, 0.030355778586904754, -0.02736401144405591, -0.23870916107066367, 0.022273093951243095, 0.2656255300361335, 0.1244340591729968, -0.15226991980021082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35112931973100436, -0.10493215937317057, -0.16417893881545068, 0.3176829549346932, -0.20381899634852044, -0.02798873547664122, 0.1023161572228418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19888012749079415, 0.05992059893890097, 0.0022984459617024834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20016679470852397, 0.22461810660336734, 0.5714204886721297, 0.0, 0.0492515606625755, -0.3048795567549562, -2.9335321144560953, -1.0423074447214344, -2.10140738073954, -0.15596642624339424, -1.0405372644415392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7535642511419999, 0.6969653494000717, 1.4197151124779401, -1.1382226627253809, -1.7586848946400433, -0.37953926699620993, 0.8615644584658677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8322950464256667, -0.5375590699744391, 0.019029445546714298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011863175815503065, -0.0049828634462796215, 0.0779204704246687, 0.0, 0.024212936762020215, -0.026766289403073663, -0.229595711837008, 0.01634510891429119, 0.25858005868156314, 0.1095796836792056, -0.15321935651433463, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3552183131289241, -0.10777006166679028, -0.16170565130509318, 0.3243594560296713, -0.2046140439546916, -0.030067001361030556, 0.10055635110850149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1988298728021799, 0.06210826064544102, 0.003099288496347424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200172776239212, 0.2242322692592346, 0.5753793197616183, 0.0, 0.050143828812840734, -0.3061910582581071, -2.944550534505061, -1.041743376056535, -2.0888357341121013, -0.15093367718695333, -1.048277236264781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7356141941268067, 0.691432512186373, 1.4117532741877563, -1.121661763852356, -1.7689514159459603, -0.3811251082443771, 0.86649506189296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8422339086677469, -0.5343440199178914, 0.019210896739374525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001196306137608304, -0.007716746882654741, 0.07917662178977203, 0.0, 0.0178453630053046, -0.026230030063017495, -0.2203684009793198, 0.011281373297985921, 0.25143293254877075, 0.1006549811288182, -0.15479943646483557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3590011403038624, -0.11065674427397341, -0.15923676580367516, 0.3312179774604951, -0.2053304261183416, -0.031716824963344104, 0.09861206854184656, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19877724484160614, 0.06430100113095442, 0.003629023853204522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017880771966834, 0.2237276625238269, 0.5794013303291399, 0.0, 0.050699909006210096, -0.30747661967759615, -2.9551116517246165, -1.0413867886406278, -2.0766216597974223, -0.14608404137141487, -1.0561326296271798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7174848001385788, 0.6857562710597147, 1.4039161304800842, -1.10475315105645, -1.7792470152797084, -0.3827741958966008, 0.871319355442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8521699154814953, -0.5310119017509993, 0.01940522188486421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012062960912663622, -0.01009213470815384, 0.08044021135043324, 0.0, 0.011121603867387315, -0.025711228389780374, -0.21122234439110926, 0.007131748318146876, 0.2442814862935846, 0.09699271631076936, -0.1571078672479778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36258787976455753, -0.11352482253316624, -0.1567428741534436, 0.33817225591812267, -0.20591198667496285, -0.032981753044473566, 0.0964858709840395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.198720136274969, 0.06664236333784118, 0.0038865029097937334]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001848920125801, 0.22311939837896405, 0.5834870489289138, 0.0, 0.05090078540002527, -0.308735882796434, -2.9652229966883774, -1.0411980034684942, -2.064759670416598, -0.14123323192581774, -1.0641371565315465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6991809830148032, 0.679939291147258, 1.3962051220839664, -1.087493451223696, -1.7895626538601601, -0.3844693487373193, 0.8760279613648302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8621028082079024, -0.5275522348262791, 0.01960080649115936]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012168585823553865, -0.012165282897256904, 0.08171437199547749, 0.0, 0.004017527876303342, -0.025185262376756567, -0.2022268992752162, 0.0037757034426703215, 0.23723978761649236, 0.09701618891194237, -0.16009053808733326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3660763424755128, -0.1163395982491342, -0.15422016792235796, 0.34519399665507955, -0.2063127716090326, -0.03390305681437007, 0.09417211845336478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19865785452814178, 0.06919333849440365, 0.003911692125903012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001910339768254, 0.22241740746155528, 0.5876373692829787, 0.0, 0.05072825256032961, -0.3099686862518699, -2.9748947407521658, -1.0411450762759276, -2.0532395768694993, -0.13626393879654164, -1.0723170910833948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6807032804433021, 0.6739849745819401, 1.388621114169803, -1.0698788282800074, -1.7998873562412572, -0.3861952801931571, 0.8806108106665858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8720323358314703, -0.5239535080029184, 0.019788621026410307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012283928490566007, -0.014039818348175664, 0.083006407081299, 0.0, -0.0034506567939130836, -0.024656069108718866, -0.19343488127577046, 0.0010585438513315741, 0.2304018709419729, 0.09938586258552179, -0.1635986910369645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3695540514300244, -0.1190863313063596, -0.15168015828326817, 0.3522924588737728, -0.20649404762193996, -0.03451862911675506, 0.09165698603511138, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19859055247135768, 0.07197453646721513, 0.0037562907050189094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001972276229123, 0.22160015992593438, 0.5918536565550914, 0.0, 0.05023534327615232, -0.31115485912438157, -2.98399731890119, -1.0412776896283897, -2.0420522122641835, -0.1323673535576393, -1.08069297108184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6620730424338469, 0.6678791574614724, 1.3811606617335281, -1.0518815424837384, -1.8102108812872644, -0.3879171685167433, 0.8850471905233438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8819592391097035, -0.5202568933142251, 0.019987756381997294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012387292173853077, -0.016344950712418115, 0.08432574544225284, 0.0, -0.00985818568354585, -0.023723457450233045, -0.1820515629804796, -0.0026522670492431072, 0.22374729210631697, 0.07793170477804703, -0.16751759996890506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3726047601891036, -0.12211634240935253, -0.1492090487254995, 0.35994571592537883, -0.2064705009201449, -0.034437766471724654, 0.08872759713516082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853806556466372, 0.07393229377386722, 0.0039827071117397314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20020347439010194, 0.22066886640840974, 0.5961368789821828, 0.0, 0.04942137616753238, -0.3122911282120764, -2.9924717451619225, -1.0415807058060549, -2.0311924115217646, -0.12926459359144046, -1.0893046900564256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6433087343387187, 0.6616151695062485, 1.3738233634988397, -1.0334828954614335, -1.820518215348053, -0.3896034935502784, 0.8893152917455368, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918837518366295, -0.5164777926262232, 0.020196315181244682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001249353437924127, -0.018625870350492735, 0.0856644485418279, 0.0, -0.0162793421723988, -0.0227253817538959, -0.1694885252146481, -0.0060603235533009635, 0.21719601484837767, 0.06205519932397649, -0.17223437949171228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3752861619025646, -0.12527975910447817, -0.1467459646937689, 0.36797294044609824, -0.20614668121577498, -0.03372650067070167, 0.08536202444386097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984902545385202, 0.07558201376003792, 0.004171175984947794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002097713156489, 0.21963330701260128, 0.6004876430588264, 0.0, 0.04826735161790908, -0.31337521052871675, -3.0002854311434213, -1.042017856951844, -2.020651124882025, -0.12654774583476963, -1.0982068765058308, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6244231401634923, 0.6551909860127477, 1.3666107181270413, -1.014669781954262, -1.830789814952071, -0.3912255494765068, 0.8933920015145673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9018058862955415, -0.5126188329621287, 0.020406874864572447]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001259385109389794, -0.020711187916169344, 0.08701528153287227, 0.0, -0.023080490992466042, -0.021681646332807118, -0.1562737196299728, -0.008743022915782392, 0.21082573279478972, 0.054336955133416694, -0.17804372898810442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37771188350452867, -0.12848366987001567, -0.14425290743596728, 0.3762622701434281, -0.2054319920803594, -0.032441118524568074, 0.08153419538060984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19844268917823923, 0.07717919328188974, 0.004211193666555281]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021612092282184, 0.21850629281013784, 0.6049063830180879, 0.0, 0.04674694556987107, -0.3144054031470295, -3.0074185370116227, -1.0425507553929605, -2.010411408134718, -0.12394384477934386, -1.1074574531963899, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6054236679376318, 0.6486078022609617, 1.3595250401006225, -0.9954321389298569, -1.8410018235275876, -0.3927577856739413, 0.897252692534199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9117255410177183, -0.5086754720012359, 0.020610626904816205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001269921434586169, -0.022540284049268652, 0.08837479918522834, 0.0, -0.030408120960760072, -0.02060385236625595, -0.1426621173640283, -0.01065796882233028, 0.20479433494613986, 0.052078021108515345, -0.18501153381118132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37998944451720995, -0.1316636750357197, -0.1417135605283744, 0.38475286048810226, -0.20424017151033333, -0.030644723948690555, 0.07721382039263426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19839309444353564, 0.07886721921785816, 0.004075040804875125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022253027785625, 0.2172997061063792, 0.6093940275144712, 0.0, 0.044831410138811985, -0.31538213075779564, -3.0138605032598287, -1.0431464819052012, -2.0004478758145035, -0.12130496351048073, -1.1171087473807155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5863125474238096, 0.6418689300364602, 1.3525686390384142, -0.975760852223192, -1.8511263198677277, -0.3941779859496728, 0.9008708398699348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9216425579681401, -0.5046390286167527, 0.020799215252272733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012818710068790215, -0.024131734075172735, 0.08975288992766754, 0.0, -0.03831070862118175, -0.01953455221532188, -0.12883932496411699, -0.011914530244816071, 0.19927064640429257, 0.05277762537726262, -0.1930258836865146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38222241027644466, -0.13477744449003068, -0.13912802124416684, 0.39342573413329984, -0.20248992680280403, -0.02840400551462917, 0.07236294671471433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19834033900843503, 0.08072886768966328, 0.0037717669491305742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022900860672177, 0.21602149077378158, 0.6139508566643666, 0.0, 0.04249304529260065, -0.3163082802897171, -3.019609641149978, -1.0437794882828788, -1.9907280811770776, -0.11855834742913957, -1.127203397503628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56708689339683, 0.6349787981933329, 1.3457432785905576, -0.9556459545254953, -1.8611315315344155, -0.39546708486206655, 0.9042174428273831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9315567687691604, -0.5004987690426352, 0.020966024033625068]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012956657731027664, -0.02556430665195258, 0.09113658299790565, 0.0, -0.04676729692422672, -0.01852299063842921, -0.11498275780298244, -0.012660127553552256, 0.1943958927485175, 0.054932321626823176, -0.20189300245824846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38451308053959093, -0.13780263686254624, -0.136507208957131, 0.4022979539539349, -0.20010423333375432, -0.02578197824787499, 0.06693205914896853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982842160204063, 0.08280519148234991, 0.003336175627046675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20023567613729168, 0.21468232598148812, 0.618579669380404, 0.0, 0.039716685832498946, -0.3170317589450412, -3.0246594038591277, -1.0443415770723183, -1.9812217011084206, -0.11567135386636834, -1.13777905015814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477513703633965, 0.6279428756470102, 1.3390496574407549, -0.9350758302929199, -1.8709811549442146, -0.39660843413451846, 0.9072602766909373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9414681136338643, -0.49624739219259395, 0.02109857982582755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013335061139804465, -0.02678329584586907, 0.09257625432074831, 0.0, -0.05552718920203407, -0.014469573106482808, -0.1009952541829951, -0.011241775788790789, 0.19012760137314005, 0.05773987125542451, -0.21151305309023985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3867104606686719, -0.14071845092645366, -0.13387242299605406, 0.4114024846515084, -0.1969924681959818, -0.022826985449038478, 0.06085667727108461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982268972940784, 0.08502753700082558, 0.0026511158440496816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024248448796664, 0.2132817010339462, 0.6232850539165122, 0.0, 0.03648736491123274, -0.3176151113242534, -3.029022659188296, -1.0448138848933215, -1.9718877847713319, -0.11262628356749618, -1.1488617258468545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.52829997285123, 0.6207655905849384, 1.332488202871619, -0.914035823072634, -1.8806351577949825, -0.39758655139198784, 0.909962810616463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.951376543075006, -0.49187641030852547, 0.02119267081108958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013616701349902424, -0.028012498950838564, 0.0941076907221639, 0.0, -0.06458641842532403, -0.011667047584244146, -0.08726510658336331, -0.009446156420062756, 0.1866783267417718, 0.060901405977443104, -0.2216535137742917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3890279502433304, -0.1435457012414359, -0.1312290913827172, 0.42080014440571706, -0.19308005701535966, -0.01956234514938717, 0.054050678510513796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19816858882283422, 0.08741963768137005, 0.0018818197052405962]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024942643988033, 0.21179744237757436, 0.6280614356300516, 0.0, 0.032837414321974116, -0.31812578977269435, -3.0326111904443955, -1.0452508930410527, -1.9626876112700173, -0.11087403638981642, -1.1604767590735159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5087462976732324, 0.6134391523867183, 1.3260590187239967, -0.8924938010822095, -1.8900486175493625, -0.3983666197484187, 0.9122756140155615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9612828171656946, -0.48741756737242403, 0.021263334940033223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001388390382738015, -0.029685173127436876, 0.09552763427078588, 0.0, -0.07299901178517247, -0.010213568968818868, -0.07177062512199014, -0.008740162954621399, 0.18400347002629233, 0.035044943553595116, -0.23230066453322595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.391073503559951, -0.14652876396440218, -0.1285836829524449, 0.430840439808488, -0.1882691950876016, -0.015601367128617337, 0.04625606798196829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1981254818137743, 0.0891768587220289, 0.0014132825788728686]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025648617165462, 0.2102159997234052, 0.6329105085744566, 0.0, 0.02877294974059154, -0.31860398466958934, -3.0353794732601376, -1.0456722544572943, -1.9535790164030598, -0.10975106669980453, -1.1726841966576451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48909731099497733, 0.6059579119762081, 1.3197643797852852, -0.8704192973769448, -1.8991693651637631, -0.39891412960312955, 0.9141417636527343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711873739518471, -0.4828893418700921, 0.0213193368087825]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001411946354858873, -0.03162885308338303, 0.09698145888810075, 0.0, -0.08128929162765157, -0.009563897937899444, -0.05536565631484504, -0.008427228324830742, 0.18217189733915135, 0.022459393800237974, -0.24414875168258673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39297973356510235, -0.1496248082102037, -0.12589277877422897, 0.44149007410529506, -0.1824149522880104, -0.01095019709421708, 0.03732299274345578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19809113572304787, 0.0905645100466391, 0.0011200373749855554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20026365067228066, 0.20853153423470647, 0.6378348053398177, 0.0, 0.024287414359991967, -0.31906383544072553, -3.03730358821359, -1.0460803808476857, -1.944506846300838, -0.10880336925481057, -1.1855679286607015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46935386567918885, 0.5983182674664688, 1.3136084475674703, -0.8477824018146772, -1.9079370164244762, -0.3991966785218747, 0.9154962070713135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9810904491676253, -0.47830120746567945, 0.021365983100818976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014329001252086628, -0.0336893097739748, 0.09848593530722288, 0.0, -0.08971070761199146, -0.009197015422723371, -0.03848229906904507, -0.008162527807830557, 0.18144340204443837, 0.018953948899879114, -0.2576746400611291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39486890631576926, -0.1527928901947863, -0.12311864435629659, 0.4527379112453502, -0.17535302521426147, -0.005650978374902695, 0.02708886837158525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19806150431556513, 0.09176268808825254, 0.0009329258407294982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002709181633583, 0.2067445984866543, 0.6432883074780156, 0.0, 0.019368020415770022, -0.319506030596099, -3.0383767612417256, -1.0464716606443134, -1.93539817392384, -0.10785793321986444, -1.1992183447754208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.449511737566043, 0.5905186190172917, 1.30759712755751, -0.8245528155742337, -1.9162819395303767, -0.39918565990323196, 0.9162647015301013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9909921334418351, -0.4736560022976525, 0.021405717349798476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014534982155259296, -0.035738714961043055, 0.1090700427639566, 0.0, -0.0983878788844389, -0.008843903107469055, -0.021463460562710514, -0.007825595932554615, 0.1821734475399597, 0.018908720698922653, -0.2730083222943843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39684256226291714, -0.15599296898354148, -0.1202264001992059, 0.46459172480887045, -0.1668984621180081, 0.0002203723728545822, 0.015369889175756525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19803368548419537, 0.09290410336053989, 0.000794684979589968]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20027829438051795, 0.20485868510348465, 0.6490013560727583, 0.0, 0.014002434650858962, -0.31992610835046786, -3.0386077281967667, -1.0468412358708508, -1.9261612032181843, -0.10686461645591573, -1.2137239690189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295630481332781, 0.5825587072681266, 1.3017382359732208, -0.8006983855868464, -1.9241240546061331, -0.39885668361580096, 0.9163618604901093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0008924345494923, -0.4689530184259971, 0.02143932756822293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001475243431933699, -0.037718267663393076, 0.11426097189485505, 0.0, -0.10731171529822119, -0.008401555087377478, -0.0046193391008222465, -0.007391504530747066, 0.18473941411311273, 0.01986633527897399, -0.2901124848695834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39897378865529753, -0.15919823498330188, -0.11717783168578469, 0.4770885997477463, -0.15684230151512948, 0.006579525748620504, 0.0019431792001582751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980060221531453, 0.09405967743310696, 0.0006722043684891009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028578925979554, 0.20287743274338085, 0.6547406686796089, 0.0, 0.008185018820865536, -0.32031794640898287, -3.0380197116706626, -1.0471838245626715, -1.9166848868198592, -0.10581108299932915, -1.2291713152384198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.409497880984442, 0.5744384300934184, 1.2960420336682963, -0.7761829962429637, -1.9313712603623479, -0.39818884409194577, 0.9156880981674309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0107913532621287, -0.46419123734401335, 0.021467110255929775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014989758555187285, -0.03962504720207571, 0.11478625213701081, 0.0, -0.11634831659986852, -0.007836761170300528, 0.011760330522081603, -0.0068517738364139965, 0.18952632796650123, 0.02107066913173159, -0.30894692439039756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4013033429767219, -0.16240554349416467, -0.11392404609848922, 0.49030778687765375, -0.1449441151242955, 0.013356790477103832, -0.01347524645356626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19797837425272766, 0.09523562163967537, 0.0005556537541368603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20029341668299114, 0.20080310284452807, 0.6604121090446456, 0.0, 0.001921849586408484, -0.3206748265522026, -3.036649950845352, -1.0474931959378289, -1.9068372060650318, -0.10469342341170036, -1.2456491252742798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38930633750726457, 0.5661566921582276, 1.2905223641067847, -0.750964653980663, -1.9379170515353874, -0.3971633693842987, 0.9141253637504341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0206889396240197, -0.45937220777499244, 0.021489539567299338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015254846391213545, -0.04148659797705568, 0.11342880730073404, 0.0, -0.12526338468914103, -0.007137602864394741, 0.027395216506216978, -0.006187427503146391, 0.1969536150965476, 0.022353191752575823, -0.32955620071719854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.403830869543549, -0.16563475870381658, -0.11039339123023295, 0.5043668452460132, -0.13091582346079012, 0.020509494152941406, -0.03125468833993677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979517272378216, 0.09638059138041875, 0.00044858622739128284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030119568854826, 0.19863638606599057, 0.6660139722038477, 0.0, -0.0047654859416252715, -0.32098958444084497, -3.034549899605448, -1.047761372718335, -1.8964610837443059, -0.10350850752967147, -1.2632545889497222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3689808614367368, 0.5577104480698207, 1.2851985271167368, -0.7249939125996567, -1.9436369605967867, -0.39576205076792975, 0.9115313297721367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305853548399064, -0.45450238080270544, 0.021507407707782908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015558011114232356, -0.04333433557074981, 0.1120372631840425, 0.0, -0.1337467105606751, -0.006295157772847987, 0.04200102479807478, -0.005363535610125525, 0.207522446414517, 0.023698317640577764, -0.3521092735088453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40650952141055535, -0.16892488176813872, -0.10647673980095607, 0.5194148276201257, -0.11439818122798806, 0.028026372327378497, -0.05188067956594836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792830431773525, 0.09739653944573959, 0.0003573628096714333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030914634140978, 0.19637390500117713, 0.6715828451201916, 0.0, -0.011823845857501004, -0.32125109674842384, -3.0317232352621573, -1.047993758889174, -1.8853759253989026, -0.10350850752923797, -1.282109695006647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34853531759768974, 0.5490903893140774, 1.2800996783217704, -0.6982100150772024, -1.9483808813828611, -0.3939543090524812, 0.9077272656514751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0404812611623253, -0.44961272326613566, 0.021525033954934155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001590130572305638, -0.045249621296268805, 0.11137745832687744, 0.0, -0.14116719831751465, -0.005230246151577747, 0.056533286865820584, -0.004647723416777062, 0.22170316690806577, 8.670054257864379e-12, -0.37710212113849784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4089108767809417, -0.17240117511486672, -0.10197697589932689, 0.535677950449087, -0.09487841572149006, 0.036154834308971096, -0.07608128241323243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19791812644837758, 0.09779315073139577, 0.00035252494302495706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003172693409572, 0.1940175527107981, 0.6771603689056768, 0.0, -0.019193679667741763, -0.321440476638921, -3.028179268613157, -1.0481732072969074, -1.8733471366727263, -0.10350850752836022, -1.3024202699248018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3279913270141919, 0.5402847239915176, 1.2752683565321803, -0.670544663390444, -1.9519661143688292, -0.39170631156022995, 0.9024892898828979, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0503774344917505, -0.4447394511672975, 0.021544256271463894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016245999094805286, -0.047127045807580724, 0.11155047570970374, 0.0, -0.1473966762048152, -0.0037875978099430434, 0.07087933298000587, -0.003588968154669996, 0.24057577452352463, 1.7555029717154477e-11, -0.40621149836309306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4108798116699565, -0.17611330645119624, -0.09662643579180089, 0.5533070337351663, -0.07170465971936085, 0.04495994984502532, -0.10475951537154438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792346658850413, 0.09746544197676281, 0.000384446330594774]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032562408611035, 0.19157898268789894, 0.6827789936632113, 0.0, -0.02680877064690194, -0.32154935222513786, -3.0239496911498267, -1.048269333871253, -1.8600634801830365, -0.10350850752892245, -1.3244520270897273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3073749799692585, 0.5312801892863821, 1.2707653820007925, -0.641920890359514, -1.9541671935741474, -0.38898616714406864, 0.8955337475218497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0602746926488202, -0.43992003567794874, 0.02156267750140531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016709490306319699, -0.04877140045798318, 0.11237249515069075, 0.0, -0.15230181958320357, -0.002177511724336902, 0.0845915492666035, -0.0019225314869087012, 0.2656731297937968, -1.1244587338957728e-11, -0.440635143298511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41232694089866834, -0.18009069410271097, -0.09005949062775538, 0.5724754606185991, -0.04402158410636586, 0.05440288832322622, -0.13911084722096373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979451631413971, 0.09638830978697575, 0.0003684245988282738]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003343827899983, 0.18908234189505516, 0.6884591475134899, 0.0, -0.03458886264762535, -0.32156845280526186, -3.019089507224257, -1.0482170064255085, -1.8451117116401439, -0.10350850752801133, -1.348545726744807, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.28671800434849704, 0.5220618657484017, 1.2666775150992649, -0.6122492040576393, -1.9547005956772974, -0.38576786993113416, 0.886494070350839, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0701739237493035, -0.4351940617873942, 0.02157207271245176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017517407775899616, -0.04993281585687589, 0.11360307700557186, 0.0, -0.15560184001446814, -0.0003820116024801435, 0.09720367851139555, 0.0010465489148875277, 0.29903537085785037, 1.8222420301728088e-11, -0.48187399310159584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4131395124152298, -0.18436647075960821, -0.08175733803055242, 0.5934337260374951, -0.010668042062998706, 0.06436594425868974, -0.18079354342021137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19798462200966607, 0.09451947781108981, 0.00018790422092902821]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003437113012565, 0.1865590655037719, 0.6942110743842566, 0.0, -0.042433366863801565, -0.32148710723549906, -3.013687044176947, -1.0479506258393319, -1.8279278250508226, -0.10350850752730906, -1.3751539477281702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26605257839378216, 0.5126101957533383, 1.263130067889564, -0.5814169572975708, -1.953201116026987, -0.38203307191891245, 0.8748821920655593, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0800761664844183, -0.43060595297904586, 0.021563618093416753]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018657022516393627, -0.05046552782566498, 0.11503853741533392, 0.0, -0.15689008432352433, 0.0016269113952556665, 0.10804926094620285, 0.00532761172353181, 0.34367773178642597, 1.4045463697372213e-11, -0.5321644196672647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41330851909429756, -0.1890333999012687, -0.07094894419401514, 0.6166449352013684, 0.02998959300620538, 0.07469596024443391, -0.23223756570559562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19804485470229513, 0.09176217616696702, -0.00016909238070013938]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20035384746092152, 0.18404512675042728, 0.7000380490622289, 0.0, -0.050212851054079896, -0.32129764731835564, -3.007872020375405, -1.047408573474381, -1.807714696520507, -0.1035085075265131, -1.4049158957652377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24540734864367067, 0.5028965248793075, 1.260308356335637, -0.5492699698748068, -1.949181545315102, -0.3777738292535714, 0.8600228144996451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899826588460824, -0.42620844655981927, 0.021530459334271956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020272319330068492, -0.050278775066892704, 0.11653949355944743, 0.0, -0.1555896838055666, 0.003789198342868636, 0.11630047603084057, 0.01084104729901766, 0.4042625706063127, 1.5919110619624917e-11, -0.5952389607413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41290459500222965, -0.19427341748061752, -0.0564342310785417, 0.6429397484552792, 0.08039141423770374, 0.08518485330682168, -0.2971875513182835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19812984723328245, 0.08795012838453235, -0.0006631751828959446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036843163460358, 0.18136281953048786, 0.7059390781648229, 0.0, -0.057767388905325394, -0.3210710738639323, -3.0019894450633307, -1.0466631557182662, -1.7833826261393904, -0.10350850752649103, -1.4386498684378064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22607875701511615, 0.49392618538752037, 1.2587569083891101, -0.5184133404197366, -1.941897647938553, -0.3738639731587597, 0.8417880744913834, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0998962708048692, -0.4221692529637803, 0.021686362584224045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002916834736410404, -0.053646144398788474, 0.1180205820518809, 0.0, -0.1510907570249099, 0.0045314690884670624, 0.1176515062414791, 0.014908355122296033, 0.4866414076223328, 4.4136456503999646e-13, -0.6746794534513738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3865718325710906, -0.17940678983574165, -0.03102895893053481, 0.6171325891014039, 0.1456779475309793, 0.07819712189623458, -0.36469480016523564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19827223917573664, 0.08078387192078006, 0.0031180649990417805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003942537113021, 0.17828529615059197, 0.7119086970749711, 0.0, -0.06481104577349599, -0.32095649077276867, -2.9965751754981027, -1.0458472146225162, -1.753576222358894, -0.10350850752557518, -1.476720268237994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21045717232158523, 0.4874910167006223, 1.2591597974561297, -0.492597068932329, -1.930827428581285, -0.371992393713558, 0.821011277691062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1098211641847406, -0.4187433454099081, 0.02231639502794631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000516441533970284, -0.061550467597917866, 0.11939237820296275, 0.0, -0.14087313736341175, 0.0022916618232726514, 0.10828539130455896, 0.016318821914997908, 0.5961280756099278, 1.8317036250482457e-11, -0.7614079960037541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.31243169387061864, -0.12870337373796226, 0.008057781340389522, 0.5163254297481521, 0.22140438714536217, 0.03743158890403379, -0.4155359360064289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984978675974289, 0.06851815107744402, 0.012600648874445338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004388397255267, 0.17485617009380533, 0.7179373658089209, 0.0, -0.0708799625458358, -0.32108736955233547, -2.9921991868446067, -1.0449728458633074, -1.7183656050601326, -0.103508507551078, -1.5186732699592207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20058607313259408, 0.48488016496026076, 1.261770084558291, -0.47557115538422545, -1.9164565911539984, -0.3734251779064008, 0.7994134183993886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1197616468296943, -0.41613950387568394, 0.023478168149860274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008917202844920643, -0.06858252113573299, 0.12057337467899516, 0.0, -0.12137833544679619, -0.002617575591335923, 0.08751977306991583, 0.01748737518417392, 0.70421234597523, -5.100565746783541e-10, -0.8390600344245331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19742198377982317, -0.052217034807230445, 0.052205742043229766, 0.34051827096207177, 0.2874167485457316, -0.028655683856854998, -0.43195718583346787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19880965289907265, 0.0520768306844828, 0.023235462438279234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005152505839828, 0.1713391455780551, 0.7240261343656306, 0.0, -0.0757735884958979, -0.3213355926797959, -2.9889814816028712, -1.0440263392981617, -1.6783008240333939, -0.10350850760301146, -1.5640162619985774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19755116875234574, 0.48665761041572353, 1.2661729829388388, -0.4710855997270218, -1.9005937735528882, -0.3787027586782937, 0.7798707452587533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.129720437439687, -0.4144030404743032, 0.02505428898970948]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015282171691219392, -0.07034049031500482, 0.12177537113419343, 0.0, -0.09787251900124191, -0.004964462549208628, 0.0643541048347083, 0.018930131302915862, 0.8012956205347723, -1.0386692511734449e-09, -0.9068598407871321, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06069808760496673, 0.03554890910925572, 0.08805796761095572, 0.08971111314407304, 0.31725635202220503, -0.10555161543785882, -0.3908534628127065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917581219985286, 0.034729268027614696, 0.03152241679698409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20065601839622627, 0.16807247951426837, 0.7301320595769725, 0.0, -0.07969648408535791, -0.32176962153628585, -2.986607289663825, -1.0431390960024967, -1.6342489992114075, -0.10350850760306361, -1.6122408329025861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20067328395522496, 0.492400892843251, 1.2716015314676967, -0.47859763667929617, -1.8855827822470475, -0.3876223444709693, 0.7649963838140723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1396650036073466, -0.41338405076823215, 0.026870077922475817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0028153562448687964, -0.06533332127573466, 0.12211850422683904, 0.0, -0.07845791178920039, -0.008680577129799173, 0.04748383878092355, 0.017744865913298997, 0.881036496439728, -1.042922814899149e-12, -0.9644914180801775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062442304057584455, 0.11486564855054912, 0.10857097057715762, -0.1502407390454879, 0.30021982611681386, -0.1783917158535125, -0.29748722889361945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19889132335319332, 0.02037979412142081, 0.036315778655326744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20096542306793036, 0.1654449932387038, 0.7362508424313801, 0.0, -0.08304710453424663, -0.32573663391034274, -2.9837188757965825, -1.0443762733868391, -1.5870075393538325, -0.10521373332923009, -1.662240832902595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2086725093691195, 0.5012186466235822, 1.2773543946865247, -0.496107667472857, -1.874211870670797, -0.3994081790168006, 0.7573401079606881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1494812901559333, -0.4128914605340995, 0.02866861537375455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006188093434081931, -0.0525497255112915, 0.1223756570881518, 0.0, -0.06701240897777443, -0.07934024748113738, 0.05776827734485358, -0.024743547686851254, 0.9448291971514986, -0.034104514523329695, -1.0000000000001805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998450827789035, 0.17635507560662322, 0.1150572643765603, -0.35020061587121726, 0.22741823152500568, -0.2357166909166251, -0.15312551706768568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1963257309717322, 0.009851804682653769, 0.03597074902557463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20152838728931086, 0.16369481209325562, 0.7423906816198869, 0.0, -0.08691864583703286, -0.3314701379428469, -2.9768146445403336, -1.0486542064114133, -1.5393105615783342, -0.11197817370281932, -1.712240832902578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22038123413262947, 0.5120842470988328, 1.282798670935164, -0.5219493598008356, -1.870009977014743, -0.4126385789809851, 0.7601173661938881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158737285299586, -0.41276466205298745, 0.030274916064017]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011259284427610077, -0.035003622908963465, 0.12279678377013534, 0.0, -0.07743082605572461, -0.11467008065008287, 0.13808462512497643, -0.08555866049148067, 0.9539395555099669, -0.13528880747178448, -0.999999999999657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2341744952701998, 0.21731200950501292, 0.1088855249727857, -0.5168338465595709, 0.08403787312108424, -0.2646079992836903, 0.05554516466400122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18511990287305707, 0.0025359696222403425, 0.03212601380524895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20202627967430978, 0.16284106308747984, 0.7485249734313544, 0.0, -0.09344210826657097, -0.33808688780499263, -2.962144595895054, -1.0563212869545757, -1.4949080658849068, -0.1275518286405913, -1.7622408329025676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2350154259370006, 0.5242289585463547, 1.287687448692728, -0.5546227136632432, -1.873673089113286, -0.42613294628406545, 0.7728950815705997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1674067985535097, -0.41296480272338026, 0.031647632194646884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009957847699978529, -0.017074980115515438, 0.12268583622935114, 0.0, -0.1304692485907622, -0.1323349972429145, 0.29340097290509703, -0.15334161086325052, 0.8880499138684388, -0.31147309875544, -0.9999999999997944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.29268383608742216, 0.24289422895043714, 0.09777555515128335, -0.6534670772481537, -0.0732622419708612, -0.2698873460616072, 0.25555430753423225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17339026507847224, -0.004002813407856775, 0.027454322612597743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.202398800107997, 0.16280683147053426, 0.7545672663418745, 0.0, -0.10236052291981554, -0.34514526068085766, -2.938669555357371, -1.066806922522258, -1.4566519388420978, -0.15099873731396388, -1.8122408329025614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2521359232549917, 0.5371313790297202, 1.2922238548942178, -0.5927613967532037, -1.8839800229080845, -0.4391346299700987, 0.794086424033654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1756525480679787, -0.413549951262761, 0.03278605831622804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007450408673744192, -0.0006846323389115214, 0.12084585821040356, 0.0, -0.17836829306489152, -0.141167457517301, 0.4695008107536621, -0.2097127113536453, 0.7651225408561788, -0.4689381734674513, -0.9999999999998763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3424099463598216, 0.2580484096673115, 0.090728124029795, -0.76277366179921, -0.20613867589596885, -0.26003367372066566, 0.42382684926108727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16491499028938097, -0.01170297078761519, 0.022768522431623063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2027163628310531, 0.163548418785463, 0.7604249409633889, 0.0, -0.1129019331978828, -0.34889525657054227, -2.9078895229271913, -1.0783023625548778, -1.4236392592615992, -0.1812568968502859, -1.862240832902567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27156293012603155, 0.5504404420941427, 1.2967143864739177, -0.6352723432251367, -1.8997476245278966, -0.4511342511228243, 0.8224317087991058, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.18355943573368, -0.4145957872726459, 0.03365033610337059]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006351254461121899, 0.014831746298575024, 0.11715349243028593, 0.0, -0.21082820556134538, -0.07499991779359372, 0.6156006486035991, -0.2299088006523955, 0.6602535916099723, -0.6051631907264403, -1.000000000000111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3885401374207975, 0.26618126128844893, 0.08981063159399902, -0.85021892943866, -0.31535203239624304, -0.23999242305451118, 0.5669056953090346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15813775331402652, -0.020916720197697428, 0.01728555574285116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20300062721202383, 0.16503843169782795, 0.7660373673432823, 0.0, -0.12443766154595379, -0.35264525165413685, -2.8712654969834506, -1.0900256812328397, -1.3939445447531358, -0.217290875746959, -1.9122408329024576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29321619565331164, 0.563902471783936, 1.3017963568395874, -0.6812811004027302, -1.920152501583522, -0.46209018873095564, 0.856740237231522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1912604617573923, -0.41613681364612143, 0.0342114464647145]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005685287619414848, 0.029800258247298695, 0.11224852759786824, 0.0, -0.23071456696141968, -0.07499990167189127, 0.7324805188748166, -0.23446637355923902, 0.5938942901692699, -0.7206795779334619, -0.9999999999978096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4330653105456018, 0.2692405937958666, 0.10163940731339415, -0.92017514355187, -0.4080975411125062, -0.21911875216262716, 0.6861705686483266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1540205204742444, -0.030820527469511003, 0.01122220722687825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20327350143028525, 0.16728785758489248, 0.7713944842449668, 0.0, -0.1366453821212773, -0.35264524971890543, -2.829966276228405, -1.1011813700863278, -1.3659979985495936, -0.25811805886428807, -1.9622408329024688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.317005942110701, 0.5772663034002397, 1.3082663081475974, -0.7300881061447986, -1.9449740073709518, -0.4723040399021917, 0.8960526609708361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1988628223791276, -0.4181387944267183, 0.034438861496440466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005457484365228559, 0.04498851774129044, 0.10714233803369108, 0.0, -0.24415441150647035, 3.8704628849139944e-08, 0.8259844151009157, -0.2231137770697607, 0.5589309240708441, -0.8165436623465813, -1.000000000000223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47579492914778665, 0.26727663232607307, 0.12939902616019983, -0.976140114841369, -0.49643011574859736, -0.2042770234247212, 0.786248474786281, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1520472124347034, -0.040039615611937036, 0.004548300634519246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354427407946665, 0.17029590589764237, 0.7765242390469841, 0.0, -0.14957609567993307, -0.3526452497225634, -2.784926899624365, -1.111502092915575, -1.3387330147559335, -0.30277980535815, -2.012240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3425978958829109, 0.59021135720085, 1.3168912697811177, -0.7800881312000915, -1.9743114642801527, -0.4823756353417002, 0.939502599962036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2064712450597492, -0.42048907395168095, 0.0343385347184016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005415452983628351, 0.06016096625499762, 0.10259509604034556, 0.0, -0.25861427117311553, -7.315934072253455e-11, 0.900787532080797, -0.20641445658494453, 0.5452996758732007, -0.8932349298772394, -0.9999999999999883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5118390754441977, 0.258901076012207, 0.17249923267040806, -1.0000005011058573, -0.5867491381840184, -0.20143190879016956, 0.8689987798239975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15216845361243223, -0.047005590499253035, -0.0020065355607773996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20380902679416726, 0.1740250608263596, 0.7814815414939414, 0.0, -0.16345409175240433, -0.35264524972256756, -2.7368953983411313, -1.1210488685706324, -1.3114909002989157, -0.3505092025532365, -2.062240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3694491359183932, 0.6024375144364038, 1.3280363297310942, -0.8300881562554033, -2.008190975646627, -0.49297056126018424, 0.9862625511421699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2141691199585547, -0.4230301045584226, 0.033953799488170976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005295054294012406, 0.07458309857434448, 0.09914604893914625, 0.0, -0.277559921449425, -8.306185477170416e-14, 0.960630025664667, -0.19093551310114656, 0.544842289140358, -0.954587943901729, -0.9999999999999948, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5370248007096454, 0.2445231447110752, 0.22290119899952948, -1.0000005011062378, -0.6775902273294845, -0.2118985183696804, 0.9351990236026778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15395749797610853, -0.05082061213483312, -0.007694704604612444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20405302516662302, 0.17839110823571697, 0.7863344254845989, 0.0, -0.17851430003789928, -0.35264524972255495, -2.686895373285901, -1.1300227185258729, -1.2838256251509144, -0.40050922760850854, -2.112240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3969237492142522, 0.613741097894437, 1.3415486574536832, -0.8800881813106121, -2.0459772709518442, -0.504647076992953, 1.0355802259860223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2220102602948362, -0.4255933560538981, 0.03335268787598558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004879967449115027, 0.0873209481871476, 0.09705767981314739, 0.0, -0.30120416570989883, 2.525265043987572e-13, 1.000000501104607, -0.17947699910481119, 0.5533055029600262, -1.0000005011054416, -0.9999999999999959, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5494922659171806, 0.22607166916066412, 0.2702465544517814, -1.0000005011041742, -0.7557259061043429, -0.23353031465537516, 0.9863534968770462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15682280672562757, -0.05126502990950946, -0.012022232243707826]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20427427775571064, 0.1832657630480131, 0.7911560606975594, 0.0, -0.19402046241882806, -0.3526452497225476, -2.6369255548772657, -1.1381357395602882, -1.2541818029209706, -0.4505092526637864, -2.1622408329024654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4241780894055525, 0.6240109137311005, 1.3565984597849061, -0.9300882063658712, -2.086394358193773, -0.5175612797107543, 1.085580225986022, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2299439964350036, -0.4280393053467843, 0.03261250819647751]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004425051781752245, 0.09749309624592228, 0.09643270425921166, 0.0, -0.3101232476185755, 1.46698788079243e-13, 0.9993963681727096, -0.16226042068830895, 0.5928764445988757, -1.0000005011055564, -0.9999999999999505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5450868038260062, 0.2053963167332707, 0.3009960466244557, -1.0000005011051827, -0.8083417448385756, -0.2582840543560268, 0.9999999999999947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15867472280334796, -0.04891898585772456, -0.014803593590161389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20448925460959733, 0.1884861482941713, 0.7960013837556438, 0.0, -0.20812797112921447, -0.3526452497225536, -2.590735943115225, -1.1442111287049983, -1.2195158208931738, -0.5005092777190392, -2.2122408329024843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4501567220181025, 0.6334540335899963, 1.3712930643842167, -0.9782469378031894, -2.1265963620534154, -0.531072591019149, 1.1355802259860202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2377756105301416, -0.43028076956376143, 0.03180917214483589]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004299537077733934, 0.10440770492316372, 0.09690646116168819, 0.0, -0.28215017420772837, -1.204229784694197e-13, 0.923792235240814, -0.12150778289419997, 0.6933196405559353, -1.0000005011050557, -1.000000000000377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5195726522509989, 0.1888623971779163, 0.29389209198621125, -0.9631746287463633, -0.8040400771928422, -0.2702262261678953, 0.9999999999999597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1566322819027592, -0.04482928433954309, -0.016066721032832413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2047468885177489, 0.19387014210656023, 0.8008866381240283, 0.0, -0.21961803998109392, -0.3521226426517718, -2.5514919148248616, -1.1465010588890092, -1.1798068664050003, -0.5505093027742914, -2.262240832902491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4737450900696767, 0.642079354452608, 1.3843459861892113, -1.0220309843042243, -2.1630376093293977, -0.5443202336407252, 1.1818302260191775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2452004234030019, -0.4322623985728623, 0.031009374273467866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005152678163031458, 0.10767987624777886, 0.09770508736768965, 0.0, -0.2298013770375888, 0.010452141415636393, 0.784880565807272, -0.04579860368021922, 0.794179089763471, -1.0000005011050457, -1.0000000000001337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47176736103148464, 0.17250641725223376, 0.2610584360998941, -0.8756809300207011, -0.7288249455196422, -0.2649528524315232, 0.9250000006631481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14849625745720518, -0.03963258018201765, -0.015995957427360454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2051287495455325, 0.19923065914216656, 0.8057737414679297, 0.0, -0.2281785742138778, -0.35022616837644915, -2.519391471608246, -1.1433405956760947, -1.136039702814632, -0.6005093278295216, -2.3122408329025026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4940033565817461, 0.6497248585809339, 1.3951808982628564, -1.059285479802085, -2.192812112797505, -0.5564281233814546, 1.2207959277732934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2519001603691544, -0.4339526108995303, 0.030265197010617452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007637220555672521, 0.10721034071212654, 0.09774206687802872, 0.0, -0.1712106846556775, 0.03792948550645252, 0.6420088643323169, 0.06320926425829188, 0.8753432718073637, -1.0000005011046043, -1.0000000000002376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4051653302413882, 0.15291008256651703, 0.21669824147290176, -0.7450899099572149, -0.5954900693621484, -0.24215779481458866, 0.7793140350823167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13399473932305103, -0.03380424653335981, -0.014883545257008256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20576022076715375, 0.2043888656870428, 0.8105783890627817, 0.0, -0.2337123229928388, -0.3464879381815168, -2.4940922874295155, -1.1337999009427524, -1.0890259719424475, -0.650509352884751, -2.362240832902516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510514236160238, 0.6564071831994994, 1.403620965527082, -1.0890059379932011, -2.214526068245795, -0.5667107378922177, 1.2507736607049844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2576710963515167, -0.4353477493425074, 0.029610162330812134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012629424432424752, 0.10316413089752449, 0.09609295189704037, 0.0, -0.11067497557922014, 0.07476460389864714, 0.5059836835746102, 0.19081389466684653, 0.9402746174436897, -1.0000005011045867, -1.0000000000002702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33021759156983965, 0.133646492371311, 0.16880134528450907, -0.5944091638223233, -0.43427910896580035, -0.20565229021526063, 0.5995546586338187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11541871964724648, -0.027902768859541856, -0.013100693596106397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064101730111816, 0.20918969614030278, 0.8151985088088208, 0.0, -0.23619468757488218, -0.34091006903492105, -2.475337384198103, -1.1177464421455081, -1.0394149872447274, -0.7005093779400104, -2.412240832902519, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.523403301297924, 0.6622822239167705, 1.4098182069669167, -1.1113813433797564, -2.2283755764191837, -0.5748417513451253, 1.2719013258029221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2624608795377155, -0.43646862893810046, 0.029057378771169932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880557524, 0.09601660906519982, 0.09240239492078313, 0.0, -0.04964729164086727, 0.11155738293191456, 0.375098064628254, 0.3210691759448877, 0.9922196939544017, -1.0000005011051882, -1.0000000000000613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2577813027537198, 0.11750081434542253, 0.1239448287966965, -0.44750810773110444, -0.27699016346777455, -0.16262026905815133, 0.42255330195875485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.095795663723975, -0.022417591911861316, -0.011055671192844046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2070601252552261, 0.2135221305357053, 0.8195134890305069, 0.0, -0.23592775110245523, -0.33388518964591246, -2.462551220837017, -1.0959194558390715, -0.9894149872447394, -0.7505094029952885, -2.4622408329025243, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5333287265246551, 0.667481948193073, 1.4142498397471182, -1.1277963513126714, -2.2360476984196853, -0.5810006042943882, 1.2859313215966783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.266386030912219, -0.4373574993376022, 0.028596672850609083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880889928, 0.08664868790805016, 0.08629960443372142, 0.0, 0.005338729448539366, 0.1404975877801714, 0.25572326722171174, 0.4365397261287322, 0.9999999999997586, -1.0000005011055593, -1.0000000000001035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19850850453462252, 0.10399448552605098, 0.08863265560402797, -0.32830015865830164, -0.1534424400100285, -0.12317705898525709, 0.2805999158751256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07850302749007283, -0.017777407990034997, -0.009214118411216964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20771007749924222, 0.2173234455155467, 0.823412480102414, 0.0, -0.2331721748620815, -0.3259143561449327, -2.4553099141551606, -1.0691483838741687, -0.9394149872447404, -0.8005094280505596, -2.512240832902523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5410462930877361, 0.6720870992422457, 1.4174490504828554, -1.1398783046788483, -2.23955831534367, -0.5855875325806078, 1.2949642850495815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2696122536938677, -0.43805918705077557, 0.028207867985896987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880322287, 0.07602629959682783, 0.0779798214381413, 0.0, 0.05511152480747473, 0.1594166700195956, 0.14482613363713087, 0.5354214392980579, 0.9999999999999802, -1.0000005011054218, -0.9999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15435133126162043, 0.09210302098345298, 0.0639842147147435, -0.2416390673235393, -0.07021233847969158, -0.09173856572439221, 0.18065926905806198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0645244556329731, -0.014033754263467138, -0.007776097294241945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20836002974325324, 0.220580738424814, 0.8268497555052778, 0.0, -0.22776557192265945, -0.3174532650407923, -2.453736299899618, -1.0373651970028064, -0.8894149872447474, -0.8505094531076175, -2.562240832903147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5471275253317054, 0.6760967766719892, 1.419812030834297, -1.1488903227386842, -2.2406049125982195, -0.5889740129652162, 1.3007316657284402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2722569064454363, -0.43861191622931434, 0.02786773997931919]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880220122, 0.06514585818534588, 0.06874550805727751, 0.0, 0.10813205878844129, 0.1692218220828084, 0.03147228511085087, 0.6356637374272478, 0.9999999999998577, -1.0000005011411581, -1.0000000000124751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12162464487938615, 0.08019354859486817, 0.04725960702883106, -0.18024036119671732, -0.020931945090991222, -0.067729607692168, 0.1153476135771768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0528930550313747, -0.011054583570775578, -0.006802560131555889]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20890236731276418, 0.22331947192858484, 0.8299126941352141, 0.0, -0.21963384384261464, -0.3087547466632327, -2.457943386608462, -1.0008838400568223, -0.8394149872448201, -0.9005094781628663, -2.6122408329031273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519614181536695, 0.6795011419163419, 1.4215954927811791, -1.1557017087656305, -2.2403813722918278, -0.5914575442271724, 1.3044574108583427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2744018531044412, -0.43904510173632294, 0.027557092385001702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010846751390218888, 0.05477467007541689, 0.06125877259872422, 0.0, 0.16263456160089598, 0.17397036755119216, -0.08414173417687226, 0.7296271389196829, 0.9999999999985463, -1.0000005011049757, -0.9999999999996081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0966778564392827, 0.06808730488705383, 0.035669238937643385, -0.13622772053892793, 0.004470806127835566, -0.04967062523912445, 0.07451490259804805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04289893318009702, -0.008663710140172066, -0.006212951886349732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924014300176616, 0.22558907526272806, 0.832516028451838, 0.0, -0.2088784119570595, -0.29988190631457157, -2.4679101480898793, -0.9600673236121545, -0.7894149872448852, -0.9505095032181211, -2.6622408329031124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558093246584372, 0.6822883123648255, 1.4229550903934498, -1.1609092407972317, -2.239690744526241, -0.5932717611957165, 1.3069797006688277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2761077168336417, -0.4393805271434575, 0.027263123491609406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006755513780039767, 0.04539206668286434, 0.0520666863324798, 0.0, 0.2151086377111026, 0.17745680697322283, -0.19933522962834466, 0.8163303288933546, 0.9999999999986986, -1.0000005011050965, -0.9999999999997062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07695813009535564, 0.05574340896967034, 0.027191952245415554, -0.10415064063202173, 0.01381255531173049, -0.03628433937087952, 0.050445796209702576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03411727458400836, -0.006708508142691235, -0.00587937786784593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932616161286308, 0.22744569050308344, 0.834826254295132, 0.0, -0.19579154426530776, -0.2908321419076912, -2.483469466430795, -0.9154141104565975, -0.739414987245167, -1.000509528273315, -2.712240832902818, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5588604330257323, 0.6844420565639199, 1.4239877225131137, -1.164969402369256, -2.239103536428652, -0.5946108692553929, 1.3089117387084355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2774277204317501, -0.4396341865431943, 0.02698265280572664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017203722219384116, 0.037132304807107774, 0.04620451686587979, 0.0, 0.2617373538350347, 0.18099528813760773, -0.3111863668183114, 0.8930642631111416, 0.9999999999943651, -1.0000005011038793, -0.9999999999941117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06102216734590005, 0.04307488398188946, 0.020652642393276476, -0.08120323144048687, 0.011744161951782052, -0.0267821611935287, 0.03864076079215309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026400071962168384, -0.005073187994736585, -0.005609413717655272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20933056938417735, 0.228938372466004, 0.8366688095526873, 0.0, -0.18217453223378702, -0.2814297402669101, -2.500887728282853, -0.870306111972243, -0.6931649872445551, -1.0491367343047637, -2.7584908329056668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5612536679267874, 0.6860483734709207, 1.4247430436927009, -1.168155308410831, -2.2387880875171633, -0.595590809248792, 1.3105357742296277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.278425135211993, -0.4398232632180623, 0.02672449963672147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.815542628558227e-05, 0.029853639258411103, 0.03685110515110657, 0.0, 0.2723402406304148, 0.18804803281562182, -0.3483652370411696, 0.9021599696870902, 0.9250000000122373, -0.9725441206289748, -0.9250000000569817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.047864698021103345, 0.032126338140017016, 0.01510642359174525, -0.06371812083149866, 0.006308978229771619, -0.0195987998679837, 0.032480710423844435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01994829560486069, -0.003781533497360421, -0.005163063380103397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932884115003778, 0.23011316550761649, 0.8381225057841533, 0.0, -0.1693528861440909, -0.27255979656795276, -2.518771328661458, -0.8284933281084138, -0.654414987213272, -1.0926411213852207, -2.7972408329494938, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631048045192583, 0.687252723211333, 1.4252317019514358, -1.1706501793212163, -2.2387012797308765, -0.5962762215751217, 1.3119750197448723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2791678862882272, -0.4399629161625189, 0.02649902814853944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.456468279174673e-05, 0.023495860832250186, 0.029073924629319937, 0.0, 0.2564329217939224, 0.17739887397914625, -0.35767200757209533, 0.836255677276582, 0.7750000006256631, -0.8700877416091413, -0.7750000008765425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0370227318494159, 0.024086994808245304, 0.009773165174699198, -0.04989741820770852, 0.001736155725733773, -0.013708246526593065, 0.0287849103048912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014855021524681263, -0.002793058889132289, -0.004509429763640606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932788289126003, 0.23101798821627914, 0.8391026888525631, 0.0, -0.15818501666305668, -0.26483319096932273, -2.5359587088692606, -0.7937257558710759, -0.6250680896836437, -1.1277424437604398, -2.8260974817958933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564512246192544, 0.6882110000970189, 1.4254194277410992, -1.172594032649529, -2.2387410078804804, -0.5966909778580843, 1.3133183993931452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2797159619590375, -0.4400654543891233, 0.026310697312253172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9165175554961214e-05, 0.018096454173253205, 0.0196036613681976, 0.0, 0.22335738962068408, 0.15453211197260083, -0.34374760415605077, 0.6953514447467598, 0.5869379505925651, -0.7020264475043795, -0.5771329769279895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02814883346571545, 0.01916553771371786, 0.0037545157932705603, -0.0388770665662527, -0.0007945629920774432, -0.008295125659251692, 0.02686759296545663, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010961513416206263, -0.002050764532088299, -0.003766616725725312]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209326967977962, 0.23170153162576393, 0.8397180196333647, 0.0, -0.14905358832275853, -0.25852071302748747, -2.5515493738647765, -0.7668782370757354, -0.6040801048930344, -1.1540211237438165, -2.8459557199745085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5655600193084604, 0.6890612677378614, 1.4252544891234067, -1.1741005473302502, -2.2388086006669075, -0.5968383061702716, 1.3146469020890874, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2801180324457406, -0.44014044847222306, 0.0261579683581745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.829826596068004e-05, 0.013670868189695779, 0.01230661561603071, 0.0, 0.1826285668059628, 0.12624955883670494, -0.31181329991032136, 0.5369503759068073, 0.4197596958121855, -0.5255735996675329, -0.397164763572303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02095546231832748, 0.01700535281684921, -0.003298772353851691, -0.030130293614425267, -0.001351855728544265, -0.002946566243744073, 0.02657005391884625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008041409734061587, -0.001499881661994671, -0.003054579081573399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093259380204269, 0.23220977394247713, 0.8400854275917896, 0.0, -0.14197612515217423, -0.2536482214865198, -2.564986775067951, -0.7473180611300209, -0.5895743811466219, -1.1724845390217244, -2.858801959448876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663198497966578, 0.6899025586887599, 1.424707731640309, -1.1752628476276366, -2.2388339068055143, -0.5967248652769541, 1.3160195454508985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2804118817113503, -0.440195155718598, 0.02603609857431136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0599150701613132e-05, 0.010164846334263896, 0.007348159168498353, 0.0, 0.14154926341168605, 0.09744983081935366, -0.2687480240634872, 0.39120351891429056, 0.29011447492825215, -0.36926830555815804, -0.2569247894873526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015196609763948796, 0.016825819017970946, -0.010935149661955473, -0.023246005947725922, -0.0005061227721400406, 0.0022688178663480153, 0.027452867236222957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005876985312195564, -0.0010941449274996567, -0.002437395677262807]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932478082939882, 0.23258303632233118, 0.8403182736213654, 0.0, -0.13673976621698192, -0.25009048605629397, -2.5760634691920976, -0.7338035035911181, -0.5797348308047431, -1.1846861181123198, -2.8666674562661716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5668496073376568, 0.690808718640863, 1.423754695329556, -1.176157114405769, -2.2387707525162717, -0.5963535131611295, 1.3174903452101003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2806261112024597, -0.4402349952513054, 0.02593967049718884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.314382056186457e-05, 0.007465247597081032, 0.004656920591515499, 0.0, 0.10472717870384635, 0.07115470860451609, -0.22153388248293018, 0.2702911507780543, 0.19679100683757533, -0.24403158181190557, -0.1573099363459114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010595150819977833, 0.018123199042062353, -0.019060726215059675, -0.017885335562650054, 0.001263085784849995, 0.007427042316493482, 0.02941599518403489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004284589822188753, -0.0007967906541475968, -0.00192856154245041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932339724114024, 0.2328547249447787, 0.8404844977878413, 0.0, -0.13302175330080057, -0.2476419798401231, -2.5848497946527678, -0.7249578381638652, -0.5731054595349542, -1.1922294288601571, -2.8712263686173403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5671915980120815, 0.6918542953571599, 1.4223367074189475, -1.1768459124727995, -2.2385826009709686, -0.5957045777303653, 1.3191371386595554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2807820429389665, -0.440263974177527, 0.025863793622816735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.76717651716686e-05, 0.0054337724489508295, 0.003324483329518648, 0.0, 0.0743602583236267, 0.048970124323417547, -0.17572650921339994, 0.17691330854505882, 0.13258742539577828, -0.1508662149567478, -0.09117824702337414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006839813488494819, 0.020911534325937276, -0.028359758212169114, -0.013775961340610206, 0.0037630309060581193, 0.012978708615283687, 0.03293586898910326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003118634730133735, -0.000579578524432414, -0.001517537487442093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932160909258068, 0.2330513790842077, 0.840695975766972, 0.0, -0.1304781107382692, -0.24608019902554626, -2.5915906810501066, -0.7195101586413297, -0.5686273915797048, -1.1965227031409893, -2.873712065986655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5673716881041702, 0.6931383151733975, 1.420324885976035, -1.1773812592468422, -2.2382285951112917, -0.5947182660780783, 1.321087474954143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2808954222641762, -0.44028503700835714, 0.025804395699238862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.576297119099514e-05, 0.003933082788579588, 0.004229559582612759, 0.0, 0.05087285125062718, 0.031235616291536917, -0.1348177279467748, 0.1089535904507085, 0.08956135910498746, -0.08586548561664105, -0.04971394738629807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003601801841772482, 0.02568039632475126, -0.0402364288582501, -0.01070693548085521, 0.007080117193534543, 0.019726233045739956, 0.03900672589175434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022675865041934746, -0.000421256616602761, -0.0011879584715574895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931920301568352, 0.2331934293386948, 0.8408585872212334, 0.0, -0.12879737342821995, -0.245203650165338, -2.5966091754426435, -0.7164018528654865, -0.5655782245461377, -1.198687194199383, -2.8749662449540203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56739952898861, 0.6947976467255678, 1.417501623225868, -1.1778071478137369, -2.2376551247952263, -0.5932859412217962, 1.3235316849239758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.280977805635369, -0.4403003384623748, 0.025758135598587646]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.812153794340694e-05, 0.0028410050897417867, 0.0032522290852278627, 0.0, 0.03361474620098516, 0.017530977204165292, -0.10036988785073828, 0.0621661155168642, 0.06098334067134223, -0.04328982116787521, -0.02508357934730481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005568176887978771, 0.033186631043404066, -0.056465255003339654, -0.008517771337891071, 0.011469406321307846, 0.02864649712564206, 0.04888419939665492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016476674238530644, -0.0003060290803538771, -0.0009252020130243051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931618104453162, 0.23329626311703922, 0.8409724071782145, 0.0, -0.12772312341066705, -0.24481395712687198, -2.6002446659971485, -0.7148146095129365, -0.5634795661829842, -1.199550618643628, -2.875531087473784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5672778537988058, 0.6969542188524047, 1.4136642286778873, -1.1781593437099984, -2.2368185258139257, -0.5913055409781842, 1.3266454613493943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810376429208725, -0.44031145120516274, 0.02572219668437234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0439423038208124e-05, 0.002056675566888427, 0.002276399139622121, 0.0, 0.021485000351057923, 0.007793860769319941, -0.07270981109009911, 0.03174486705099942, 0.041973167263069225, -0.01726848888489693, -0.011296850395268064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024335037960834314, 0.04313144253673796, -0.07674789095961343, -0.007043917925231801, 0.016731979626013978, 0.03960800487223917, 0.06227552850837193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011967457100707489, -0.00022225485575790908, -0.0007187782843061262]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093132596300379, 0.2333713576137685, 0.8411024824889938, 0.0, -0.12705684411839407, -0.2447149090405895, -2.602818979415272, -0.7141544056546724, -0.5620128669998177, -1.199683608494942, -2.8757399307150244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5670300950976542, 0.6995436439667067, 1.4089507589655348, -1.1784599753817526, -2.2357609555553686, -0.5888537791612296, 1.3303470237452841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810810937432404, -0.4403195204187482, 0.0256940742681744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.842828987430867e-05, 0.0015018899345859969, 0.0026015062155844244, 0.0, 0.013325585845459686, 0.00198096172564936, -0.0514862683624715, 0.013204077165283132, 0.029333983663330492, -0.002659797026282086, -0.004176864824815902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004955174023030489, 0.05178850228603931, -0.09426939424704964, -0.0060126334350839375, 0.021151405171141162, 0.04903523633909185, 0.07403124791779794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008690164473574144, -0.00016138427170990318, -0.0005624483239587907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931107145574457, 0.23342725960843494, 0.8412299048084414, 0.0, -0.1266536488275151, -0.24475560750623362, -2.6046089182401073, -0.71401434648281, -0.56096890190329, -1.1994554876513186, -2.875785908046203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5667027024736216, 0.7023252529122656, 1.4038254173463194, -1.1787187226710483, -2.234602608355407, -0.5861785294179096, 1.334307758548752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811126383451363, -0.44032537855362475, 0.02567146062408601]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3763485867001316e-05, 0.001118039893328548, 0.002548446388953234, 0.0, 0.008063905817579597, -0.0008139693128823918, -0.035798776496701455, 0.002801183437245544, 0.020879301930553273, 0.004562416872467299, -0.0009195466235717882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006547852480650781, 0.05563217891117837, -0.10250683238430679, -0.005174945785914244, 0.023166943999231908, 0.053504994866400785, 0.07921469606935587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006308920379176483, -0.00011716269753029164, -0.0004522728817677998]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093095357777038, 0.23347030733254687, 0.8413333933949931, 0.0, -0.12641317592168402, -0.2448425633689893, -2.6058359713905936, -0.7141318406218842, -0.5602121250904676, -1.1990895838369133, -2.8757726831399966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663405076834858, 0.7050641520890193, 1.398739313522182, -1.1789408532348258, -2.23345759570976, -0.5835200154982266, 1.3382051322199189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281135535361113, -0.44032963089928073, 0.02565226245036766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0713560815450024e-05, 0.0008609544822384934, 0.002069771731034684, 0.0, 0.00480945811662164, -0.001739117255113497, -0.024541063009727, -0.0023498827814825117, 0.015135536256447077, 0.007318076288105374, 0.0002644981241333316, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007243895802718277, 0.0547779835350745, -0.10172207648274745, -0.004442611275548488, 0.022900252912939713, 0.05317027839365999, 0.07794747342334042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00045794031953013753, -8.504691312025128e-05, -0.0003839634743670364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093083863401872, 0.23350509051701604, 0.8413646252815028, 0.0, -0.12626914210007656, -0.2449286003817336, -2.606668321483937, -0.7143485456589677, -0.5596551025701284, -1.1987097357395833, -2.875750105900365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.565974677304888, 0.7076153731996925, 1.393973547800686, -1.1791313171364814, -2.2323958449919328, -0.5810281181019368, 1.3418399661678189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811521534988537, -0.4403327173759992, 0.025634732928234014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2988750332211854e-05, 0.0006956636893833827, 0.0006246377301939144, 0.0, 0.0028806764321491277, -0.001720740254886341, -0.016647001866865102, -0.004334100741669422, 0.011140450406784304, 0.007596961946602426, 0.0004515447926331461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007316607571954944, 0.051024422213464565, -0.09531531442991814, -0.0038092780331124413, 0.021235014356552527, 0.049837947925796156, 0.07269667895799907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000332362754814236, -6.172953436950594e-05, -0.0003505904426728646]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093074345213319, 0.23353476076684745, 0.8413867836530399, 0.0, -0.12617978319897336, -0.2449968772106131, -2.6072287718098015, -0.714577054554873, -0.559240923775451, -1.1983759739779265, -2.8757378530791198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5656226078371608, 0.7099212289243557, 1.3896443520739996, -1.1792953816447265, -2.2314451351174696, -0.5787651709376522, 1.345133091682759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811642136478232, -0.4403349575490008, 0.02561761009628726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9036377105635495e-05, 0.0005934049966281783, 0.000443167430740441, 0.0, 0.0017871780220643492, -0.0013655365775899187, -0.011209006517291896, -0.0045701779181072716, 0.008283575893547793, 0.006675235233133516, 0.00024505642489917266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007041389354544094, 0.0461171144932648, -0.08658391453372918, -0.003281290164901044, 0.01901419748926482, 0.045258943285691154, 0.06586251029880365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002412029793911311, -4.480346003190916e-05, -0.0003424566389351333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930656804015205, 0.23356129882315158, 0.8413701620718517, 0.0, -0.12612001251429453, -0.24504422559840863, -2.607604653229138, -0.7147753717799153, -0.5589313399745239, -1.1981100556589004, -2.8757403173484275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5652913274534491, 0.7119836069201142, 1.385754835100013, -1.1794382729338133, -2.2306047665306026, -0.5767333927952603, 1.3480873651022844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281172965508997, -0.440336583464336, 0.025600174956988263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7329623597052658e-05, 0.0005307611260826335, -0.00033243162376509416, 0.0, 0.0011954136935767837, -0.0009469677559102456, -0.007517628386735238, -0.003966344500848236, 0.006191676018541968, 0.005318366380524382, -4.928538615713067e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006625607674232605, 0.04124755991517044, -0.077790339479733, -0.0028578257817353727, 0.01680737173734279, 0.040635562847839264, 0.059085468390505325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017503722347327722, -3.2518306703991607e-05, -0.00034870278597991196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930571697289413, 0.23358578927657528, 0.8413301762265463, 0.0, -0.1260756570374459, -0.24507464315984007, -2.6078564227091303, -0.7149285725174833, -0.5586999459037346, -1.1979128602868756, -2.8757551078398103, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5649807970422012, 0.7138384212270887, 1.3822426312907556, -1.1795648525660125, -2.229858153091005, -0.5749001873910619, 1.3507527457911412, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811793163762348, -0.4403377635721811, 0.02558220222703967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.702134515844646e-05, 0.0004898090684743421, -0.000799716906108358, 0.0, 0.0008871095369727812, -0.0006083512286286783, -0.0050353895998431234, -0.0030640147513591332, 0.004627881415787143, 0.003943907440495759, -0.0002958098276514625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006210608224958936, 0.03709628613948982, -0.07024407618514973, -0.0025315926439827795, 0.014932268791951654, 0.036664108083967424, 0.05330761377713449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001270173447574517, -2.360215690101155e-05, -0.00035945459897185014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093048289687132, 0.23360869936906162, 0.8412687929570802, 0.0, -0.12603921694238535, -0.24509250940629626, -2.6080254533918, -0.7150364279503766, -0.5585275030750284, -1.197775332567186, -2.8757778356522703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5646863279103231, 0.7155384116720686, 1.3790120388227531, -1.1796795240936315, -2.229181352658341, -0.5732152525497688, 1.3532028827256402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811839248259298, -0.44033862013547376, 0.02556383189244487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7760083618687023e-05, 0.0004582018497266741, -0.0012276653893209275, 0.0, 0.0007288019012108107, -0.00035732492912375895, -0.0033806136533930773, -0.0021571086578656457, 0.00344885657412393, 0.002750554393789047, -0.00045455624919883757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005889382637561511, 0.03399980889959524, -0.06461184936005213, -0.002293430552380959, 0.013536008653279674, 0.033698696825861935, 0.04900273868997617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.216899389749787e-05, -1.713126585362548e-05, -0.0003674066918959724]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093038618960449, 0.23363013314251516, 0.8412021612596656, 0.0, -0.12600711441060672, -0.24510213748602921, -2.6081395104400515, -0.7151055316030717, -0.5583997009662818, -1.1976850765639133, -2.8758042432433197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5644002197876236, 0.7171431776920782, 1.3759527757440497, -1.1797862949051272, -2.228548011012204, -0.571620595983273, 1.3555215766006095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811872688471595, -0.44033924188535506, 0.02554541065054421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9341453365596536e-05, 0.00042867546907065216, -0.0013326339482925987, 0.0, 0.0006420506355724892, -0.00019256159465898116, -0.0022811409650317937, -0.00138207305390175, 0.0025560421749317797, 0.0018051200654563017, -0.0005281518209890811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005722162453991348, 0.03209532040019296, -0.06118526157406873, -0.002135416229915026, 0.01266683292273626, 0.03189313132991613, 0.04637387749938665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.688042459223199e-05, -1.243499762654782e-05, -0.0003684248380132118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930277955712914, 0.23365003479002197, 0.841142355991144, 0.0, -0.12597786919762735, -0.2451067040304369, -2.608217050437533, -0.7151446630045013, -0.5583056253473476, -1.1976298647099906, -2.875831082964572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564112916098539, 0.718713631945134, 1.3729505868607748, -1.1798888818872901, -2.227932048589906, -0.5700562098209019, 1.3577952065121577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811896953317157, -0.44033969321508903, 0.025527345973332755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1646778315541915e-05, 0.0003980329501363525, -0.0011961053704323751, 0.0, 0.0005849042595874469, -9.133088815418519e-05, -0.0015507999496303946, -0.0007826280285938342, 0.001881512378682125, 0.0011042370784556759, -0.0005367944250410268, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005746073781690693, 0.03140908506111582, -0.06004377766550069, -0.002051739643259896, 0.012319248445959628, 0.03128772324742158, 0.04547259823096527, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.852969112507101e-05, -9.026594679226684e-06, -0.0003612935442291047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930155521577734, 0.23366833009605906, 0.841094961488964, 0.0, -0.12595099681958702, -0.24510830575426978, -2.608270244854492, -0.7151623127094201, -0.5582368711318413, -1.1975992576938694, -2.8758562656040474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5638140257817605, 0.7203079847006745, 1.369895085563649, -1.1799907533268417, -2.227309439495549, -0.5684642412888999, 1.360107104727664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281191456016363, -0.440340020855898, 0.02550999675993775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4486827036107972e-05, 0.0003659061207415492, -0.0009478900435981089, 0.0, 0.0005374475608064811, -3.203447665762285e-05, -0.0010638883391749958, -0.0003529940983749414, 0.0013750843101261174, 0.0006121403224216934, -0.0005036527895113157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0059778063355689585, 0.03188705511080903, -0.061110025942516716, -0.0020374287910290695, 0.012452181887139795, 0.03183937064003895, 0.046237964310127326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.521369294633575e-05, -6.552816180006944e-06, -0.0003469842679000255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930018081720683, 0.23368500968621683, 0.8410609628302775, 0.0, -0.125926388040214, -0.24510836130916702, -2.6083070567133824, -0.7151655660674753, -0.5581869933210988, -1.1975851125906631, -2.875878686583119, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.563493591706401, 0.7219767244682881, 1.3666896025534783, -1.18009501357608, -2.226660223367573, -0.5667941725697253, 1.3625303249008929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811927335841258, -0.44034025872312105, 0.025493606580810426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7487971409974618e-05, 0.00033359180315545664, -0.0006799731737292077, 0.0, 0.0004921755874602552, -1.1110979447739581e-06, -0.0007362371778133676, -6.506716110269497e-05, 0.0009975562148499739, 0.0002829020641273661, -0.0004484195814282261, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006408681507189875, 0.033374795352271634, -0.06410966020341216, -0.002085204984763627, 0.012984322559509329, 0.033401374383493235, 0.04846440346457676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5551355253924737e-05, -4.757344460149128e-06, -0.00032780358254653704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929867884331144, 0.2337001652461733, 0.8410398000736337, 0.0, -0.1259039816055719, -0.24510771241587442, -2.608332691702937, -0.7151597804444204, -0.5581510785125475, -1.1975814871566215, -2.875897971265622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631438560880656, 0.7237552448328658, 1.3632656213457324, -1.180204082582403, -2.225971326545408, -0.5650103653121799, 1.365116883684307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281193660600752, -0.4403404314317798, 0.025478275340491713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0039477908181726e-05, 0.00030311119912921383, -0.00042325513287815654, 0.0, 0.0004481286928418511, 1.2977865851722881e-05, -0.0005126997910942445, 0.00011571246109806768, 0.0007182961710260918, 7.250868083288599e-05, -0.0003856936500588376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006994712366707671, 0.03557040729155468, -0.0684796241549184, -0.002181380126459792, 0.013777936443305007, 0.03567614515090822, 0.051731175668285306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8540332523773255e-05, -3.4541731755088937e-06, -0.00030662480637424854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092971066962968, 0.23371399345663038, 0.8410315183894932, 0.0, -0.12588360240755486, -0.24510639356105499, -2.6083506489147124, -0.7151486795474746, -0.5581253344249605, -1.1975842653907938, -2.875914255468676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5627612462555937, 0.7256557504430601, 1.3595986979929144, -1.180319265356326, -2.225239514424052, -0.5631003451914094, 1.3678858125913502, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811943332514166, -0.44034055684806567, 0.025463959270514265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.144294029240099e-05, 0.000276564209141811, -0.0001656336828101733, 0.0, 0.00040758396034068956, 2.6377096388984554e-05, -0.00035914423550959505, 0.00022201793891585123, 0.0005148817517415824, -5.55646834436625e-05, -0.0003256840610755665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007652196649439385, 0.03801011220388612, -0.07333846705635926, -0.0023036554784603078, 0.014636242427122956, 0.03820040241540994, 0.055378578140861626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3453013296197203e-05, -2.508325717375635e-06, -0.000286321399548956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929554240381656, 0.23372677844954556, 0.8410309175430131, 0.0, -0.12586495439624742, -0.24510451324511714, -2.608363229770946, -0.715134626654381, -0.5581069586289285, -1.1975907620666153, -2.875927934791054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5623475532949853, 0.7276636348005215, 1.355715874881219, -1.1804404942998248, -2.2244724050053057, -0.5610786053208363, 1.3708175312484436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811948213291113, -0.4403406479415184, 0.025450491256586823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.128584960460454e-05, 0.0002556998583034697, -1.2016929603494417e-05, 0.0, 0.00037296022614867746, 3.7606318756892435e-05, -0.0002516171246731703, 0.00028105786187182383, 0.00036751592064140806, -0.00012993351642981148, -0.00027358644755902454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008273859212166279, 0.040157687149229564, -0.07765646223390661, -0.002424578869977944, 0.015342188374920577, 0.040434797411462116, 0.05863437314186746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.7615538926286e-06, -1.8218690544552197e-06, -0.00026936027854881727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209294053398125, 0.23373885868698788, 0.8410335748135789, 0.0, -0.12584763873052435, -0.24510210272088584, -2.6083719747967073, -0.7151189612611795, -0.558093895091273, -1.197599327374643, -2.8759395243000445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.561909294418856, 0.7297428023174414, 1.3516858663276905, -1.1805665121830295, -2.2236858833252864, -0.5589813906049087, 1.3738611251068245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195175474863, -0.4403407141278588, 0.025437617055845567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9780113831033408e-05, 0.00024160474884648138, 5.314541131553214e-05, 0.0, 0.00034631331446133593, 4.821048462616556e-05, -0.00017490051522889565, 0.00031330786403151347, 0.0002612707531080156, -0.00017130616055594606, -0.00023179017981265172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008765177522586246, 0.041583350338396, -0.080600171070569, -0.0025203576640966487, 0.01573043360038643, 0.04194429431855181, 0.060871877167615614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.082915030469657e-06, -1.3237268083657956e-06, -0.0002574840148251435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929267402278356, 0.23375058401338336, 0.8410368464974026, 0.0, -0.1258312071972287, -0.24509912738008263, -2.608377934289759, -0.7151023257509268, -0.5580846474444042, -1.1976090235471704, -2.8759495580003933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5614554637779701, 0.7318480731070073, 1.3475954379145076, -1.180695442257408, -2.222898841005886, -0.5568542851154894, 1.3769520004783893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195432432936, -0.4403407622430411, 0.0254250422090177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7587506829197594e-05, 0.00023450652790980332, 6.543367647447401e-05, 0.0, 0.0003286306659130794, 5.9506816063916064e-05, -0.00011918986102826232, 0.0003327102050529317, 0.00018495293737567448, -0.00019392345054728718, -0.00020067400697726577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009076612817717112, 0.04210541579131824, -0.08180856826365653, -0.0025786014875700805, 0.015740846388008323, 0.04254210978838492, 0.06181750743129771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.139161459139613e-06, -9.623036454801814e-07, -0.0002514969365572958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929140492578405, 0.23376226979364867, 0.8410366838434314, 0.0, -0.1258152304891205, -0.24509561131307556, -2.6083818247290775, -0.7150849474311873, -0.5580781479145169, -1.1976193739597198, -2.875958516984219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5609949280913906, 0.7339380409830827, 1.3435246690204103, -1.180825424830752, -2.22212797938815, -0.5547392558008276, 1.380030415191857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811956188667661, -0.44034079724974484, 0.025412482780436875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.538193999048871e-05, 0.00023371560530605358, -3.2530794247178512e-06, 0.0, 0.0003195341621644069, 7.032134014142217e-05, -7.78087863706458e-05, 0.0003475663947893592, 0.00012999059774529547, -0.00020700825098755003, -0.0001791796765088974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009210713731589496, 0.04179935752150859, -0.08141537788194497, -0.002599651466876533, 0.015417232354719007, 0.042300586293236575, 0.06156829426935478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7286766039075745e-06, -7.001340752734186e-07, -0.0002511885716165004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929022605121414, 0.23377415724123438, 0.8410354043712006, 0.0, -0.12579936807991787, -0.245091880159618, -2.6083840897483874, -0.7150668577609607, -0.55807369540577, -1.197630180755887, -2.8759667720472466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5605345511860355, 0.7359832897091294, 1.3395309574510912, -1.1809550542929945, -2.2213846728043958, -0.552666304106167, 1.3830534858866987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811957541294259, -0.44034082274968717, 0.025399710587983983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3577491398254557e-05, 0.000237748951714319, -2.5589444615739494e-05, 0.0, 0.0003172481840523629, 7.462306915097544e-05, -4.5300386200787526e-05, 0.00036179340453244813, 8.905017493845235e-05, -0.00021613592333979306, -0.0001651012605533446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009207538107104077, 0.040904974520935396, -0.07987423138638482, -0.002592589244853728, 0.01486613167508669, 0.04145903389321194, 0.06046141389683468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7052531964609267e-06, -5.099988465446153e-07, -0.00025544384905784367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092891087142332, 0.2337863889700238, 0.8410360082603573, 0.0, -0.12578335826999573, -0.24508741702397602, -2.6083851827022246, -0.715048050955997, -0.5580706532528865, -1.1976413418152407, -2.8759746453116835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5600783519138955, 0.7379690563802977, 1.3356436247608887, -1.1810835571516842, -2.2206741594981336, -0.5506506833394155, 1.3859992698826669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811958522663727, -0.4403408413557531, 0.025386583483815072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2346739618580776e-05, 0.0002446345757885683, 1.207778313352136e-05, 0.0, 0.0003201961984425355, 8.926271283950733e-05, -2.18590767437206e-05, 0.0003761360992743255, 6.084305766997865e-05, -0.00022322118707697718, -0.00015746528873960834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009123985442799153, 0.03971533342336723, -0.07774665380405146, -0.002570057173793344, 0.014210266125241882, 0.04031241533503041, 0.058915679919361294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9627389349568807e-06, -3.721213176678822e-07, -0.0002625420833782228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928802517115022, 0.23379900514934923, 0.8410349328638245, 0.0, -0.125767081482586, -0.24508231676848866, -2.6083853909718746, -0.7150285610661412, -0.5580686155401812, -1.1976528125791381, -2.8759823294466824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5596274722157201, 0.7398939844199924, 1.3318660572606382, -1.1812107802490412, -2.219996308616668, -0.5486940638167193, 1.3888652079976598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959234561143, -0.4403408549627982, 0.025373054806792944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1670861659835338e-05, 0.00025232358650895104, -2.1507930657501184e-05, 0.0, 0.00032553574819482414, 0.00010200510974724494, -4.1653930017752455e-06, 0.0003897977971152688, 4.075425410771976e-05, -0.0002294152779486388, -0.0001536826999770408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00901759396351018, 0.038498560793894, -0.07555135000501167, -0.002544461947141193, 0.013557017629314352, 0.03913239045392443, 0.05731876229985881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4237948324154929e-06, -2.721409020453415e-07, -0.00027057354044257597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928695084797927, 0.2338119584573455, 0.8410321159752371, 0.0, -0.12575052771739645, -0.2450766126830368, -2.6083849522399776, -0.7150084945107471, -0.558067272264523, -1.1976645422434569, -2.875989934475641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5591806119876536, 0.7417669828489495, 1.3281815578917626, -1.181337083108363, -2.219347098584525, -0.5467876350123405, 1.3916637907816496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959750864783, -0.4403408649438677, 0.025359163293032172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.148646341928201e-05, 0.00025906615992544573, -5.6337771747108655e-05, 0.0, 0.00033107530379099525, 0.00011408170903712871, 8.774637939968811e-06, 0.0004013311078828809, 2.6865513162621074e-05, -0.00023459328637668916, -0.0001521005791680687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00893720456133019, 0.03745996857914207, -0.07368998737751273, -0.002526057186434127, 0.012984200642861312, 0.038128576087575396, 0.05597165567979601, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.032607281879432e-06, -1.9962139030758776e-07, -0.000277830275215461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928586632714155, 0.23382514213019298, 0.8410281279171928, 0.0, -0.1257337701212526, -0.245070380155813, -2.608384056205543, -0.7149880199197897, -0.5580663940860073, -1.1976764629807153, -2.875997503976249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5587346767482065, 0.7436035660074914, 1.3245602911608023, -1.1814631941859728, -2.218720221675862, -0.5449157679568635, 1.3944173987513842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196012518856, -0.4403408722934107, 0.02534500869895688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.169041675451192e-05, 0.0002636734569495852, -7.976116088462764e-05, 0.0, 0.000335151922876737, 0.00012465054447576959, 1.7920688690471714e-05, 0.0004094918191487047, 1.756357031465416e-05, -0.000238414745170206, -0.0001513900121642371, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008918704788940066, 0.036731663170838695, -0.07242533461920501, -0.0025222215521966854, 0.012537538173262038, 0.03743734110954007, 0.05507215939469092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.486475535157642e-07, -1.4699085936223667e-07, -0.0002830918815058249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928475816571282, 0.23383842289331924, 0.8410237772334282, 0.0, -0.12571693075540719, -0.24506380536438543, -2.6083828393500443, -0.7149673371095181, -0.5580658266392596, -1.1976884972615673, -2.876005033477747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5582855023094606, 0.7454223285409701, 1.320966063736913, -1.1815900579661462, -2.2181085407857957, -0.5430595762208513, 1.397153250655472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960396432749, -0.4403408777315123, 0.025330721100861507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2163228574663497e-05, 0.00026561526252498984, -8.701367529104261e-05, 0.0, 0.00033678731690860153, 0.00013149582855127422, 2.4337109971788726e-05, 0.0004136562054321969, 1.134893495327528e-05, -0.00024068561703942797, -0.00015059002995320076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008983488774919038, 0.03637525066957294, -0.07188454847778691, -0.002537275603468942, 0.012233617801327062, 0.03712383472024385, 0.05471703808175564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.424883800536471e-07, -1.0876203281328585e-07, -0.00028575196190749576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928361962021858, 0.233851671975343, 0.8410200329115725, 0.0, -0.12570014481308564, -0.24505718307812926, -2.608381384654628, -0.714946639975147, -0.5580654824178932, -1.19770057133443, -2.87601249037681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5578285987012843, 0.7472417640137283, 1.317362530804653, -1.1817186799421848, -2.217505315958886, -0.5412001596216567, 1.3998987606241629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960592890377, -0.4403408817798127, 0.025316430660225216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2770909884935263e-05, 0.00026498164047559765, -7.488643711521706e-05, 0.0, 0.0003357188464307567, 0.00013244572512316, 2.909390832013645e-05, 0.0004139426874227912, 6.884427328987225e-06, -0.0002414814572513849, -0.00014913798126398273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00913807216352482, 0.036388709455163676, -0.07207065864519666, -0.0025724395207737606, 0.012064496538201786, 0.037188331983892126, 0.054910199373815416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9291525549217034e-07, -8.096600676193637e-08, -0.0002858088127258603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928245108894183, 0.23386478804542368, 0.8410174650185066, 0.0, -0.125683527186835, -0.24505075403237622, -2.6083797446478076, -0.7149260860247941, -0.55806531127179, -1.1977126232930966, -2.876019838179076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.557359873636548, 0.7490775025074466, 1.31371866460612, -1.181849972036363, -2.216905181731572, -0.5393214456994128, 1.402677423283606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960735113084, -0.4403408848165188, 0.025302244240532755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3370625534722936e-05, 0.0002623214016136919, -5.135786131682776e-05, 0.0, 0.000332352525012723, 0.00012858091506071477, 3.280013641051642e-05, 0.0004110790070570588, 3.4229220628398828e-06, -0.000241039173333795, -0.0001469560453180969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00937450129472489, 0.03671476987436629, -0.07287732397065966, -0.0026258418835635637, 0.01200268454627503, 0.03757427844487955, 0.05557325318886109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.844454131390296e-07, -6.07341217716913e-08, -0.0002837283938491854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928125975254663, 0.2338777108130339, 0.8410158630732162, 0.0, -0.1256671439747314, -0.24504447219903447, -2.608377986471098, -0.7149057769458779, -0.5580652503388998, -1.1977246030067663, -2.876027063526532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5568762726491504, 0.7509401348519842, 1.3100131355736913, -1.181984612037136, -2.2163048343526506, -0.5374124503813171, 1.4055054932543025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196083799387, -0.44034088711628594, 0.02528823051558007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3826727904008558e-05, 0.0002584553522042788, -3.203890580907234e-05, 0.0, 0.000327664242072245, 0.00012563666683489575, 3.516353418872416e-05, 0.0004061815783248623, 1.2186578059567068e-06, -0.0002395942733952444, -0.00014450694912265818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009672019747952372, 0.03725264689075036, -0.07411058064857856, -0.002692800015456993, 0.012006947578431529, 0.0381799063619132, 0.056561399413934295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0576157060140677e-07, -4.5995343059355314e-08, -0.0002802744990537038]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928005822107565, 0.23389042542853103, 0.8410148861598132, 0.0, -0.1256510139598323, -0.24503832647630847, -2.608376152939475, -0.7148857485231586, -0.5580652620672273, -1.1977364858353845, -2.8760341665429783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5563762310020239, 0.7528339407988729, 1.3062369547787211, -1.182122942229882, -2.2157033441213, -0.535468624793998, 1.4083899574042051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960912332747, -0.4403408888790849, 0.02527441387595175]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4030629419687853e-05, 0.0002542923099423783, -1.953826805875379e-05, 0.0, 0.00032260029798148945, 0.00012291445452000235, 3.667063245698228e-05, 0.00040056845438629304, -2.3456654998743283e-07, -0.0002376565723656537, -0.00014206032892117383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010000832942529793, 0.037876118937773505, -0.07552361589940103, -0.002766603854918861, 0.012029804627013495, 0.038876511746381424, 0.057689282998053766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.486777525501345e-07, -3.525597893159262e-08, -0.00027633279256637983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927886130024168, 0.2339029581009885, 0.8410143843772253, 0.0, -0.12563511083264114, -0.2450323182141585, -2.6083742664359377, -0.7148659747237618, -0.5580653290243688, -1.1977482722593595, -2.876041161779588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558598237937736, 0.7547568426705952, 1.3023937086428552, -1.182264935247827, -2.21510201780957, -0.5334919482142477, 1.4113283165359392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960965966573, -0.4403408902509209, 0.025260777130170713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.393841667927272e-05, 0.0002506534491489933, -1.0035651758644546e-05, 0.0, 0.0003180625438231048, 0.00012016524299924724, 3.773007074423181e-05, 0.0003954759879352741, -1.339142829504216e-06, -0.0002357284794985124, -0.00013990473219042374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010328144165007061, 0.038458037434445515, -0.07686492271731701, -0.0028398603588998673, 0.012026526234592393, 0.039533531595005764, 0.05876718263468003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0726765329846376e-07, -2.7436719599043683e-08, -0.00027273491562077913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092776824624636, 0.23391536552185, 0.8410144391534922, 0.0, -0.12561937333641351, -0.24502644928800751, -2.608372332749249, -0.714846381459219, -0.5580654492593156, -1.197759983980225, -2.8760480752640456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5553285643804892, 0.7567016476649344, 1.2984972245575668, -1.182410240711934, -2.2145038309831597, -0.5314896916689004, 1.4143103114192785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961004586885, -0.440340891338681, 0.025247270725072626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3576755561743843e-05, 0.0002481484172302796, 1.0955253381353154e-06, 0.0, 0.00031474992455246607, 0.00011737852301981131, 3.8673733772419264e-05, 0.0003918652908572367, -2.4046989356143726e-06, -0.00023423441731272078, -0.00013826968915586324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010625188265690203, 0.03889609988678383, -0.07792968170576704, -0.002906109282138934, 0.011963736528207015, 0.040045130906946655, 0.05963989766678648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.724062164925631e-08, -2.175520169768459e-08, -0.00027012810196172857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927653107197078, 0.23392772070120912, 0.84101540580586, 0.0, -0.12560372148059526, -0.2450207360536313, -2.608370340249683, -0.7148268663770398, -0.5580656368309801, -1.1977716584644167, -2.8760549373458373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5547849118132201, 0.7586582290391126, 1.2945673283683066, -1.1825582987058603, -2.2139125863543287, -0.5294722015989911, 1.417321104001079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961032334704, -0.44034089222072975, 0.02523382607193861]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3027809855934757e-05, 0.0002471035871828815, 1.9333047355637315e-05, 0.0, 0.0003130371163650664, 0.00011426468752416804, 3.984999132486252e-05, 0.00039030164358217097, -3.751433291583298e-06, -0.00023348968383076396, -0.00013724163583012978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010873051345381439, 0.03913162748356494, -0.07859792378520314, -0.0029611598785264674, 0.011824892576616503, 0.04034980139818535, 0.06021585163600526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.5495637686507746e-08, -1.764097494381458e-08, -0.00026889306268031713]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927541131276883, 0.23394009802358995, 0.8410185932189661, 0.0, -0.12558808170539637, -0.24501536003159705, -2.6083682275172504, -0.7148073196989726, -0.5580659552445796, -1.1977833488101328, -2.8760617628774376, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5542316414209236, 0.7606159964722238, 1.2906249655285476, -1.182708483457291, -2.21333203892798, -0.5274503660158455, 1.4203449570214883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196105224699, -0.4403408929544426, 0.025220370236506463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2395184038915284e-05, 0.00024754644761651673, 6.374826212170298e-05, 0.0, 0.0003127955039780514, 0.00010752044068553737, 4.225464864792489e-05, 0.0003909335613460387, -6.368271990569878e-06, -0.00023380691432252473, -0.00013651063200414507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011065407845928948, 0.039155348662223484, -0.07884725679517919, -0.0030036950286129248, 0.011610948526976715, 0.04043671166291232, 0.06047706040818713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.982457199812676e-08, -1.4674257741168563e-08, -0.0002691167086428905]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092743215783537, 0.23395255998394907, 0.8410230051473843, 0.0, -0.1255723470215273, -0.24500948683706794, -2.6083661263330646, -0.7147876519622324, -0.5580662673833868, -1.1977950636282821, -2.8760686341751702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5536712534113452, 0.7625660031818171, 1.2866879830377118, -1.182860236787746, -2.2127652088517054, -0.5254334347642385, 1.4233684315272994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066363056, -0.4403408935819532, 0.025206839486613532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1794688302532136e-05, 0.0002492392071820842, 8.823856836351996e-05, 0.0, 0.00031469367738097055, 0.00011746389058215508, 4.202368371624377e-05, 0.0003933547348035006, -6.242776145484021e-06, -0.00023429636298597504, -0.000137425954647393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011207760191569353, 0.03900013419186768, -0.0787396498167154, -0.0030350666091020382, 0.011336601525492554, 0.04033862503213897, 0.06046949011622329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.823213433133761e-08, -1.2550211904220164e-08, -0.0002706149978586365]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927325796914456, 0.23396514844578484, 0.8410271275585507, 0.0, -0.1255564580338701, -0.24500311691316207, -2.6083640599432076, -0.7147677981657665, -0.5580665472338727, -1.1978068265208242, -2.876075583750252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.553105546653773, 0.7645022849839103, 1.2827683981542415, -1.1830131612272698, -2.2122139963352003, -0.5234276176635633, 1.426382469184317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119610762088, -0.44034089413375943, 0.025193188723775455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1272184183163444e-05, 0.00025176923671551226, 8.244822332876133e-05, 0.0, 0.0003177797531437408, 0.00012739847811768642, 4.132779714126504e-05, 0.0003970759293174542, -5.597009716998422e-06, -0.00023525785083845817, -0.00013899150163114093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011314135151442745, 0.03872563604186414, -0.07839169766940694, -0.0030584887904729547, 0.011024250330098417, 0.04011634201350546, 0.06028075314034978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9691486868662377e-08, -1.1036124096475251e-08, -0.00027301525676155737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927221430519952, 0.23397788059636185, 0.8410270716064849, 0.0, -0.12554039099261471, -0.24499642276078032, -2.608362020589197, -0.7147477276260098, -0.5580668007004707, -1.197818655240422, -2.8760826201722662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5525354056982379, 0.7664223422694074, 1.278871353095892, -1.1831670647227828, -2.2116791073875484, -0.5214355596259588, 1.4293832066465353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961082891086, -0.4403408946317607, 0.025179396447075814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0873278901138924e-05, 0.00025464301154047255, -1.119041316239696e-06, 0.0, 0.0003213408251079206, 0.00013388304763496832, 4.0787080209078265e-05, 0.0004014107951335775, -5.069331957641143e-06, -0.00023657439195773594, -0.00014072844028634236, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011402819110700887, 0.03840114570994267, -0.07794090116698955, -0.003078069910258842, 0.010697778953041907, 0.03984116075209075, 0.06001474924436734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3364573338846698e-08, -9.96002479206681e-09, -0.00027584553399285095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927118397610842, 0.23399075006007178, 0.8410239311303209, 0.0, -0.1255241513808587, -0.24498956199327032, -2.608359996228923, -0.7147274444229025, -0.5580670386222834, -1.1978305548826256, -2.8760897378995463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519607905134508, 0.7683268961315398, 1.2749955209541877, -1.1833219600052314, -2.2111602189092636, -0.5194565663562908, 1.4323716913338567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087239965, -0.44034089509134106, 0.025165464592248835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0606581822150228e-05, 0.00025738927419882105, -6.280952327926157e-05, 0.0, 0.00032479223511994534, 0.00013721535019996331, 4.048720548120468e-05, 0.0004056640621466314, -4.758436254420416e-06, -0.0002379928440712219, -0.00014235454560254028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492303695741828, 0.0380910772426483, -0.07751664283408612, -0.0030979056489716097, 0.010377769565691192, 0.03957986539335971, 0.05976969374642933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.697758470711222e-09, -9.191606961494153e-09, -0.0002786370965395946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927016114082483, 0.23400373210759065, 0.8410194512123002, 0.0, -0.12550776676360897, -0.24498264241683182, -2.6083579783408393, -0.7147069809039911, -0.558067269018674, -1.1978425179494117, -2.8760969224402344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5513808833672721, 0.770219150729859, 1.2711345184463556, -1.1834780299146201, -2.210656286818563, -0.5174873471763168, 1.4353528300773581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961089872947, -0.4403408955231401, 0.025151414134471806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0456705671853165e-05, 0.0002596409503772192, -8.959836041594101e-05, 0.0, 0.00032769234499486994, 0.00013839152876997973, 4.035776167439639e-05, 0.0004092703782273909, -4.607927813112079e-06, -0.00023926133572264456, -0.0001436908137622857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011598142923575108, 0.037845091966384706, -0.0772200501566399, -0.0031213981877756675, 0.010078641814011902, 0.03938438359947973, 0.05962277487002981, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.265964787306103e-09, -8.635980485045285e-09, -0.0002810091555406154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092691414881666, 0.23401679135898465, 0.8410150085045758, 0.0, -0.12549127854671643, -0.24497574505774763, -2.608355960179742, -0.7146863868814608, -0.5580674989080651, -1.1978545284643507, -2.8761041534961382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5507943371419204, 0.7721037991406221, 1.2672788624344777, -1.1836355715101474, -2.2101659072623985, -0.5155230332547469, 1.4383339177750694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091267843, -0.4403408959343855, 0.02513727793862914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0393053164340324e-05, 0.00026118502787984593, -8.885415448636424e-05, 0.0, 0.00032976433785099205, 0.00013794718168371885, 4.036322194714469e-05, 0.0004118804506054077, -4.597787821579858e-06, -0.00024021029877926975, -0.0001446211180774292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011730924507034505, 0.037692968215261316, -0.07711312023755544, -0.003150831910545682, 0.009807591123291796, 0.0392862784313995, 0.059621753954225365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7897920090490064e-09, -8.224908377818695e-09, -0.00028272391685331427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926812261786906, 0.23402988986582984, 0.8410113546364125, 0.0, -0.1254747319744555, -0.24496891110737837, -2.6083539390949957, -0.7146657179611566, -0.5580677317620203, -1.1978665659441785, -2.8761114100393854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5501995705682504, 0.7739859735345267, 1.2634180710725733, -1.1837949304919402, -2.209687661112676, -0.5135582639844605, 1.441323046386029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091769961, -0.44034089633000717, 0.025123092917831803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.037740595119924e-05, 0.00026197013690362075, -7.307736326522295e-05, 0.0, 0.0003309314452189297, 0.00013667900738548018, 4.042169492600479e-05, 0.000413378406083312, -4.657079103848079e-06, -0.00024074959655829772, -0.00014513086494717239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011895331473398937, 0.037643487878091735, -0.07721582723808787, -0.0031871796358551034, 0.009564922994449472, 0.039295385405728384, 0.05978257221919284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0042353279090035e-09, -7.91243332768826e-09, -0.00028370041594671626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209267104140628, 0.2340429943556656, 0.8410087467675743, 0.0, -0.12545816787715466, -0.24496215978482463, -2.6083519141469704, -0.7146450246015063, -0.5580679696948085, -1.1978786103348296, -2.8761186733775808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5495950616600683, 0.7758702989590087, 1.2595425870350851, -1.1839564366614876, -2.2092203933095136, -0.5115881754110759, 1.4443276391989144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091630049, -0.44034089671341636, 0.025108892724971923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0369544821449065e-05, 0.00026208979671518603, -5.215737676477587e-05, 0.0, 0.0003312819460165331, 0.0001350264510744388, 4.049896050569199e-05, 0.00041386719300691855, -4.75865576519643e-06, -0.00024088781302224356, -0.00014526676390855757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012090178163641576, 0.0376865084896394, -0.07750968074976214, -0.0032301233909471402, 0.009345356063242948, 0.039401771467691124, 0.060091856257709055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7982296091932287e-10, -7.668184058429974e-09, -0.00028400385719756733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926608744319491, 0.2340560813647748, 0.84100714592006, 0.0, -0.12544161653442082, -0.244955497567562, -2.6083498843726542, -0.7146243440160265, -0.558068214967887, -1.1978906458593799, -2.8761259294668036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5489795953441095, 0.7777601731303376, 1.2556452680292212, -1.1841203496511143, -2.2087633966761158, -0.50960916074856, 1.447353305741198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091030892, -0.4403408970870755, 0.025094702314994995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0333948661378775e-05, 0.00026174018218340985, -3.20169502866619e-05, 0.0, 0.0003310268546768269, 0.00013324434525306686, 4.059548631981508e-05, 0.0004136117095959833, -4.905461569446624e-06, -0.000240710491007444, -0.0001451217844593823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012309326319177109, 0.03779748342657835, -0.07794638011728017, -0.003278259792533467, 0.009139932667958336, 0.03958029325031823, 0.06051333084567211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1983133136278932e-09, -7.473183279607074e-09, -0.00028380819953853617]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926507518548892, 0.23406913975715812, 0.8410063972109484, 0.0, -0.1254250943916626, -0.24494892316027456, -2.608347847602481, -0.7146036957909659, -0.5580684709624298, -1.197902663376985, -2.8761331701051116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5483524295994947, 0.7796573562743375, 1.2517222633995697, -1.1842868227479875, -2.208316486536265, -0.5076193119658289, 1.450403158759081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961090106299, -0.4403408974528865, 0.025080534974728976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.024515411962932e-05, 0.00026116784766674965, -1.4974182231708038e-05, 0.0, 0.0003304428551644765, 0.00013148814574851165, 4.073540347224048e-05, 0.0004129645012103608, -5.11989085565838e-06, -0.00024035035209954281, -0.00014481276615678032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012543314892294048, 0.03794366287999797, -0.07846009259303048, -0.0033294619374617247, 0.008938202797012384, 0.039796975654622084, 0.06099706035765974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8491878388867557e-09, -7.316219767631447e-09, -0.00028334680532038955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092640706247312, 0.23408217066001355, 0.8410063526322429, 0.0, -0.12540860373294258, -0.2449424304491214, -2.60834579975472, -0.7145830813160546, -0.5580687427240117, -1.1979146611692344, -2.876140392932268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477133581084443, 0.7815619052704538, 1.2477731946150523, -1.184455889736394, -2.207879969820352, -0.5056185028546967, 1.4534776604086994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961088954982, -0.44034089781242836, 0.025066391894913224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.009121515419239e-05, 0.000260618057108365, -8.915741105720763e-07, 0.0, 0.00032981317440052325, 0.00012985422306327325, 4.095695521190876e-05, 0.0004122894982256085, -5.435231639094996e-06, -0.00023995584498924465, -0.00014445654312312013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012781429821006966, 0.03809097992232506, -0.07898137569034647, -0.0033813397681313325, 0.008730334318258284, 0.0400161822226447, 0.06149003299236816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3026331635870013e-09, -7.190836763878865e-09, -0.00028286159631504327]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926307691308385, 0.23409518526677917, 0.8410069402647227, 0.0, -0.1253921349031404, -0.24493601079447763, -2.6083437344912714, -0.7145624864817306, -0.5580690372130511, -1.1979266443344707, -2.8761476003795403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5470626671276048, 0.7834724248618756, 1.2438006829971782, -1.184627475277609, -2.207454529886821, -0.5036081384235395, 1.4565749690388725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087651023, -0.44034089816707767, 0.025052263927612763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.987423294722793e-05, 0.0002602921353122936, 1.1752649594739351e-05, 0.0, 0.00032937659604336363, 0.00012839309287525946, 4.1305268976469446e-05, 0.0004118966864805311, -5.889780787719116e-06, -0.00023966330472836243, -0.00014414894544540635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013013819616792176, 0.03821039182843783, -0.07945023235748334, -0.0034317108242994452, 0.008508798670629213, 0.04020728862314311, 0.061946172603460165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.6079186586223684e-09, -7.0929858090402915e-09, -0.0002825593460092203]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926209653450153, 0.23410820123521298, 0.8410082143246913, 0.0, -0.1253756709732818, -0.24492966907772523, -2.6083416402413238, -0.7145418865534288, -0.5580693663526989, -1.1979386237684981, -2.8761547968083865, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5464010059180497, 0.7853865487005857, 1.2398093933607142, -1.1848014244146543, -2.207041062165461, -0.5015906591196544, 1.4596916611728852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961086252894, -0.44034089851804437, 0.025038134870181875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9607571646466996e-05, 0.0002603193686763777, 2.5481199373799305e-05, 0.0, 0.00032927859717196993, 0.0001268343350481614, 4.188499894923267e-05, 0.00041199856603673615, -6.582792954605186e-06, -0.00023958868055025964, -0.0001439285769249745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013233224191099789, 0.038282476774199756, -0.0798257927292779, -0.003478982740907496, 0.008269354427197501, 0.04034958607770108, 0.06233384268025381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7962567570105424e-09, -7.0193344667182365e-09, -0.00028258114861774437]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926113099265617, 0.234121238526162, 0.8410105984550883, 0.0, -0.1253591947926548, -0.24492346106987012, -2.6083394906020354, -0.7145212518834684, -0.5580697569854639, -1.1979506160215903, -2.8761619827878184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5457292068060542, 0.7873015241020881, 1.2358048465440552, -1.184977542987103, -2.206640501330332, -0.49956893056404467, 1.4628236370430239, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961084815775, -0.4403408988663479, 0.025023985465707808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931083690758048e-05, 0.0002607458189806041, 4.768260794038333e-05, 0.0, 0.00032952361254006915, 0.00012416015710208913, 4.2992785767106124e-05, 0.0004126933992083718, -7.812655299679258e-06, -0.0002398450618418897, -0.0001437195886432252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01343598223991072, 0.03829950803004944, -0.08009093633318079, -0.0035223714489752, 0.008011216702579899, 0.0404345711121948, 0.06263951740277536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8742398780104438e-09, -6.966071248459883e-09, -0.0002829880894813476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926018097379936, 0.23413431550550415, 0.8410167207029203, 0.0, -0.12534271040293332, -0.2449177927150775, -2.608337171986235, -0.7145005514573702, -0.5580703255885383, -1.1979626566472965, -2.876169126106767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5450480973304483, 0.7892147697485378, 1.2317922688863037, -1.1851556392368676, -2.206253675763402, -0.4975456560147912, 1.4659670042325852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961083432173, -0.4403408992127139, 0.025009797299432257]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9000377136226644e-05, 0.0002615395868425685, 0.00012244495664020678, 0.0, 0.00032968779442995655, 0.00011336709585256783, 4.637231600443822e-05, 0.00041400852196258844, -1.1372061487813333e-05, -0.00024081251412407916, -0.00014286637897059832, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013622189512117975, 0.03826491292899262, -0.08025155315503234, -0.003561924995294374, 0.007736511338602989, 0.040465490985068735, 0.06286734379122626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7672025351042834e-09, -6.927319278877532e-09, -0.0002837633255110353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925924473431196, 0.23414744577279814, 0.8410295052634726, 0.0, -0.12532615413129616, -0.24491146594222257, -2.6083348858091493, -0.7144797706276045, -0.5580708638242928, -1.1979747109666614, -2.876176309298787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5443583420276428, 0.7911243028203149, 1.2277756938930156, -1.1853355594288222, -2.205881215621574, -0.49552292125638464, 1.4691187756999138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961081996834, -0.4403408995579558, 0.024995556101940583]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.872478974795834e-05, 0.0002626053458798795, 0.0002556912110465393, 0.0, 0.0003311254327433029, 0.00012653545709845852, 4.5723541721021796e-05, 0.0004156165953142211, -1.0764715090429236e-05, -0.00024108638729753126, -0.00014366384040922283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013795106056110737, 0.038190661435542575, -0.08033149986576091, -0.0035984038390933335, 0.007449202836556653, 0.04045469516813203, 0.06303542934656964, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.870679197150595e-09, -6.904837927637466e-09, -0.00028482394983349996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209258321812838, 0.23416063671814646, 0.8410437398870134, 0.0, -0.12530950693366413, -0.2449045021895959, -2.6083326703868854, -0.7144588979179173, -0.5580713315230594, -1.1979867766771146, -2.876183551344064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5436603401302411, 0.7930289777705635, 1.2237574461151752, -1.1855172087541164, -2.205523515013933, -0.4935019358093305, 1.4722772729752847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196108047214, -0.4403408999025876, 0.02498125341052859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8458429479456307e-05, 0.00026381890696620686, 0.00028469247081648613, 0.0, 0.00033294395264052857, 0.0001392750525336554, 4.430844527807723e-05, 0.0004174541937448723, -9.353975332314504e-06, -0.00024131420906434384, -0.00014484090553941895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013960037948034177, 0.03809349900497107, -0.08036495555680431, -0.003632986505881571, 0.007154012152821098, 0.04041970894108255, 0.06316994550741814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0493887787539148e-09, -6.892636135295253e-09, -0.00028605382823986507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925741079071422, 0.23417388915558981, 0.8410558513561877, 0.0, -0.1252927688848866, -0.24489716620190444, -2.608330514922322, -0.7144379299689384, -0.5580717393380537, -1.1979988583162735, -2.876190849474161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5429541857656108, 0.7949285340699397, 1.219738015378438, -1.1857005597806267, -2.20518074960298, -0.49148297443279904, 1.4754422337730737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961078852034, -0.44034090024685824, 0.02496688719657855]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.822044247553129e-05, 0.00026504874886679614, 0.00024222938348463573, 0.0, 0.00033476097555076287, 0.00014671975382885406, 4.3109291263184026e-05, 0.00041935897957802475, -8.15629988416167e-06, -0.00024163278317604285, -0.00014596260194143167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014123087292605495, 0.0379911259875245, -0.08038861473474176, -0.003667020530205452, 0.006855308219058671, 0.04037922753062938, 0.06329921595578203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.240211931340805e-09, -6.8854117509447195e-09, -0.0002873242790007967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925651016993824, 0.2341871982181353, 0.841064560189934, 0.0, -0.12527594904818817, -0.244889683732324, -2.6083283999322955, -0.7144168718483338, -0.5580721071402739, -1.1980109586672534, -2.8761981945080244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5422396885604397, 0.796823478601238, 1.2157162776406405, -1.1858856473286126, -2.204852931173053, -0.48946549449193955, 1.4786146509471971, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961077143157, -0.440340900590808, 0.024952461212057558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8012415519644415e-05, 0.0002661812509097066, 0.00017417667492830742, 0.0, 0.0003363967339687805, 0.00014964939160868815, 4.22998005336657e-05, 0.0004211624120919971, -7.356044404709993e-06, -0.00024200701959800386, -0.00014690067726872157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014289944103422625, 0.03789889062596692, -0.08043475475595119, -0.003701750959717785, 0.006556368598541364, 0.04034959881719022, 0.06344834348246732, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.417755392511266e-09, -6.878994897202412e-09, -0.0002885196904198138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925561871488957, 0.2342005551099568, 0.8410618129676085, 0.0, -0.12525905888066197, -0.24488214897121363, -2.6083263175041984, -0.7143957352424114, -0.5580724431370468, -1.1980230752117988, -2.876205579243565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5415164409760148, 0.7987148547729442, 1.2116899592973498, -1.1860725531242928, -2.204539981107109, -0.4874483756147806, 1.4817964206867469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196107529577, -0.4403409009345591, 0.024937983419938786]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7829100973510103e-05, 0.00026713783642982983, -5.494444651112204e-05, 0.0, 0.00033780335052389384, 0.00015069522220727264, 4.1648561942064236e-05, 0.00042273211844828475, -6.719935459193817e-06, -0.00024233089091155212, -0.0001476947108070534, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0144649516884974, 0.03782752343412516, -0.08052636686581613, -0.0037381159136050312, 0.006259001318883878, 0.04034237754317851, 0.063635394790993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.6947749940585474e-09, -6.875021760779324e-09, -0.00028955584237541106]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925473569686348, 0.23421394931927147, 0.8410514001986437, 0.0, -0.1252421128803267, -0.24487463982329583, -2.6083242575075474, -0.714374534897885, -0.5580727580383967, -1.1980352043068812, -2.876212994467474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5407839134953499, 0.8006039588567667, 1.207656221940558, -1.186261384604039, -2.2042418051162214, -0.48543021847138557, 1.484989893729473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961073308133, -0.4403409012779771, 0.024923463887919817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.766036052164086e-05, 0.0002678841862932682, -0.0002082553792966759, 0.0, 0.0003389200067054922, 0.00015018295835598537, 4.119993302519067e-05, 0.00042400689052663815, -6.298026998768619e-06, -0.00024258190164787988, -0.00014830447818341125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014650549613298546, 0.037782081676448954, -0.08067474713583679, -0.0037766295949263422, 0.005963519817753503, 0.04036314286790055, 0.06386946085452182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.975271951200736e-09, -6.868360176661031e-09, -0.00029039064037935573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092538608537945, 0.23422737072300479, 0.8410381966315522, 0.0, -0.12522512498451718, -0.24486719520491726, -2.6083222122520726, -0.7143532856264078, -0.558073060175217, -1.1980473414524133, -2.8762204318291222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5400415571601024, 0.802492060683494, 1.203612248263087, -1.1864522523033614, -2.203958355577257, -0.48340964194609903, 1.4881974215808351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961071196258, -0.4403409016208386, 0.024908912697799563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7496861379995055e-05, 0.0002684280746661161, -0.00026407134182844635, 0.0, 0.0003397579161902799, 0.00014889236757115187, 4.0905109493422496e-05, 0.0004249854295460771, -6.042736403583455e-06, -0.00024274291064534188, -0.00014874723296733107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014847126704950253, 0.03776203653454571, -0.08087947354941886, -0.0038173539864452552, 0.005668990779289269, 0.04041153050573016, 0.06415055702724443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.223748727891442e-09, -6.857230398915573e-09, -0.0002910238024050965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092529944076841, 0.23424081134161082, 0.8410256342076418, 0.0, -0.1252081083032503, -0.24485987423481367, -2.6083201681803243, -0.7143319993473054, -0.5580733639668903, -1.19805948425245, -2.876227881748336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5392888952123503, 0.8043801749776589, 1.199555730702428, -1.1866452498983047, -2.203689672700999, -0.4813855291015325, 1.4914209744135996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961069010158, -0.44034090196284364, 0.024894338130268572]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.73289222079557e-05, 0.0002688123721204562, -0.00025124847820875187, 0.0, 0.0003403336253374409, 0.0001464194020714956, 4.088143496894334e-05, 0.00042572558204703276, -6.075833466954572e-06, -0.00024285600073301045, -0.00014899838427806628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015053238955041206, 0.037762285883297685, -0.08113035121317991, -0.00385995189886731, 0.005373657525156167, 0.0404822568913309, 0.06447105665528777, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.372200407588851e-09, -6.840101178064515e-09, -0.00029149135061983824]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925213689002095, 0.2342542662563984, 0.8410156966170897, 0.0, -0.12519107192954645, -0.24485269584579836, -2.6083181143208978, -0.7143106838121357, -0.5580736811329241, -1.1980716312967383, -2.8762353371275893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5385255891694956, 0.8062689141714454, 1.1954851943908478, -1.1868404398340329, -2.2034359013919644, -0.47935718789178705, 1.4946618848676878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066785933, -0.44034090230379175, 0.024879745639150908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.715035326296363e-05, 0.00026909829575125156, -0.00019875181104035377, 0.0, 0.0003407274740771001, 0.00014356778030618733, 4.1077188530469014e-05, 0.0004263107033934446, -6.343320675583013e-06, -0.000242940885769391, -0.00014910758505718826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015266120857095179, 0.03777478387572981, -0.08141072623160639, -0.0039037987145622843, 0.00507542618069157, 0.04056682419490884, 0.06481820908176425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.448451342577258e-09, -6.818962556157126e-09, -0.0002918498223532651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925128903715878, 0.23426773395518843, 0.8410091822802671, 0.0, -0.1251740209093694, -0.24484566153708204, -2.608316039956505, -0.7142893418370708, -0.5580740230314425, -1.1980837830640352, -2.8762427927565875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5377514715302819, 0.8081584355938903, 1.191400123617303, -1.1870378465048221, -2.203197285560948, -0.47732441194759734, 1.4979207434700035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961064552824, -0.44034090264356734, 0.024865137375008096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6957057243526444e-05, 0.00026935397580074723, -0.0001302867364530094, 0.0, 0.00034102040354084764, 0.00014068617432632294, 4.1487287853933165e-05, 0.00042683950129745, -6.8379703677965584e-06, -0.00024303534593528628, -0.0001491125799654512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015482352784273262, 0.037790428448899266, -0.08170141547089317, -0.003948133415784107, 0.004772316620325626, 0.04065551888379408, 0.06517717204631435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4662181708756e-09, -6.795512158578875e-09, -0.00029216528285619614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925045163771558, 0.23428121600255097, 0.841006182580274, 0.0, -0.1251569578582527, -0.2448387886481049, -2.6083139287135433, -0.7142679714400227, -0.5580744067173158, -1.198095943175205, -2.8762502430157117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5369665434085289, 0.8100484778689586, 1.1873008984865836, -1.1872374571208901, -2.202974145462632, -0.47528744564920095, 1.5011974420998633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961062340045, -0.44034090298211515, 0.02485051238883319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.674798886404033e-05, 0.00026964094725063224, -5.999399986235081e-05, 0.0, 0.0003412610223343902, 0.0001374577795425186, 4.2224859239858586e-05, 0.0004274079409619088, -7.673717465437287e-06, -0.00024320222339622167, -0.00014900518248552445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015698562435060924, 0.03780084550136615, -0.08198450261439016, -0.003992212321361882, 0.00446280196632445, 0.04073932596792761, 0.06553397259719447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.425557552529118e-09, -6.770956109758903e-09, -0.000292499723498149]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092496254561651, 0.23429471621174008, 0.8410070818992268, 0.0, -0.12513988917033175, -0.24483220114101195, -2.6083117354932526, -0.7142465662167454, -0.5580748787203342, -1.1981081230145345, -2.876257672920959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5361709421772896, 0.8119384662083703, 1.1831885815751473, -1.1874392290545575, -2.2027668457589105, -0.47324687428874174, 1.5044913358973206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961060191408, -0.4403409033193899, 0.024835867359076832]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6523631009647197e-05, 0.00027000418378232623, 1.7986379055652413e-05, 0.0, 0.00034137375841914824, 0.0001317501418588057, 4.38644058126588e-05, 0.000428104465546681, -9.440060369282882e-06, -0.00024359678659280064, -0.00014859810494164313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01591202462478672, 0.03779976678823284, -0.082246338228728, -0.004035438673345594, 0.004145994074430361, 0.04081142720918442, 0.06587787594914715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.2972752186325556e-09, -6.745495156767535e-09, -0.0002929005951271798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924881037954635, 0.23430823941628123, 0.8410104805760512, 0.0, -0.12512278443502178, -0.24482522520652472, -2.6083095683298225, -0.7142251228420964, -0.5580753276019556, -1.1981203016818394, -2.876265125001612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5353648890732149, 0.8138276562638193, 1.1790646163154206, -1.1876431018294107, -2.2025757636634418, -0.47120347108002103, 1.507801477500176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961058005932, -0.4403409036557102, 0.02482119775785553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6301532375350888e-05, 0.00027046409082271354, 6.797353648898557e-05, 0.0, 0.00034209470619956105, 0.00013951868974477018, 4.334326859974839e-05, 0.0004288674929802702, -8.977632425557614e-06, -0.00024357334609904135, -0.00014904161305743515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016121062081492537, 0.037783801108978735, -0.08247930519453568, -0.004077455497066453, 0.0038216419093723523, 0.04086806417441358, 0.0662028320571086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.370951473633228e-09, -6.7264061167353235e-09, -0.00029339202442599564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924800703709684, 0.23432179057086786, 0.8410220134799768, 0.0, -0.1251056348788504, -0.24481791065265449, -2.608307439769383, -0.7142036343470946, -0.5580757402627518, -1.1981324793969663, -2.876272606590669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5345486301753641, 0.815715283537283, 1.174930509137666, -1.187849009680018, -2.202401260338183, -0.46915803691662905, 1.511126864406344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961055784995, -0.44034090399110765, 0.024806498730338414]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6066848990084677e-05, 0.000271023091732647, 0.0002306580785137615, 0.0, 0.0003429911234276098, 0.00014629107740476386, 4.2571208786319135e-05, 0.00042976990003583957, -8.253215924271817e-06, -0.00024355430253760203, -0.00014963178114351563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01632517795701424, 0.037752545469273785, -0.08268214355509021, -0.00411815701214592, 0.003490066505177751, 0.040908683267839405, 0.06650773812336223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.441875061750068e-09, -6.707948679834676e-09, -0.0002939805503423458]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924721542543817, 0.23433537370842256, 0.8410361863605892, 0.0, -0.12508843718601376, -0.24481039522159975, -2.608305342609468, -0.7141820942853051, -0.5580761239398435, -1.1981446603147465, -2.8762801172878922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5337223806981956, 0.8176006922550547, 1.1707875488863044, -1.1880568938312568, -2.202243664018041, -0.46711126031023903, 1.5144666613670423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961053527348, -0.4403409043256543, 0.024791766155124875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5832233173576852e-05, 0.0002716627510938502, 0.00028345761224643766, 0.0, 0.0003439538567329903, 0.0001503086210947443, 4.194319830212943e-05, 0.000430801235789004, -7.673541835312326e-06, -0.00024361835560364367, -0.00015021394446600118, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01652498954337114, 0.037708174355435345, -0.08285920502723475, -0.004157683024774714, 0.0031519264028380908, 0.040935532127800434, 0.06679593921396432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.515292675017828e-09, -6.690933603425866e-09, -0.00029465150427082805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924643533830425, 0.2343489912932732, 0.8410488218063917, 0.0, -0.12507119063353525, -0.2448027929086804, -2.6083032659665797, -0.7141604982942021, -0.558076489693346, -1.1981568485621175, -2.8762876545351124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5328862835321865, 0.8194834221540722, 1.1666366132028636, -1.1882667114267673, -2.2021032639672424, -0.4650636217414324, 1.5178203558558363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961051233105, -0.4403409046594021, 0.024776997345098726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5601742678380886e-05, 0.0002723516970125972, 0.0002527089160520015, 0.0, 0.00034493104957015075, 0.00015204625838715168, 4.153285776985821e-05, 0.000431919822058675, -7.315070048949514e-06, -0.0002437649474163956, -0.00015074494440707218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0167219433201824, 0.03765459798034946, -0.08301871366881823, -0.004196351910210223, 0.002808001015978366, 0.04095277137613264, 0.06707388977588098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.588484374229094e-09, -6.674955954323654e-09, -0.0002953762005229549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924566647408677, 0.2343626439628206, 0.8410582188776666, 0.0, -0.12505389614320422, -0.2447951709450306, -2.6083012010642563, -0.7141388447389879, -0.5580768464749206, -1.198169046739875, -2.876295215589466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5320403872014193, 0.8213632450124095, 1.1624780814579907, -1.1884784401226691, -2.2019803143826557, -0.46301535181210113, 1.5211878305426285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196104890307, -0.4403409049923652, 0.02476219137471044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5377284349828743e-05, 0.0002730533909486646, 0.00018794142549695913, 0.0, 0.0003458898066202609, 0.00015243927299610655, 4.129804646886761e-05, 0.0004330711042844184, -7.135631492355292e-06, -0.0002439635551490929, -0.00015122108707033406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016917926615343505, 0.03759645716674715, -0.08317063489745692, -0.004234573918034956, 0.002458991691729575, 0.04096539858662546, 0.0673494937358462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.660066937348196e-09, -6.659262154159706e-09, -0.00029611940776575553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924490848327904, 0.23437633061949292, 0.8410560835309228, 0.0, -0.12503655431277882, -0.24478752010214577, -2.6082991495782464, -0.7141171348764142, -0.5580771925424345, -1.1981812541074885, -2.8763028006481965, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5311846441002754, 0.8232401533797046, 1.1583118511849793, -1.1886920782222765, -2.201875045276336, -0.4609664411809146, 1.524569354157154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961046486924, -0.44034090532473663, 0.024747349055800713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.515981615443592e-05, 0.0002737331334461661, -4.2706934877010327e-05, 0.0, 0.0003468366085082563, 0.0001530168576964341, 4.102972019804011e-05, 0.0004341972514756301, -6.921350278078256e-06, -0.0002441473522719288, -0.0001517011746054956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017114862022878714, 0.037538167345899924, -0.08332460546022809, -0.004272761992147246, 0.0021053821263965393, 0.04097821262373043, 0.0676304722905131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.8322945298618424e-09, -6.647428706090912e-09, -0.00029684637819448666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924416111709013, 0.23439004885222628, 0.8410461448202162, 0.0, -0.12501916851060207, -0.24477986099661353, -2.608297108373726, -0.7140953718715477, -0.5580775311962143, -1.1981934700527117, -2.8763104073626153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5303189263193195, 0.8251143119355534, 1.1541374375979159, -1.1889076410571624, -2.2017876764519566, -0.458916691640201, 1.527965505878348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961043974682, -0.44034090565650524, 0.024732472576478384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.494732377830591e-05, 0.00027436465466719494, -0.0001987742141298727, 0.0, 0.00034771604353479976, 0.00015318211064475697, 4.082409040750608e-05, 0.0004352600973289408, -6.773075596842037e-06, -0.0002443189044638289, -0.0001521342883787291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017314355619117806, 0.03748317111697732, -0.0834882717412666, -0.004311256697716052, 0.0017473764875824422, 0.0409949908142728, 0.06792303442387358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.024482560456021e-09, -6.6353721321817925e-09, -0.0002975295864465577]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092434241898101, 0.23440379548519505, 0.8410332845986868, 0.0, -0.12500174317378177, -0.24477220846572847, -2.608295074172032, -0.7140735601679984, -0.5580778659557126, -1.1982056933796754, -2.876318032849949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5294430534430056, 0.8269859865684598, 1.1499541243889762, -1.189125154817421, -2.2017184311773126, -0.45686579217268836, 1.5313770578414172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961041372786, -0.4403409059875701, 0.024717564985329347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4738545600715052e-05, 0.0002749326593754455, -0.0002572044305889292, 0.0, 0.00034850673640610146, 0.0001530506177013048, 4.068403387558512e-05, 0.0004362340709858327, -6.695189967279231e-06, -0.00024446653927346663, -0.00015250974666713418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01751745752627855, 0.037433492658127586, -0.08366626417879379, -0.004350275205172314, 0.0013849054928832506, 0.04101798935025297, 0.0682310392613842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.20379147070437e-09, -6.6212970787305426e-09, -0.0002981518229807454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924269768571976, 0.23441756723256021, 0.8410211936055637, 0.0, -0.12498428656625127, -0.24476466142210812, -2.6082930282445553, -0.7140517040554214, -0.5580782163099339, -1.1982179260165966, -2.876325668360499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5285568258487621, 0.8288554673713606, 1.1457611312938534, -1.1893446493034172, -2.2016675466270863, -0.4548134026388708, 1.5348048426790608, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196103873076, -0.44034090631767464, 0.024702629546660564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4530081806884725e-05, 0.0002754349473032083, -0.00024181986246085216, 0.0, 0.0003491321506098486, 0.00015094087240714833, 4.091854953169874e-05, 0.00043712225154075634, -7.007084426564443e-06, -0.0002446527384237837, -0.00015271021099671814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017724551884869048, 0.03738961605801727, -0.08385986190245388, -0.004389889719921877, 0.0010176910045214236, 0.041047790676350795, 0.06855569675287329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.284054276865303e-09, -6.602091496072119e-09, -0.00029870877337561573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924198163869062, 0.2344313611202062, 0.8410122464977837, 0.0, -0.12496680663473403, -0.2447572764006, -2.608290952109812, -0.7140298075149323, -0.5580786015168077, -1.1982301698893667, -2.8763333053410314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5276600565197247, 0.8307230000548407, 1.141557766052324, -1.1895661509740727, -2.2016352798132326, -0.45275922901337, 1.5382496319416816, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961036089454, -0.44034090664660797, 0.024687669311053716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4320940582745845e-05, 0.00027587775291998173, -0.0001789421555994827, 0.0, 0.000349598630344771, 0.00014770043016274956, 4.152269486684434e-05, 0.0004379308097814693, -7.704137474671007e-06, -0.0002448774554009283, -0.00015273961065152483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017935386580748176, 0.03735065366960045, -0.08406730483058789, -0.004430033413108865, 0.0006453362770783385, 0.04108347251001572, 0.0688957852524162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.282608769722518e-09, -6.578666193878617e-09, -0.00029920471213696226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924127625602892, 0.2344451748886894, 0.8410079530709207, 0.0, -0.12494931498664277, -0.244750168298184, -2.6082888080760194, -0.7140078729634463, -0.5580790606308612, -1.1982424314263758, -2.8763409284529082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5267525963935548, 0.8325887363924743, 1.1373435371498235, -1.1897896775209689, -2.2016219084821045, -0.4507030786006588, 1.5417120444288943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961033496475, -0.4403409069741575, 0.02467268668987216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4107653234047511e-05, 0.00027627536966383934, -8.58685372608118e-05, 0.0, 0.00034983296182516905, 0.00014216204832000084, 4.288067585132707e-05, 0.0004386910297200211, -9.182281072144481e-06, -0.0002452307401810137, -0.0001524622375366768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018149202523398262, 0.0373147267526732, -0.08428457805000901, -0.004470530937921876, 0.00026742662256651394, 0.04112300825422484, 0.06924824974425506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.1859567260439755e-09, -6.5509905493119906e-09, -0.00029965242363114023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092405814221847, 0.23445900711925993, 0.8410076193949413, 0.0, -0.12493180308159409, -0.24474297271213807, -2.6082866415957042, -0.7139859042924999, -0.5580795469753796, -1.1982546995110912, -2.876348553631648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5258343494031532, 0.8344527092342277, 1.1331182132852262, -1.1900152349403026, -2.2016277287256725, -0.44864488862339164, 1.5451924969752042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961030939942, -0.440340907300321, 0.024657683298567584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3896676884206326e-05, 0.0002766446114107791, -6.67351958730456e-06, 0.0, 0.0003502381009738575, 0.0001439117209183849, 4.3329606299553536e-05, 0.00043937341892728914, -9.726890369524963e-06, -0.000245361694308613, -0.0001525035747982607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01836493980803164, 0.037279456835067414, -0.08450647729194553, -0.004511148386673094, -0.00011640487135941536, 0.04116379954534321, 0.06960905092619887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.113067642888294e-09, -6.523269362194304e-09, -0.0003000678260915194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923989737066429, 0.23447285729849482, 0.8410173949544465, 0.0, -0.12491426032710078, -0.2447354537589122, -2.608284502251769, -0.71396390406394, -0.5580800095622412, -1.198266962763555, -2.8763561988785353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5249052765248465, 0.8363148320871545, 1.1288818293044027, -1.1902428166137695, -2.201653048920596, -0.4465847280576006, 1.5486911968215638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961028376508, -0.44034090762510103, 0.024642659859163866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3681030408542761e-05, 0.00027700358469752445, 0.00019551119010394067, 0.0, 0.0003508550898663204, 0.00015037906451729831, 4.27868787103912e-05, 0.00044000457119782273, -9.251737232382818e-06, -0.00024526504927672977, -0.00015290493773938857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018581457566134493, 0.03724245705853732, -0.08472767961646975, -0.004551633469339973, -0.0005064038984640953, 0.041203211315821324, 0.06997399692719035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.126869319532842e-09, -6.495600528856092e-09, -0.0003004687880743624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092392244501384, 0.234486725664656, 0.8410311200160856, 0.0, -0.12489668545552522, -0.24472768583321533, -2.6082823951474987, -0.7139418722212836, -0.5580804432043482, -1.1982792199698034, -2.8763638661337536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5239653889266263, 0.8381749203751567, 1.1246346429876275, -1.1904724048381408, -2.201698183225296, -0.4445227753775335, 1.5522081740767828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961025786713, -0.4403409079485101, 0.024627616319695567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3458410517791e-05, 0.0002773673232235325, 0.00027450123278138414, 0.0, 0.0003514974315111833, 0.00015535851393738803, 4.214208540367673e-05, 0.00044063685312759504, -8.672842140828888e-06, -0.0002451441249686973, -0.00015334510436367145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018797751964405293, 0.037201765760044934, -0.08494372633550343, -0.004591764487425716, -0.0009026860940070896, 0.041239053601341294, 0.07033954510438059, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.179590171708666e-09, -6.4681820872776385e-09, -0.00030087078936595537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092385628245801, 0.23450061290819943, 0.841043974989202, 0.0, -0.12487907955192709, -0.24471978613250056, -2.6082803126668055, -0.7139198076214038, -0.5580808557941545, -1.1982914729840688, -2.87637155287179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5230147331040501, 0.840032726778139, 1.1203770586254933, -1.1907039742031829, -2.201763446439512, -0.44245928030608556, 1.555743342117177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961023164102, -0.4403409082705559, 0.024612552136522255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3232511166461702e-05, 0.0002777448708686309, 0.0002570994623296304, 0.0, 0.0003521180719626334, 0.00015799401429511677, 4.164961386793083e-05, 0.0004412919975958298, -8.251796124645198e-06, -0.0002450602853071114, -0.00015373476072257683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01901311645152213, 0.0371561280596449, -0.08515168724268607, -0.004631387300841511, -0.0013052642843153798, 0.04126990142895847, 0.07070336080788225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.245223065171383e-09, -6.440916079248447e-09, -0.000301283663466211]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923791258923294, 0.23451451984754135, 0.841053839335408, 0.0, -0.124861443738691, -0.24471183909284877, -2.6082782461560727, -0.7138977088744598, -0.5580812562752453, -1.198303724005304, -2.876379256266048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5220533722188224, 0.8418879814421235, 1.1161095379235029, -1.1909374956665297, -2.201849150615711, -0.4403945196928669, 1.5592965689997291, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196102050767, -0.44034090859124075, 0.024597466590461522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3004706942721193e-05, 0.0002781387868381211, 0.00019728692411996905, 0.0, 0.00035271626472192926, 0.00015894079303583724, 4.1330214656937515e-05, 0.00044197493888114875, -8.009621817293962e-06, -0.0002450204247059355, -0.00015406788515755283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019227217704553823, 0.03710509327968975, -0.0853504140398068, -0.004670429266939552, -0.0017140835239768332, 0.041295212264373216, 0.0710645376510457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.312866158655143e-09, -6.413697667347336e-09, -0.0003017109212146423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923727385304727, 0.2345284471820798, 0.8410522138073605, 0.0, -0.12484378254230989, -0.24470398536804427, -2.6082761725991963, -0.7138755742604499, -0.5580816683877518, -1.1983159783207948, -2.876386968121842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5210813675425818, 0.8437404292008875, 1.111832515911148, -1.191172940537945, -2.2019556038910966, -0.4383287562399933, 1.56286774570927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961017818023, -0.44034090891060784, 0.024582359033059612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2774723713286888e-05, 0.00027854669076925285, -3.251056095003856e-05, 0.0, 0.00035322392762227256, 0.00015707449608995283, 4.147113752742501e-05, 0.0004426922801981734, -8.242250128389216e-06, -0.0002450863098167964, -0.00015423711587763197, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01944009352481135, 0.03704895517528012, -0.08554044024709782, -0.004708897428303273, -0.002129065507710266, 0.04131526905747279, 0.07142353419081342, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.379290814927804e-09, -6.3873414308310886e-09, -0.000302151148038187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092366466504449, 0.2345423951962035, 0.8410434472930469, 0.0, -0.12482610237027067, -0.2446963384501182, -2.6082740628509478, -0.7138534024818921, -0.5580821222057958, -1.1983282422944421, -2.8763946777497114, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5200987630336469, 0.8455898577733169, 1.107546335549563, -1.1914102836995266, -2.2020831116149004, -0.4362622067468347, 1.566456840158064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961015123277, -0.44034090922857455, 0.024567229195095627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2544052047728873e-05, 0.0002789602824744588, -0.00017533028627138354, 0.0, 0.00035360344078455975, 0.000152938358521538, 4.2194964967829366e-05, 0.0004434355711551118, -9.0763608804408e-06, -0.000245279472945569, -0.00015419255739288778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019652090178698466, 0.03698857144858722, -0.08572360723169974, -0.004746863231634872, -0.002550154476074551, 0.04133098986317244, 0.07178188897588188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.389492783145938e-09, -6.359334203315072e-09, -0.0003025967592796801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923603119785542, 0.23455636366143515, 0.8410353019987932, 0.0, -0.1248084242584862, -0.24468923095470801, -2.6082718269296277, -0.713831191059617, -0.5580827105398091, -1.1983405351414187, -2.876402351621198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.519105575620468, 0.8474361134617115, 1.1032512099441503, -1.1916495054977405, -2.202231978612754, -0.4341950240570607, 1.5700639289912093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961012491604, -0.4403409095449165, 0.024552077293800822]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2309051789507755e-05, 0.00027936930463274916, -0.00016290588507396475, 0.0, 0.00035356223568931217, 0.00014214990820386725, 4.471842639831812e-05, 0.00044422844550102134, -1.1766680265442813e-05, -0.00024585693952967403, -0.00015347742973165416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019863748263576935, 0.03692511376789492, -0.08590251210825339, -0.004784435964277944, -0.0029773399570713964, 0.04134365379548046, 0.07214177666290271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.26334369806623e-09, -6.326839330366228e-09, -0.00030303802589605624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092354267738185, 0.2345703517593418, 0.841037086357163, 0.0, -0.12479072675782128, -0.24468196978950849, -2.608269562166431, -0.71380894456449, -0.5580833331616019, -1.1983528350359811, -2.87641002529331, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5181017919564832, 0.8492791034645827, 1.0989472139222365, -1.1918905930169712, -2.2024025140696923, -0.4321272937656738, 1.5736892075793183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961010055812, -0.4403409098589737, 0.02453690412215113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2088480738122096e-05, 0.0002797619581327564, 3.568716739713108e-05, 0.0, 0.0003539500132983976, 0.00014522330399074646, 4.529526392674975e-05, 0.0004449299025413268, -1.2452435856533942e-05, -0.00024599789125044413, -0.0001534734422348367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020075673279695384, 0.03685980005742207, -0.08607992043827516, -0.004821750384614016, -0.003410709138764685, 0.04135460582773689, 0.07250557176218154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.871585243622658e-09, -6.281143838603349e-09, -0.0003034634329938299]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923483351000108, 0.23458435821041387, 0.8410433690732536, 0.0, -0.1247729928187537, -0.24467419120495768, -2.6082673488459154, -0.7137866672064415, -0.5580839074054937, -1.198365123797158, -2.87641772791869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5170873720815716, 0.85111878546559, 1.0946343060215737, -1.192133538432852, -2.202595032702884, -0.43005904517215826, 1.5773329717200524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961007619495, -0.4403409101713919, 0.024521710933646846]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1865276348927471e-05, 0.0002801290214417316, 0.00012565432181280977, 0.0, 0.00035467878135150756, 0.0001555716910162052, 4.4266410315425116e-05, 0.0004455471609690459, -1.1484877837322644e-05, -0.00024577522353742175, -0.0001540525076079574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020288397498231026, 0.0367936400201483, -0.0862581580132528, -0.00485890831761699, -0.003850372663837832, 0.04136497187031095, 0.07287528281468234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.872635981013225e-09, -6.248363731130677e-09, -0.00030386377008570877]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923425164787207, 0.2345983814792764, 0.841050347506695, 0.0, -0.12475522292646406, -0.24466603816082416, -2.6082651926888545, -0.713764361211254, -0.5580844274851053, -1.1983773992061868, -2.876425460844925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5160622570306792, 0.8529551512103469, 1.09031236495632, -1.1923783374825825, -2.2028098565664673, -0.4279902694218642, 1.5809955887759293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961005111467, -0.4403409104823721, 0.02450649925825024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.163724258027144e-05, 0.0002804653772501444, 0.0001395686688296028, 0.0, 0.0003553978457929012, 0.0001630608826704875, 4.312314121554707e-05, 0.0004461199037493099, -1.0401592232705189e-05, -0.0002455081805767086, -0.00015465852470114935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02050230101784817, 0.03672731489513667, -0.08643882130507669, -0.004895980994609451, -0.004296477271664276, 0.041375515005881276, 0.073252341117538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.0160564280701034e-09, -6.219605362174422e-09, -0.0003042335079320552]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092336812073117, 0.23461241991371726, 0.8410561678621937, 0.0, -0.12473742219781848, -0.24465770728454195, -2.6082630802066746, -0.7137420285191424, -0.5580849074418099, -1.198389663027904, -2.8764332181693337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5150263785751835, 0.8547882069357311, 1.0859812336661037, -1.1926249875088784, -2.2030473162083246, -0.4259209411969448, 1.5846774624480346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961002514438, -0.44034091079192145, 0.024491270776937437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1408811207364125e-05, 0.0002807686888172977, 0.00011640710997282274, 0.0, 0.00035601457291151454, 0.00016661752564447262, 4.224964359557917e-05, 0.0004466538422316748, -9.599134091982837e-06, -0.0002452764343438294, -0.0001551464881691109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020717569109913524, 0.03666111450768433, -0.08662262580432678, -0.004933000525917938, -0.0047491928371491505, 0.041386564498387415, 0.07363747344210625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.194058572993528e-09, -6.190986860384029e-09, -0.00030456962625612414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092331222669531, 0.23462647193549757, 0.841052066079572, 0.0, -0.12471959924255467, -0.24464941954873765, -2.608260982624077, -0.713719670597397, -0.55808537708744, -1.1984019203027907, -2.8764409883123934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5139796698170055, 0.8566179539149585, 1.0816407643975692, -1.1928734852410094, -2.203307750057057, -0.4238510406151482, 1.5883789956931182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960999830891, -0.44034091110001405, 0.02447602713313368]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1178807172321633e-05, 0.00028104043560611415, -8.203565243488869e-05, 0.0, 0.00035645910527626145, 0.00016575471608629082, 4.195165195554541e-05, 0.00044715843490582383, -9.392912601900415e-06, -0.00024514549773298693, -0.00015540286119064626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02093417516356161, 0.03659493958454977, -0.08680938537068913, -0.004969954642621503, -0.005208676974652198, 0.04139801163593095, 0.07403066490167189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.367093402234195e-09, -6.1618522748371104e-09, -0.0003048728760751354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923257491223984, 0.23464053609047267, 0.8410419055366319, 0.0, -0.12470176364589647, -0.24464133781230815, -2.6082588665282125, -0.7136972887095854, -0.5580858710249742, -1.1984141770704049, -2.8764487579958957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5129220742543645, 0.8584443728070699, 1.077290855772315, -1.1931238248543903, -2.2035915028096063, -0.42178057102604194, 1.5921005596733184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960997096226, -0.440340911406489, 0.024460769881989263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0947094264936601e-05, 0.00028128309950176415, -0.0002032108588002307, 0.0, 0.00035671193316402056, 0.00016163472858988137, 4.232191728334855e-05, 0.0004476377562333042, -9.878750685222405e-06, -0.0002451353522834519, -0.00015539367005093068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021151911252818414, 0.03652837784222549, -0.08699817250508257, -0.005006792267617171, -0.005675055050982058, 0.04140939178212616, 0.07443127960400155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.469333852017078e-09, -6.129498761064716e-09, -0.00030514502288832664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923203945074248, 0.234654611139149, 0.8410329760044956, 0.0, -0.12468393783006151, -0.24463381737345521, -2.608256641870117, -0.7136748820675878, -0.5580864822372624, -1.1984264517189394, -2.876456493033111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5118535520675944, 0.86026741417937, 1.0729314763532303, -1.193375996563004, -2.2038989229339174, -0.4197095700785597, 1.59584247316251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960994386653, -0.4403409117110504, 0.024445500384940443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0709229947061336e-05, 0.0002815009735270556, -0.00017859064272867818, 0.0, 0.0003565163166989832, 0.00015040877705849477, 4.449316191303092e-05, 0.000448132839952295, -1.2224245764281534e-05, -0.00024549297069120405, -0.0001547007443032467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0213704437354033, 0.036460827446003485, -0.08718758838169695, -0.005043434172273638, -0.0061484024862227945, 0.041420018949645344, 0.07483826978383265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.41914580147142e-09, -6.091227530342086e-09, -0.00030538994097642047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923151539108384, 0.23466869601465398, 0.8410369603092293, 0.0, -0.12466610730241652, -0.24462629384666287, -2.6082543779253315, -0.7136524549442156, -0.5580871394853086, -1.1984387281294149, -2.876464218332244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5107740827551385, 0.8620869957374822, 1.0685626721506054, -1.1936299866938658, -2.2042303620937327, -0.41763811324967404, 1.5996049968703707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960991865436, -0.44034091201287073, 0.024430219834777226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0481193173066671e-05, 0.0002816975100991661, 7.968609467351684e-05, 0.0, 0.00035661055289996446, 0.00015047053584673302, 4.5278895708661466e-05, 0.0004485424674445845, -1.3144960923647588e-05, -0.0002455282095096486, -0.00015450598266201668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02158938624911852, 0.03639163116224268, -0.08737608405249829, -0.005079802617235855, -0.006628783196301097, 0.04142913657771301, 0.07525047415721449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.042432717502845e-09, -6.0364069223755525e-09, -0.0003056110032643384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923100283255752, 0.23468278982685334, 0.8410444950602779, 0.0, -0.12464825226265315, -0.24461829692062967, -2.6082521656327224, -0.713630011550289, -0.5580877491526708, -1.198450985861604, -2.8764719670998957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5096836649634202, 0.8639030045311199, 1.0641845631582998, -1.1938857771391707, -2.2045861721409685, -0.4155663116254859, 1.603388334133879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960989332096, -0.44034091231267136, 0.024414929235849793]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0251170526505469e-05, 0.00028187624398724346, 0.0001506950209727834, 0.0, 0.00035710079526729164, 0.00015993852066417723, 4.4245852182918864e-05, 0.0004488678785303976, -1.219334724283644e-05, -0.00024515464378050837, -0.0001549753530299669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021808355834365044, 0.03632017587275478, -0.08756217984611223, -0.005115808906095752, -0.007116200944715079, 0.041436032483762424, 0.07566674527016634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.066679126741525e-09, -5.996012086212419e-09, -0.00030581197854868307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923050216204658, 0.23469689186915452, 0.8410516616188889, 0.0, -0.12463037171473912, -0.24460994079275783, -2.6082500133720026, -0.7136075531239947, -0.5580883027034881, -1.1984632225123395, -2.8764797420544017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5085823128939614, 0.8657153051896176, 1.0597973256827151, -1.194143346163699, -2.2049667038536658, -0.4134943030747915, 1.6071926446615838, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196098671681, -0.44034091261067837, 0.024399629399881436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0013410218914426e-05, 0.00028204084602383465, 0.00014333117222068478, 0.0, 0.00035761095828053827, 0.00016712255743682876, 4.304521440058582e-05, 0.0004491685258869663, -1.1071016345658088e-05, -0.0002447330147117217, -0.00015549909012203795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022027041389176896, 0.03624601316995274, -0.08774474951169516, -0.0051513804905646155, -0.007610634253944473, 0.041440171013887465, 0.07608621055409705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.230571128178997e-09, -5.960140387646349e-09, -0.0003059967193671177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923001346662412, 0.23471100150640223, 0.8410570992865238, 0.0, -0.124612469576945, -0.24460141530682628, -2.6082479078840874, -0.7135850801968361, -0.5580888139089831, -1.1984754403653106, -2.876487537895516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5074700501760492, 0.867523751218759, 1.0554011660280609, -1.1944026698833945, -2.2053723078435907, -0.4114222395388834, 1.6110180667421843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960984004842, -0.440340912906907, 0.024384321059351226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.77390844932557e-06, 0.0002821927449540467, 0.000108753352697927, 0.0, 0.00035804275588250685, 0.00017050971863127144, 4.210975830491218e-05, 0.0004494585431732285, -1.0224109900509904e-05, -0.0002443570594232101, -0.0001559168222916129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022245254358245144, 0.036168920582829035, -0.08792319309308277, -0.005186474393909225, -0.008112079798501207, 0.04144127071816173, 0.07650844161200956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.423937811173064e-09, -5.924572664479066e-09, -0.0003061668106041999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092295368781185, 0.23472511812237018, 0.8410525567244167, 0.0, -0.12459455539927589, -0.24459298694859025, -2.608245811408167, -0.7135625925579099, -0.5580893217995248, -1.1984876469894246, -2.876495340225951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5063469036469429, 0.8693281958882545, 1.0509962948414044, -1.1946637235971365, -2.205803335645199, -0.40935027469185803, 1.6148647387961867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960981211883, -0.440340913201293, 0.024369004918805077]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.531770112582698e-06, 0.0002823323193592111, -9.085124214319048e-05, 0.0, 0.0003582835533821116, 0.00016856716472041987, 4.192951841072784e-05, 0.00044975277852422565, -1.0157810831525628e-05, -0.0002441324822768575, -0.00015604660869718368, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02246293058212572, 0.03608889338990902, -0.08809742373312995, -0.005221074274839436, -0.008620556032167825, 0.04143929694050713, 0.07693344108004997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.585919470088617e-09, -5.8877196347280575e-09, -0.00030632281092298554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922907254402637, 0.23473924097755533, 0.8410430468096177, 0.0, -0.12457664465750391, -0.24458494204825634, -2.6082436611804063, -0.7135400894695607, -0.558089891193906, -1.1984998552367652, -2.8765031252828543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5052128977614048, 0.871128501107967, 1.0465829055964682, -1.194926482883499, -2.2062601412752496, -0.4072785536904651, 1.6187328177432267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960978396832, -0.44034091349359755, 0.024353681801970777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.286681842308948e-06, 0.00028245710370275603, -0.00019019829597943813, 0.0, 0.00035821483543939294, 0.00016089800667815171, 4.3004555210236635e-05, 0.0004500617669834312, -1.1387887624443933e-05, -0.00024416494681227545, -0.00015570113806031218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022680117710762223, 0.03600610439425101, -0.08826778489872511, -0.005255185727246861, -0.009136112601008644, 0.04143442002785773, 0.07736157894079969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.630101619651346e-09, -5.8460912789013415e-09, -0.00030646233668602126]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092286203029788, 0.2347533691199173, 0.8410366097666756, 0.0, -0.12455873906782257, -0.24457712016806227, -2.608241455221437, -0.7135175725101464, -0.5580905242752763, -1.1985120646248903, -2.876510891702536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5040680507202013, 0.872924542990264, 1.042161160418863, -1.1951909245602055, -2.2067430834685604, -0.40520720662076, 1.6226224919949306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960975589218, -0.4403409137837116, 0.02433835273812638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.044820950828083e-06, 0.00028256284723898446, -0.00012874085884307046, 0.0, 0.00035811179362700286, 0.00015643760388143953, 4.411917938666845e-05, 0.0004503391882867604, -1.2661627407282987e-05, -0.00024418776250376096, -0.00015532839362946262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022896940824068145, 0.03592083764594023, -0.08843490355210347, -0.00528883353413279, -0.009658843866211879, 0.0414269413941024, 0.0777934850340786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6152266013673606e-09, -5.802281156345202e-09, -0.0003065812768879271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922817994548892, 0.23476750143913333, 0.8410317368181572, 0.0, -0.12454082133663524, -0.24456902851836237, -2.6082392747393492, -0.713495046101068, -0.5580911374821886, -1.1985242565890923, -2.87651866889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5029123732057359, 0.8747162132660619, 1.0377311860746754, -1.1954570270293148, -2.207252526997856, -0.40313634677010934, 1.6265339855381478, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960972813505, -0.4403409140713817, 0.024323018905498428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.807149797687654e-06, 0.0002826463843210159, -9.74589703665631e-05, 0.0, 0.0003583546237463803, 0.00016183299399782965, 4.360964175396415e-05, 0.00045052818156762596, -1.2264138246990007e-05, -0.0002438392840411457, -0.00015554380207734861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02311355028930857, 0.035833405515955936, -0.0885994868837508, -0.005322049382186002, -0.010188870585910479, 0.04141719701301333, 0.07822987086434155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5514245871595604e-09, -5.753402196005454e-09, -0.000306676652559026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922775208871658, 0.23478163673089025, 0.8410269189424823, 0.0, -0.12452290749927553, -0.2445610802733366, -2.60823705671734, -0.7134725099597611, -0.5580917959042532, -1.1985364438454809, -2.876526432828552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5017458688935809, 0.876503417771528, 1.0332930775127567, -1.1957247695296482, -2.2077888417223948, -0.4010660722071327, 1.6304675538598268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196097005762, -0.44034091435659856, 0.02430768157447591]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.557135447079631e-06, 0.00028270583513837535, -9.63575134987599e-05, 0.0, 0.00035827674719448194, 0.00015896490051578013, 4.4360440186066256e-05, 0.00045072282613815867, -1.3168441291317371e-05, -0.00024374512776992012, -0.00015527871823862847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023330086243100588, 0.03574409010932276, -0.08876217123837545, -0.005354850006668302, -0.010726294490778453, 0.041405491259532884, 0.07867136643357993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5117697080917796e-09, -5.704337183720439e-09, -0.00030674662045039944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092273364795529, 0.23479577360256368, 0.8410267217978544, 0.0, -0.12450499913756155, -0.2445531912725162, -2.6082348019596893, -0.7134499663025892, -0.5580924988772874, -1.1985486250627273, -2.876534182971404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5005685356159986, 0.8782860735546842, 1.0288469036469596, -1.1959941324338006, -2.2083524046662615, -0.3989964689225732, 1.6344234810585367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960967315432, -0.44034091463937164, 0.024292342210012866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.31218327346479e-06, 0.00028273743346835396, -3.942892555852602e-06, 0.0, 0.000358167234279383, 0.00015778001640777447, 4.50951530158411e-05, 0.0004508731434375434, -1.4059460683804483e-05, -0.00024362434492997581, -0.00015500285704769982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02354666555164614, 0.03565311566312634, -0.08892347731593916, -0.005387258083048048, -0.011271258877333048, 0.04139206569119055, 0.07911854397420086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4843783973253375e-09, -5.655461688257759e-09, -0.00030678728926084454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092269328669074, 0.2348099105758585, 0.8410328085718266, 0.0, -0.12448707681038215, -0.2445448705057502, -2.608232602889105, -0.7134274203571955, -0.5580931513025706, -1.1985607790395163, -2.876541952707773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4993803688712595, 0.880064103097541, 1.0243927211786348, -1.1962650965612587, -2.208943599389502, -0.3969276174649741, 1.6384020683100775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960964513507, -0.440340914919795, 0.02427700236992856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.072252910155402e-06, 0.00028273946589653745, 0.00012173547944455026, 0.0, 0.00035844654358794566, 0.0001664153353203612, 4.398141168845759e-05, 0.00045091890787210125, -1.3048505665113734e-05, -0.00024307953578067693, -0.00015539472737960248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023763334894781794, 0.03556059085713516, -0.08908364936649825, -0.005419282549162722, -0.011823894464809255, 0.04137702915198115, 0.07957174503081545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6038510622082095e-09, -5.608466697218602e-09, -0.00030679680168615704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922654166067067, 0.23482404617815011, 0.8410412273442239, 0.0, -0.12446914038951988, -0.24453622390550075, -2.608230468085501, -0.7134048745361499, -0.5580937444931828, -1.1985729027930856, -2.876549744394196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49818136574451966, 0.8818374283976583, 1.019930589651557, -1.1965376419472014, -2.2095628134221337, -0.3948595998606208, 1.6424036197278522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960961632773, -0.44034091519783325, 0.024261663614724982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.824124734902576e-06, 0.0002827120458322431, 0.0001683754479456738, 0.0, 0.0003587284172453867, 0.00017293200498848488, 4.2696072079051175e-05, 0.00045091642091311116, -1.1863812242775575e-05, -0.00024247507138728597, -0.00015583372845762609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023980062534796138, 0.035466506002346784, -0.08924263054155514, -0.00545090771885237, -0.012384280652634735, 0.04136035208706627, 0.08003102835549275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.761465067164659e-09, -5.5607647810329235e-09, -0.00030677510407153255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922616295505392, 0.23483817896123738, 0.8410490852513846, 0.0, -0.12445119489880907, -0.24452743829899679, -2.6082283837711637, -0.7133823305847966, -0.5580942928161348, -1.198584998145203, -2.8765575520800817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4969715275917248, 0.8836059669803608, 1.0154605812500674, -1.196811747499963, -2.2102104377362424, -0.39279250428916135, 1.6464284343560336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095867687, -0.44034091547339604, 0.024246327492719974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.574112335228865e-06, 0.0002826556617451584, 0.00015715814321276875, 0.0, 0.00035890981421632693, 0.00017571213007928167, 4.1686286744317405e-05, 0.0004508790270657108, -1.0966459037819545e-05, -0.00024190704235009058, -0.00015615371771426863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024196763055897286, 0.035370771654048096, -0.08940016802979006, -0.0054821110552363845, -0.012952486282172465, 0.04134191142918913, 0.0804962925636271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.911807805937267e-09, -5.5112561318106675e-09, -0.0003067224401001848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922579680585263, 0.23485230751964287, 0.8410551260082697, 0.0, -0.12443324572456714, -0.24451864694277212, -2.6082263344864067, -0.7133597902155533, -0.5580948123792668, -1.1985970672594228, -2.8765653691833957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49575086226104903, 0.8853696289438552, 1.0109827884664662, -1.1970873906083481, -2.2108868656457132, -0.39072642862796775, 1.65047679939993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960955656938, -0.4403409157463759, 0.024230995521878285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.322984026012576e-06, 0.0002825711681099264, 0.00012081513770211566, 0.0, 0.00035898348483850577, 0.00017582712449362893, 4.098569513964275e-05, 0.0004508073848668016, -1.0391262641673134e-05, -0.00024138228439390562, -0.0001563420662759655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02441330661351502, 0.035273239269888054, -0.0895558556720272, -0.005512862167700783, -0.013528558189413202, 0.04132151322387183, 0.08096730087792933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.039863141520829e-09, -5.459597199002481e-09, -0.00030663941683379875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922544348864547, 0.23486643055305054, 0.8410516600789181, 0.0, -0.12441531025423512, -0.24451022400760422, -2.608224252247095, -0.7133372533672377, -0.558095373430019, -1.198609123703882, -2.876573169694533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4945193854577599, 0.8871283156303824, 1.006497328144911, -1.1973645468070087, -2.2115924913823406, -0.388661482186963, 1.6545489860475655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095262447, -0.44034091601655695, 0.024215669123602613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.066344143356634e-06, 0.0002824606681536391, -6.931858703256564e-05, 0.0, 0.0003587094066402643, 0.00016845870335784188, 4.1644786232455846e-05, 0.00045073696631083623, -1.1221015042756142e-05, -0.00024112888918500513, -0.00015601022275316007, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02462953606578174, 0.035173733730543714, -0.08970920643110362, -0.00554312397321154, -0.014112514732550215, 0.041298928820095435, 0.0814437329527083, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0649334679944005e-09, -5.403621012739874e-09, -0.00030652796551343983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922510287796178, 0.23488054673289557, 0.8410453123797789, 0.0, -0.12439739345231203, -0.24450208979585292, -2.608222123215735, -0.7133147218632591, -0.5580959904178329, -1.198621169241677, -2.876580947616735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4932771206221174, 0.8888819200328602, 1.002004340587019, -1.1976431899810067, -2.2123277102860492, -0.38659778527636235, 1.658645250560513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196094961182, -0.44034091628382155, 0.02420034975651545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.812213673893282e-06, 0.00028232359690059553, -0.00012695398278336715, 0.0, 0.00035833603846176075, 0.00016268423502602524, 4.2580627199534485e-05, 0.00045063007957435767, -1.2339756277197146e-05, -0.00024091075590005698, -0.00015555844404097243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02484529671285001, 0.035072088049553814, -0.08985975115784277, -0.005572863479960354, -0.014704378074173489, 0.04127393821201264, 0.08192529025895022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0252987988901175e-09, -5.345292444117205e-09, -0.0003063873417432767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922477524753944, 0.23489465477246935, 0.8410452074994145, 0.0, -0.12437950954869476, -0.24449439493203598, -2.6082198931027345, -0.7132921961287746, -0.5580967194820536, -1.1986332144417962, -2.87658868200518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4920240985108147, 0.8906303281832448, 0.997503986963954, -1.1979232922787466, -2.2130929177335372, -0.38453546777582476, 1.6627658355278006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960946663445, -0.44034091654796714, 0.02418503883586631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.55260844684948e-06, 0.00028216079147531595, -2.0976072879545196e-06, 0.0, 0.0003576780723454631, 0.00015389727633898903, 4.460226001287e-05, 0.00045051468968865444, -1.4581284414749146e-05, -0.00024090400238012088, -0.00015468776889814983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025060442226055177, 0.03496816300769299, -0.0900070724612974, -0.005602045954796174, -0.015304148949760347, 0.0412463500107513, 0.08241169934575161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.896747979429786e-09, -5.282911832871913e-09, -0.0003062184129828008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922445995118852, 0.23490875335282946, 0.8410484974848362, 0.0, -0.12436162721644259, -0.2444862530313363, -2.6082177053556697, -0.7132696829483258, -0.5580974129435289, -1.1986452270616588, -2.876596425174763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49076035572194887, 0.8923734214703991, 0.9929964432129866, -1.198204825000671, -2.213888511169073, -0.38247466647819256, 1.6669109766511037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960943694733, -0.4403409168091144, 0.024169737799255797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.305927018371171e-06, 0.00028197160720243975, 6.57997084341371e-05, 0.0, 0.00035764664504322043, 0.00016283801399335354, 4.3754941293355606e-05, 0.00045026360897635297, -1.3869229504038548e-05, -0.0002402523972538747, -0.00015486339166848937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025274855777316755, 0.03486186574308656, -0.09015087501934801, -0.005630654438487442, -0.015911868710717047, 0.04121602595264391, 0.0829028224660603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.937423846599186e-09, -5.22294577457969e-09, -0.00030602073221025353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922415758091562, 0.2349228411724104, 0.8410526983818923, 0.0, -0.12434374248924537, -0.24447768873916056, -2.60821558440803, -0.7132471849890912, -0.5580980457685073, -1.19865720078781, -2.8766041854502538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4894859337370256, 0.8941110786251171, 0.9884818963113168, -1.1984877579817428, -2.214714887686934, -0.38041552288820757, 1.6710809034491936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960940678644, -0.4403409170672489, 0.02415444805994494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.047405458144199e-06, 0.0002817563916189022, 8.401794112132126e-05, 0.0, 0.0003576945439442653, 0.00017128584351477422, 4.241895279880636e-05, 0.0004499591846913434, -1.2656499568355628e-05, -0.00023947452302428265, -0.00015520550981206458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025488439698465194, 0.034753143094359555, -0.09029093803339643, -0.005658659621436673, -0.016527530357216394, 0.04118287179970025, 0.08339853596179836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.03217883464038e-09, -5.1626905210071585e-09, -0.00030579478621716805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922386825645328, 0.23493691690624557, 0.8410564512649941, 0.0, -0.1243258594111105, -0.24446889925952728, -2.6082135201018084, -0.7132247038994421, -0.5580986285853954, -1.1986691367474456, -2.8766119583016656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48820087632289133, 0.8958431793631576, 0.983960534776307, -1.1987720604255176, -2.2155724461756536, -0.3783581789414705, 1.6752758485502535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960937612354, -0.4403409173222983, 0.024139171052652106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786489246427161e-06, 0.0002815146767031294, 7.505766203420739e-05, 0.0, 0.00035766156269743726, 0.00017578959266584843, 4.1286124428578224e-05, 0.0004496217929827031, -1.1656337761063967e-05, -0.00023871919271227572, -0.00015545702823389334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025701148282685583, 0.03464201476081067, -0.09042723070019727, -0.005686048875495764, -0.017151169774387676, 0.04114687893474189, 0.08389890202119733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.132577920404379e-09, -5.1009871084421215e-09, -0.00030554014585668624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092235922605165, 0.23495097923899583, 0.8410519427358509, 0.0, -0.12430799797295512, -0.24446039171558423, -2.6082114331239783, -0.7132022392024135, -0.5580992433130904, -1.1986810509852375, -2.8766197135440503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4869052277139634, 0.8975696069788188, 0.9794325421284801, -1.1990577012557722, -2.2164615881936442, -0.37630277396989964, 1.679496053466264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960934548712, -0.4403409175740272, 0.024123908203004432]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.519918735469442e-06, 0.0002812466550050523, -9.017058286262138e-05, 0.0, 0.0003572287631076722, 0.00017015087886112826, 4.173955660569902e-05, 0.00044929394057188977, -1.2294553899290337e-05, -0.00023828475583984556, -0.00015510484769303776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025912972178559337, 0.034528552313223757, -0.09055985295653808, -0.005712816605088591, -0.017782840359812042, 0.04110809943141729, 0.08440409832021027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.127284994485085e-09, -5.034578465706776e-09, -0.0003052569929535026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922332950507752, 0.23496502672304753, 0.841047783413629, 0.0, -0.12429016966556214, -0.24445225590891467, -2.60820928186934, -0.7131797919809006, -0.5580999330293639, -1.1986929512033815, -2.8766274348355845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48559903131642573, 0.8992902496173529, 0.9748980930181969, -1.199344649530385, -2.2173827195828784, -0.3742494430608768, 1.6837417729196484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196093153261, -0.44034091782227236, 0.02410866107571083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.2551087796667704e-06, 0.0002809496810341711, -8.318644443892944e-05, 0.0, 0.00035656614785969763, 0.0001627161333910628, 4.3025092769582105e-05, 0.0004489444302589652, -1.3794325470608606e-05, -0.0002380043628809906, -0.000154425830679982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02612392795075296, 0.03441285277068236, -0.09068898220566399, -0.005738965492258566, -0.018422627784678763, 0.04106661818045598, 0.08491438906769068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0322003801230195e-09, -4.964903312858732e-09, -0.0003049425458720436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922307991070202, 0.23497905786820408, 0.8410556573019119, 0.0, -0.12427237387831729, -0.2444442940500671, -2.608207077567316, -0.7131573652116887, -0.5581006863642975, -1.1987048335720254, -2.8766351253435607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4842823300878567, 0.9010049998697255, 0.9703573543408388, -1.1996328745291291, -2.2183362506259474, -0.3721983176407974, 1.6880132741548193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960928754658, -0.44034091806592374, 0.024093431277851397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.991887509777812e-06, 0.0002806229031311392, 0.00015747776565822725, 0.0, 0.0003559157448970038, 0.00015923717695157525, 4.408604048309066e-05, 0.00044853538423953636, -1.5066698673928943e-05, -0.00023764737287945692, -0.00015381015952641166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026334024571381103, 0.0342950050474507, -0.09081477354716017, -0.005764499974883995, -0.01907062086137703, 0.041022508401587915, 0.08543002470341639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.555908666280711e-09, -4.8730279323739366e-09, -0.00030459595718869284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922284323115387, 0.23499307108162593, 0.8410620224473074, 0.0, -0.12425458744531685, -0.24443588510526554, -2.608204929517324, -0.7131349647765528, -0.5581013908433606, -1.1987166731633414, -2.8766428246415074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48295516731288507, 0.9027137532260882, 0.9658104886496258, -1.1999223453926828, -2.219322595734824, -0.37014952706588417, 1.6923108338763249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960925990926, -0.4403409183058999, 0.024078220512936645]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.7335909628940805e-06, 0.00028026426843671655, 0.00012730290790996507, 0.0, 0.00035572866000864066, 0.00016817889603117935, 4.296099983475214e-05, 0.00044800870271772164, -1.408958126273807e-05, -0.0002367918263207148, -0.00015398595893936561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02654325549943236, 0.034175067127253114, -0.09093731382426007, -0.005789417271074297, -0.019726902177531216, 0.040975811498265485, 0.08595119443011036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527463615746055e-09, -4.799523095846143e-09, -0.0003042152982949902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922261997224498, 0.2350070647912494, 0.8410577045336366, 0.0, -0.12423681243828566, -0.24442719122016499, -2.6082028373758583, -0.7131125929317202, -0.5581020469926288, -1.1987284688445206, -2.876650531726507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48161758806816896, 0.904416406601707, 0.9612576589459293, -1.2002130305739471, -2.2203421712282, -0.36810320061496893, 1.696634732660511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196092317279, -0.44034091854252083, 0.024063030469186026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.465178177833702e-06, 0.00027987419246927657, -8.635827341689408e-05, 0.0, 0.00035550014062387086, 0.00017387770201113094, 4.184282931522522e-05, 0.000447436896650261, -1.3122985361760713e-05, -0.0002359136235845094, -0.0001541416999878178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026751584894322514, 0.034053067512376585, -0.09105659407393087, -0.005813703625287087, -0.020391509867517234, 0.04092652901830437, 0.08647797568372015, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.636273932491716e-09, -4.732419414340443e-09, -0.00030380087501240055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922241016812146, 0.23502103740905048, 0.8410463694385787, 0.0, -0.12421905333043677, -0.24441836995158422, -2.608200790619741, -0.7130902517633231, -0.5581026658436722, -1.198740221602538, -2.8766582417647193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48026963952599694, 0.9061128577303539, 0.9566990298493572, -1.20050489804106, -2.221395396086243, -0.36605946817557733, 1.700985254766309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960920279746, -0.44034091877582304, 0.024047862863995576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.1960824706491225e-06, 0.0002794523560217615, -0.0002267019011576197, 0.0, 0.00035518215697770964, 0.00017642537161540508, 4.0935122353427696e-05, 0.0004468233679431487, -1.2377020867531316e-05, -0.00023505516034913785, -0.00015420076425019393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026958970843440316, 0.03392902257293763, -0.09117258193144308, -0.005837349342256303, -0.02106449716086064, 0.04087464878783213, 0.08701044211595904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786086760284027e-09, -4.666044771786301e-09, -0.00030335210380902497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922221440887018, 0.23503498739762702, 0.841036886455467, 0.0, -0.1242013481825966, -0.24441026653189415, -2.608198632835657, -0.7130679387372286, -0.5581034088108263, -1.1987519639596742, -2.876665895865233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4789113717793767, 0.9078030043511358, 0.9521347702517232, -1.200797914844916, -2.222482690370258, -0.3640184612869564, 1.7053626847014656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196091741422, -0.4403409190052954, 0.024032719370823248]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.915185025717901e-06, 0.0002789997715310093, -0.0001896596622333224, 0.0, 0.00035410295680355535, 0.0001620683938012719, 4.315568167552039e-05, 0.0004462605218899997, -1.4859343083454556e-05, -0.0002348471427225327, -0.00015308201027994006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027165354932404285, 0.03380293241563895, -0.09128519195267903, -0.005860336077119565, -0.021745885680302154, 0.04082013777241842, 0.08754859870313353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.731050726891179e-09, -4.58944610775106e-09, -0.0003028698634465459]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922203164538525, 0.23504891307276912, 0.841032541842507, 0.0, -0.12418366740896726, -0.24440192084839657, -2.6081965020990285, -0.7130456612191032, -0.5581041338020172, -1.1987636644722774, -2.876673544051086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4775428382354116, 0.9094867432162603, 0.9475650547121593, -1.2010920480404839, -2.223604478160592, -0.3619803142765615, 1.7097673090060426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960914598313, -0.4403409192310516, 0.02401760180827296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.655269698775106e-06, 0.00027851350284206105, -8.689225920218913e-05, 0.0, 0.00035361547258678437, 0.00016691366995180907, 4.2614732565614394e-05, 0.00044555036250906017, -1.4499823817667592e-05, -0.00023401025206547227, -0.0001529637170595984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027370670879302096, 0.033674777302491084, -0.09139431079127737, -0.005882663911359049, -0.022435755806672526, 0.04076294020789779, 0.08809248609153901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.631816940030336e-09, -4.515125428379149e-09, -0.0003023512510057976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218624636338, 0.23506281281421168, 0.8410356756575126, 0.0, -0.12416600432264169, -0.24439321694763538, -2.608194436426376, -0.7130234228233399, -0.5581048018148895, -1.1987753136380845, -2.876681199480581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47616409798292436, 0.9111639678647261, 0.9429900709564467, -1.2013872631601683, -2.224761182138141, -0.3599451670496676, 1.7141994056720824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960911738547, -0.44034091945324066, 0.024002511926413173]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383635029025387e-06, 0.00027799482885125325, 6.26763001119526e-05, 0.0, 0.00035326172651137423, 0.0001740780152235415, 4.131345304538199e-05, 0.00044476791526665467, -1.3360257447749238e-05, -0.00023298331614080524, -0.0001531085898994188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027574805049744477, 0.03354449296931504, -0.09149967511425215, -0.005904302393688978, -0.023134079550981332, 0.04070294453787818, 0.08864193332079673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.719530654727784e-09, -4.443781211465503e-09, -0.0003017976371957132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922170704203732, 0.23507668502075083, 0.8410423074849374, 0.0, -0.1241483623155468, -0.244384310557527, -2.6081924300125126, -0.7130012257667365, -0.5581054190160493, -1.1987869114340584, -2.876688859076571, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47477521540227136, 0.9128345692861699, 0.9384100182269607, -1.20168352459866, -2.225953224315494, -0.35791316440846443, 1.7186592461985255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960908809377, -0.44034091967180033, 0.02398745145288188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1084319293768643e-06, 0.00027744413078277237, 0.0001326365484943806, 0.0, 0.00035284014189772793, 0.00017812780216790056, 4.01282772728635e-05, 0.00044394113206605953, -1.2344023195454017e-05, -0.00023195591947688265, -0.00015319191979646822, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02777765161305974, 0.033412028428875376, -0.09160105458971957, -0.0059252287698322425, -0.02384084354705729, 0.04064005282406402, 0.08919681052886042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.858339466261557e-09, -4.371193406864528e-09, -0.00030120947062583256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922156543450052, 0.23509052810004516, 0.8410492694389827, 0.0, -0.12413074689682618, -0.24437535618911002, -2.6081904678915984, -0.712979072046481, -0.5581060010212636, -1.1987984597786585, -2.8766965163409224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47337625952659734, 0.9144984368578705, 0.9338251048857156, -1.2019807958468574, -2.2271810265116145, -0.3558844549669417, 1.7231470978947316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960905813695, -0.44034091988659374, 0.023972422108249798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8321507362843026e-06, 0.00027686158588654494, 0.00013923908090758875, 0.0, 0.00035230837441229307, 0.00017908736833938907, 3.9242418287363135e-05, 0.0004430744051094812, -1.1640104287746735e-05, -0.00023096689200289316, -0.00015314528703072957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02797911751348016, 0.03327735143401081, -0.09169826682490159, -0.00594542496394866, -0.024556043922417028, 0.0405741888304541, 0.08975703392412263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.99136182881903e-09, -4.295868409399808e-09, -0.00030058689264164613]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092214376950768, 0.2351043404631002, 0.841055000947925, 0.0, -0.12411316316685755, -0.24436644803037927, -2.6081885369185116, -0.7129569637734708, -0.5581065615745155, -1.1988099601669355, -2.8767041654304397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4719673035386995, 0.916155459116594, 0.9292355465253229, -1.2022790396236822, -2.228445010501852, -0.3538591902620027, 1.7276632254874882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196090276409, -0.44034092009746506, 0.023957425614455224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.554788474152601e-06, 0.00027624726110047753, 0.00011463017884518368, 0.0, 0.0003516745993725979, 0.000178163174614961, 3.861946173756925e-05, 0.0004421654602037304, -1.1211065038467111e-05, -0.00023000776553994804, -0.0001529817903483625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02817911975795758, 0.033140445174471, -0.09179116720785228, -0.005964875536498757, -0.025279679804751456, 0.04050529409878031, 0.0903225518551289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.099211472283008e-09, -4.217426245952425e-09, -0.00029992987589149664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132402106286, 0.23511812054038544, 0.8410520894025295, 0.0, -0.12409562383109912, -0.2443578314158735, -2.608186590890484, -0.712934902017406, -0.5581071484951111, -1.1988214212369817, -2.8767117882556934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47054842423382764, 0.9178055245993192, 0.9246415639932796, -1.202578217928743, -2.229745597925077, -0.3518375237867856, 1.7322078925422681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196089970556, -0.4403409203040926, 0.023942463678312494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2734802787669106e-06, 0.00027560154570521126, -5.8230907909955594e-05, 0.0, 0.000350786715168619, 0.0001723322901152663, 3.892056055380001e-05, 0.00044123512129748107, -1.1738411910820731e-05, -0.0002292214009220766, -0.0001524565050773675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028377586097436923, 0.033001309654503014, -0.09187965064086771, -0.0059835661012142315, -0.02601174846449523, 0.0404333295043409, 0.09089334109560107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.1170619527525975e-09, -4.1325504136064795e-09, -0.00029923872285463716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922122434115142, 0.23513186671753447, 0.8410480627601596, 0.0, -0.12407813314545002, -0.24434945545829273, -2.608184620574443, -0.7129128891496048, -0.5581077715045112, -1.198832843569758, -2.8767193803773026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4691197012732411, 0.9194485226447213, 0.9200433810360168, -1.2028782923185342, -2.2310832111884804, -0.34981960999287814, 1.7367813640484877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960896649155, -0.44034092050638907, 0.02392753805860094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.993598228687448e-06, 0.0002749235429804493, -8.053284739664491e-05, 0.0, 0.00034981371298213994, 0.00016751915161527365, 3.9406320815882495e-05, 0.0004402573560225493, -1.2460188001387484e-05, -0.00022844665552575148, -0.00015184243218659447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028574459211730487, 0.032859960908041684, -0.09196365914525552, -0.006001487795825586, -0.026752265268074542, 0.04035827587814968, 0.09146943012439056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.112808490593471e-09, -4.045929541332256e-09, -0.00029851239423111863]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211389827854, 0.23514557736365363, 0.8410578585477725, 0.0, -0.12406070988152301, -0.24434158934098602, -2.608182553769859, -0.7128909254979008, -0.5581085052234442, -1.1988442413850604, -2.8767269140492373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4676812169158026, 0.9210843438719359, 0.9154412233761499, -1.2031792237209296, -2.2324582726969604, -0.3478056037279826, 1.741383906369289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960893591872, -0.44034092070432945, 0.023912650529372945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7071673205114855e-06, 0.00027421292238309636, 0.00019591575225744434, 0.0, 0.00034846527854018143, 0.000157322346134472, 4.133609168080293e-05, 0.0004392730340808338, -1.4674378662152341e-05, -0.00022795630604805403, -0.00015067343869631415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02876968714876997, 0.032716424544291745, -0.09204315319733973, -0.006018628047907992, -0.027501230169602837, 0.0402801252979109, 0.09205084641602652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.114568185997018e-09, -3.958807443717854e-09, -0.0002977505845598786]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210672469882, 0.23515925083401482, 0.8410652320488057, 0.0, -0.12404332566823896, -0.24433336627992613, -2.608180522997439, -0.7128690180598636, -0.5581092132659031, -1.1988555845615416, -2.876734437299029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46623305579286745, 0.9227128804080058, 0.9108353175470177, -1.2034809732727259, -2.2338712072731286, -0.3457956600814619, 1.7460157904635891, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960890519567, -0.44034092089783095, 0.02389780286694324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4347159446389079e-06, 0.00027346940722347367, 0.00014747002066334785, 0.0, 0.0003476842656809194, 0.00016446122119761613, 4.0615448397339356e-05, 0.0004381487607450033, -1.4160849177094524e-05, -0.00022686352962361731, -0.00015046499583523993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896322245870369, 0.03257073072139712, -0.09211811658264313, -0.00603499103592687, -0.028258691523363376, 0.04019887293041388, 0.09263768188600079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.144607672069865e-09, -3.870029836860596e-09, -0.0002969532485941604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210100400509, 0.23517288551398433, 0.8410664138041404, 0.0, -0.1240259996089749, -0.24432528532443024, -2.608178454395147, -0.7128471669546982, -0.5581099719448497, -1.198866887773201, -2.8767419218274246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4647753056448859, 0.9243340253193703, 0.9062258936717704, -1.2037835010299036, -2.235322437674143, -0.3437899350125588, 1.750677285561212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960887517417, -0.44034092108648143, 0.023882996819733292]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1441387459766836e-06, 0.0002726935993901465, 2.3635106694689962e-05, 0.0, 0.00034652118528124735, 0.0001616191099181937, 4.1372045842379415e-05, 0.0004370221033072508, -1.5173578930017302e-05, -0.0002260642331865976, -0.00014969056791598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029155002959631346, 0.03242289822728867, -0.09218847750494656, -0.006050555143554061, -0.029024608020289562, 0.04011450137806245, 0.09322990195245989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.004299680337448e-09, -3.7730098884789655e-09, -0.0002961209441989173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092209669726632, 0.23518647970489048, 0.8410609226416369, 0.0, -0.12400872906868333, -0.24431719191532206, -2.608176369004111, -0.7128253755692321, -0.5581107597717642, -1.1988781450453656, -2.876749374387809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4633080561386832, 0.9259476735196431, 0.9016131818317626, -1.2040867669585253, -2.236812388228808, -0.34178858417897373, 1.7553686651971052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960884538656, -0.44034092127040986, 0.023868234227515342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.613477534914119e-07, 0.00027188381812338203, -0.00010982325006922625, 0.0, 0.000345410805831185, 0.00016186818216330927, 4.170782071484811e-05, 0.0004358277093212305, -1.575653829063398e-05, -0.00022514544329536624, -0.0001490512076832327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029344990124054126, 0.03227296400545834, -0.09225423680015506, -0.006065318572435898, -0.02979901109329317, 0.0400270166717004, 0.09382759271786134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.957524940023932e-09, -3.6785690750768175e-09, -0.0002952518443589767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093822929072, 0.2352000317341201, 0.8410524181684602, 0.0, -0.12399151746904731, -0.24430910863530028, -2.608174261444083, -0.7128036463850764, -0.5581115824848359, -1.1988893561534155, -2.876756791973215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46183139963036696, 0.9275537212519152, 0.8969974141792522, -1.2043907305783736, -2.238341482998964, -0.3397917636906221, 1.7600902039997306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960881578726, -0.4403409214495698, 0.0238535169087839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.748674497860114e-07, 0.0002710405845922016, -0.00017008946353326963, 0.0, 0.0003442319927206149, 0.0001616656004355191, 4.215120056168994e-05, 0.00043458368311318613, -1.645426143494226e-05, -0.0002242221609999945, -0.00014835170811919904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029533130166324435, 0.03212095464544021, -0.09231535305020915, -0.006079272396967082, -0.030581895403125385, 0.039936409767033054, 0.09443077605250862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.91986084688446e-09, -3.5831994274456708e-09, -0.0002943463746288033]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373323128, 0.23521353992827793, 0.8410438725266971, 0.0, -0.12397436044111262, -0.244300887496518, -2.6081721601693726, -0.7127819829808627, -0.558112410947662, -1.1989005135506143, -2.876764184099484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4603454313905481, 0.9291520657795702, 0.8923788256592536, -1.204695351075815, -2.239910145922031, -0.33779963049762673, 1.7648421773105925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960878624786, -0.4403409216239188, 0.023838846682848473]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8992118888876934e-07, 0.0002701638831565353, -0.00017091283526128758, 0.0, 0.0003431405586938345, 0.00016442277564585636, 4.202549420018781e-05, 0.00043326808427352663, -1.6569256520598532e-05, -0.00022314794397777974, -0.0001478425253884784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029719364796376244, 0.03196689055310157, -0.09237177039997145, -0.006092409948825406, -0.031373258461334215, 0.03984266385990679, 0.09503946621723514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907879199330411e-09, -3.486980077253522e-09, -0.00029340451870856404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373722798, 0.23522700262504698, 0.8410374403757168, 0.0, -0.12395726578111037, -0.24429269050492022, -2.6081700407288655, -0.7127603871926259, -0.5581132705496118, -1.1989116211622244, -2.8767715407119447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.458850249996433, 0.9307426050694383, 0.8877576552539141, -1.2050005870186693, -2.2415187994729133, -0.3358123427934258, 1.7696248590278236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196087569427, -0.4403409217933179, 0.023824225354744655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.993361838705048e-11, 0.0002692539353811438, -0.00012864301960679008, 0.0, 0.0003418932000452387, 0.00016393983195510124, 4.2388810139131095e-05, 0.0004319157647347982, -1.719203899706572e-05, -0.00022215223220196987, -0.00014713224921229104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029903627882302698, 0.03181078579736128, -0.09242340810678894, -0.006104718857087361, -0.03217307101764898, 0.039745754084018536, 0.09565363434462144, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.861033564134219e-09, -3.387982440439172e-09, -0.0002924265620763873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093803793915, 0.23524041814845156, 0.8410374906842297, 0.0, -0.12394022730095001, -0.2442843307062041, -2.6081679394647272, -0.712738862857545, -0.558114124022187, -1.198922669739127, -2.8767788742441045, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4573459573374052, 0.9323252377254454, 0.8831341459157536, -1.2053063966618953, -2.2431678654292573, -0.33383006012496247, 1.7744385224039096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960872769383, -0.4403409219577329, 0.02380965473961995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.860142235474362e-07, 0.0002683104680918212, 1.0061702575075656e-06, 0.0, 0.0003407696032069348, 0.00016719597432282023, 4.202528276281991e-05, 0.00043048670161862127, -1.706945150298024e-05, -0.0002209715380559683, -0.0001466706431985636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03008585318055555, 0.031652653120141615, -0.09247018676321055, -0.00611619286451865, -0.032981319126879634, 0.039645653369266835, 0.09627326752172037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.849774123333481e-09, -3.2882997372638714e-09, -0.0002914123024940956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922096657396688, 0.2352537848481625, 0.8410424879608319, 0.0, -0.12392323099804707, -0.24427550322994218, -2.608165926451545, -0.7127174147928246, -0.5581148993177725, -1.1989336427949417, -2.876786209655038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4558326592403161, 0.9338998624960788, 0.8785085463058647, -1.2056127377883856, -2.2448577636846556, -0.3318529440691488, 1.7792834377311177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960869837198, -0.44034092211708964, 0.023795136622358486]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.707205544453632e-07, 0.00026733399421898104, 9.99455320436035e-05, 0.0, 0.00033992605805876916, 0.00017654952523818242, 4.026026364787405e-05, 0.00042896129440782137, -1.550591171088359e-05, -0.0002194611162937864, -0.000146708218664564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030265961941782726, 0.03149249541266861, -0.09251199219777764, -0.0061268225298059045, -0.03379796510796265, 0.039542321116274225, 0.09689830654416252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.86437310864071e-09, -3.187134913313221e-09, -0.00029036234522933065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922100965552448, 0.23526710107514773, 0.8410490640684287, 0.0, -0.12390627994451152, -0.2442664026430487, -2.60816399756591, -0.7126960453592284, -0.5581156008578939, -1.198944539937928, -2.8767935444610173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4543104655338203, 0.9354663782831726, 0.8738811111354717, -1.2059195673919778, -2.246588910859805, -0.3298811581868147, 1.7841598707715598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960866898349, -0.4403409222713018, 0.023780672785392188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.616311522513805e-07, 0.0002663245397044324, 0.0001315221519361624, 0.0, 0.000339021070711086, 0.0001820117378696219, 3.857771269517252e-05, 0.0004273886719234314, -1.4030802428831007e-05, -0.00021794285972423394, -0.0001466961195899939, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030443874129915626, 0.031330315741874865, -0.09254870340785973, -0.006136592071843622, -0.03462294350299033, 0.039435717646682064, 0.09752866080883925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.877696582075045e-09, -3.0842428966251893e-09, -0.00028927673932593894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210673237465, 0.235280365187046, 0.8410550975979828, 0.0, -0.12388938100491373, -0.24425724891563522, -2.608162132255566, -0.7126747564615128, -0.5581162500032212, -1.1989553642943187, -2.8768008700700447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4527794894455337, 0.9370246848142204, 0.8692520991614596, -1.2062268420164741, -2.2483617212788136, -0.3279148672301889, 1.7890680851332526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960863958802, -0.4403409224202819, 0.023766265007226756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1533644406949973e-06, 0.00026528223796546833, 0.00012067059108091881, 0.0, 0.00033797879195573256, 0.00018307454826957186, 3.73062068809094e-05, 0.00042577795431106595, -1.2982906544877191e-05, -0.0002164871278149365, -0.00014651218054448473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030619521765731874, 0.031166130620956245, -0.09258023948024134, -0.006145492489924126, -0.03545620838017727, 0.03932581913251551, 0.09816428723385391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.879091789393594e-09, -2.979601671892309e-09, -0.0002881555633086335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211398984335, 0.2352935755878579, 0.8410555050831465, 0.0, -0.12387255996124569, -0.24424862974986714, -2.6081602276898908, -0.7126535474193972, -0.5581169529252559, -1.198966136758033, -2.8768081474179703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4512398472649066, 0.9385746831577152, 0.8646217720329866, -1.20653451772497, -2.2501766065511055, -0.32595423653796046, 1.7940083427031794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960861098235, -0.4403409225636437, 0.023751915023692883]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.451493739797756e-06, 0.0002642080162376779, 8.149703274743813e-06, 0.0, 0.0003364208733607873, 0.00017238331536136223, 3.809131350543452e-05, 0.00042418084231146783, -1.4058440694780964e-05, -0.00021544927428580668, -0.00014554695851592048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03079284361254177, 0.030999966869896325, -0.0926065425694596, -0.00615351416991691, -0.036297705445837984, 0.03921261384456869, 0.09880515139853736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.721133778020836e-09, -2.8672360332484574e-09, -0.00028699967067747945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221227393265, 0.23530673061450377, 0.8410565945129704, 0.0, -0.12385584263010913, -0.24424086611527335, -2.608158181332645, -0.7126324177743517, -0.5581178155082985, -1.1989768780505843, -2.8768153374764402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4496916576505383, 0.9401162761748174, 0.8599903925518251, -1.2068425503342475, -2.252033976608772, -0.3239994313693354, 1.798980905793647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960858334568, -0.4403409227013466, 0.02373762464347082]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.749896630280465e-06, 0.0002631005329173592, 2.1788596477419196e-05, 0.0, 0.00033434662273115046, 0.00015527269187593876, 4.092714491516038e-05, 0.0004225929009102559, -1.7251660853081745e-05, -0.0002148258510234415, -0.00014380116939687583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030963792287366225, 0.03083186034204511, -0.09262758962322996, -0.006160652185548577, -0.037147401153326536, 0.0390961033725009, 0.09945126180934931, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527332100915927e-09, -2.7540586281405656e-09, -0.0002858076044412479]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132919391548, 0.23531982864719386, 0.841063223931719, 0.0, -0.1238392122362804, -0.24423321920061875, -2.6081560758377376, -0.7126113735463446, -0.5581187527877131, -1.1989875685837716, -2.8768224695965015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44813504236501883, 0.941649368224787, 0.8553582259425409, -1.2071508962014381, -2.2539342407502954, -0.3220506177501416, 1.8039860375006576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196085635504, -0.44034092283093423, 0.023723395630806134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.03601300906797e-06, 0.0002619606538019357, 0.0001325883749712573, 0.0, 0.0003326078765743858, 0.000152938293091898, 4.210989814999217e-05, 0.0004208845601416009, -1.8745588290554045e-05, -0.00021381066374907771, -0.00014264240122127474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031132305710390124, 0.030661840999390497, -0.09264333218568391, -0.006166917343814103, -0.03800528283046801, 0.038976272383875785, 0.10010263414021117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.959053397238659e-09, -2.5917525910362977e-09, -0.00028458025329374653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922144519139135, 0.2353328680869434, 0.8410676669346647, 0.0, -0.12382263726512502, -0.24422491913739267, -2.6081540567514145, -0.7125904214700881, -0.5581196148820815, -1.1989981758353803, -2.8768295968508615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4465701270552781, 0.9431738636921824, 0.8507255432224222, -1.207459510790999, -2.2558778039573784, -0.3201079635102819, 1.8090239953968683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960854533182, -0.4403409229545072, 0.023709229726479042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199495176391782e-06, 0.00026078879499084965, 8.886005891627416e-05, 0.0, 0.0003314994231077098, 0.00016600126452181964, 4.038172646392046e-05, 0.00041904152513015484, -1.7241887368174105e-05, -0.0002121450321726098, -0.00014254508720348415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03129830619481516, 0.030489909347908482, -0.09265365440237223, -0.006172291791215753, -0.03887126414166291, 0.038853084797193384, 0.1007591579242136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.643715639193411e-09, -2.4714595723696988e-09, -0.00028331808654188023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922157604694372, 0.23534584736592495, 0.8410668504909772, 0.0, -0.12380612670554354, -0.24421636926187285, -2.6081520936769205, -0.7125695627130906, -0.5581204332535905, -1.1990087053101475, -2.8768367071660017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4449970414885467, 0.94468966757663, 0.8460926213960657, -1.2077683487512805, -2.2578650650041974, -0.3181716381099931, 1.8140950299117282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960852664008, -0.44034092307275113, 0.023695128639661108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6171110473867365e-06, 0.0002595855796310719, -1.6328873750977248e-05, 0.0, 0.0003302111916294966, 0.00017099751039630092, 3.9261489880747366e-05, 0.0004171751399507709, -1.636743018040559e-05, -0.0002105894953461487, -0.00014220630280115963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146171133462829, 0.030316077688951552, -0.09265843652713089, -0.006176759205631756, -0.0397452209363828, 0.038726508005776, 0.1014206902972002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.738346712078653e-09, -2.3648780842152937e-09, -0.00028202173635868386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922172187093444, 0.235358764914175, 0.8410654898822433, 0.0, -0.12378970357889556, -0.24420812020919186, -2.608150095496031, -0.7125487967681349, -0.5581213019711135, -1.1990191755044783, -2.8768437658949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4434159178476597, 0.9461966869587102, 0.8414597384723083, -1.2080773645313565, -2.2598964193485593, -0.31624181071038876, 1.8191993904816701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960850686543, -0.4403409231858745, 0.023681094082104545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.916479814417497e-06, 0.00025835096500088103, -2.721217467799101e-05, 0.0, 0.0003284625329597579, 0.00016498105361986836, 3.996361778996376e-05, 0.00041531889911317413, -1.7374350460272283e-05, -0.00020940388661766464, -0.00014117457796544163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03162247281773904, 0.03014038764160504, -0.09265765847514915, -0.006180315601519984, -0.040627086887241, 0.038596547992087005, 0.10208721139883624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.954931207271424e-09, -2.2624669460461017e-09, -0.00028069115113125986]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218820509567, 0.2353716191701673, 0.8410633476626547, 0.0, -0.1237733545919424, -0.24419974024874178, -2.6081481290056185, -0.7125281285220432, -0.5581221523588407, -1.1990295706059233, -2.8768507967261296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44182689050891993, 0.9476948312002192, 0.8368271724979245, -1.2083865130951508, -2.2619722611590123, -0.31431865007858156, 1.824337328212959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960848777775, -0.44034092329331354, 0.02366712775352238]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2036004456094876e-06, 0.0002570851198458028, -4.28443917725028e-05, 0.0, 0.00032697973906325436, 0.00016759920900176153, 3.932980824228668e-05, 0.000413364921835116, -1.7007754542764683e-05, -0.00020790202889795674, -0.0001406166245909901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03178054677479595, 0.02996288483018038, -0.09265131948767472, -0.006182971275886583, -0.04151683620905522, 0.038463212636144044, 0.10275875462577573, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.817535953222311e-09, -2.1487807233846523e-09, -0.00027932657164330354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221916360722, 0.23538440877937317, 0.84113623431204, 0.0, -0.12375716825404547, -0.24419305877140782, -2.608145824566453, -0.7125075583188882, -0.5581233419857754, -1.1990400234739393, -2.87685766726029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44024420765108996, 0.9491709563510456, 0.832235792593017, -1.208693270166394, -2.2640751584080365, -0.31229657903902314, 1.829464531952495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960847210564, -0.4403409233974491, 0.023653231142714507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.861953054122794e-07, 0.000255792184117114, 0.0014577329877055664, 0.0, 0.00032372675793870207, 0.00013362954667919574, 4.6088783318532606e-05, 0.0004114040630983184, -2.3792538695589267e-05, -0.0002090573603190461, -0.0001374106832015365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03165365715659935, 0.02952250301652904, -0.0918275980981496, -0.006135141424863823, -0.04205794498048291, 0.04044142079116874, 0.10254407479071907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1344232765148914e-09, -2.0827119200966643e-09, -0.00027793221615745386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922201868250198, 0.23539634306990492, 0.8412314006554471, 0.0, -0.12374207508064684, -0.24418789206263306, -2.6081432812967753, -0.7124882530489969, -0.5581248514787112, -1.1990499100341336, -2.8768639699113385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43850370439191116, 0.9507742115167876, 0.8272174784440234, -1.209027128457125, -2.266421303994671, -0.30998379134964577, 1.8351043704068524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846727415, -0.44034092351037646, 0.02364019598329647]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0464356000538463e-06, 0.00023868581063525855, 0.0019033268681426727, 0.0, 0.00030186346797247786, 0.00010333417549517549, 5.0865393554811415e-05, 0.0003861053978273925, -3.0189858715893594e-05, -0.00019773120388399588, -0.00012605302097634758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.034810065183576266, 0.03206510331484076, -0.10036628297987271, -0.006677165814621422, -0.0469229117326932, 0.04625575378754693, 0.11279676908714747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.66298946820811e-10, -2.2585461717950393e-09, -0.0002607031883607115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922216437310262, 0.2354080849464401, 0.8413213449530466, 0.0, -0.12372725721475548, -0.24418254640448694, -2.6081406111655814, -0.7124692442472988, -0.5581265156307138, -1.1990596621045952, -2.8768701100452763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43673363940883975, 0.9523871568461224, 0.8221391334650482, -1.2093648423795467, -2.26884706203803, -0.30766750998431247, 1.840851733829424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846677342, -0.44034092362250954, 0.023627366179124365]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.913812013021153e-06, 0.00023483753070400228, 0.00179888595198974, 0.0, 0.0002963573178272846, 0.00010691316292219053, 5.340262387741816e-05, 0.0003801760339596849, -3.328304005376323e-05, -0.00019504140923134718, -0.00012280267875417538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03540129966142834, 0.03225890658669601, -0.10156689957950295, -0.006754278448434319, -0.0485151608671812, 0.046325627306666436, 0.11494726845142962, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0014635555554529e-10, -2.242661711052622e-09, -0.00025659608344215124]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922230828349167, 0.23542179120280785, 0.8413961196175765, 0.0, -0.1237101320622456, -0.2441748125719034, -2.608137768907168, -0.7124473589817228, -0.5581281884138987, -1.1990708510518875, -2.8768772695111755, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4350979902425157, 0.9538648375688505, 0.8174609802263084, -1.2096783122332178, -2.271137094484585, -0.305621782567045, 1.846191036079717, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960845977244, -0.4403409237343511, 0.02361258903531463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8782077809993562e-06, 0.0002741251273545041, 0.0014954932906001, 0.0, 0.00034250305019766023, 0.0001546766516706125, 5.684516826768007e-05, 0.0004377053115208709, -3.3455663696616285e-05, -0.00022377894584475218, -0.0001431893179887565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03271298332648065, 0.029553614454562817, -0.09356306477479633, -0.006269397073421333, -0.04580064893110514, 0.04091454834535009, 0.10678604500586072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4001961193872394e-09, -2.236830667351529e-09, -0.0002955428761946808]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922243783393282, 0.23543903852997633, 0.8414513434500096, 0.0, -0.12368880508011355, -0.24416378984995993, -2.60813464483527, -0.7124202454252593, -0.5581298364460988, -1.1990846663697565, -2.876886296613515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4336623984435202, 0.9551532708001835, 0.8133606711026311, -1.209957272600563, -2.273199334011333, -0.3039200237919479, 1.850916595958042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196084406267, -0.44034092384720275, 0.023594268486829852]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.591008822977664e-06, 0.0003449465433696476, 0.001104476648661621, 0.0, 0.0004265396426407557, 0.00022045443886932763, 6.248143796103482e-05, 0.0005422711292714019, -3.296064400230728e-05, -0.0002763063573822093, -0.00018054204678421757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02871183597991043, 0.02576866462665916, -0.08200618247354668, -0.00557920734690619, -0.041244790534955666, 0.034035175501941975, 0.09451119756650121, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8291438123780864e-09, -2.2570332791828863e-09, -0.00036641096969553655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922255106794738, 0.23546013123742882, 0.8414867720698173, 0.0, -0.12366286242224352, -0.24414972837577267, -2.6081311939056873, -0.7123873802711952, -0.558131470146458, -1.1991013861642983, -2.876897373484767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43242675695397453, 0.9562573128632461, 0.8098307629874593, -1.2102024622712715, -2.2750240339463406, -0.30252510162345925, 1.8550265512441675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960840910455, -0.44034092395784474, 0.023572049757173866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.26468029088339e-06, 0.0004218541490494525, 0.0007085723961537018, 0.0, 0.0005188531574006369, 0.00028122948374484466, 6.901859164659148e-05, 0.0006573030812827114, -3.267400718439803e-05, -0.0003343958908373568, -0.00022153742504650204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02471282979091402, 0.022080841261251077, -0.07059816230343761, -0.004903793414171123, -0.036493998700152935, 0.027898443369773075, 0.0821991057225074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.304433286892409e-09, -2.2128403986714446e-09, -0.000444374593119745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922265159170025, 0.23548434886488395, 0.8415061255847035, 0.0, -0.1236330840946502, -0.24413351552177873, -2.608127454022146, -0.7123497254554765, -0.5581331059967973, -1.19912053705499, -2.8769101520880205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43135851539591985, 0.9572093754222624, 0.8067750353053372, -1.2104195732844663, -2.276643595151556, -0.3013598281014676, 1.8586187114510089, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960836810974, -0.44034092406159986, 0.023546586131306835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.010475057647412e-06, 0.0004843525491029461, 0.00038707029772529206, 0.0, 0.0005955665518662969, 0.0003242570798786655, 7.479767081710877e-05, 0.0007530963143733585, -3.2717006786872644e-05, -0.00038301781383230676, -0.00025557206506673664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021364831161093535, 0.01904125118032559, -0.06111455364244099, -0.00434222026389549, -0.032391224104307406, 0.023305470439832707, 0.07184320413682947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.19896031598218e-09, -2.0751025149419598e-09, -0.000509272517340654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922274555400075, 0.23551049919664788, 0.8415149219583403, 0.0, -0.12360081504552632, -0.24411619699799172, -2.6081235111311813, -0.712308950582451, -0.5581347560571188, -1.1991412817206182, -2.876924034508455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4304134333681977, 0.9580505897866057, 0.8040671225441811, -1.2106158703853926, -2.2781080914157794, -0.30034361325339415, 1.861827325592487, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960832140596, -0.44034092415520626, 0.023519010503724798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8792460097681025e-06, 0.0005230066352782863, 0.00017592747273691278, 0.0, 0.000645380982477355, 0.00034637047574014696, 7.885781929856352e-05, 0.0008154974605094604, -3.3001206429091666e-05, -0.00041489331256218425, -0.0002776484086882363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018901640554443433, 0.016824287286867967, -0.05415825522312133, -0.003925942018529482, -0.029289925284466382, 0.020324296961469136, 0.06417228282956303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.340756875042724e-09, -1.8721281955298883e-09, -0.0005515125516407263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922283902802277, 0.23553740499180734, 0.8415182253375447, 0.0, -0.12356741262006192, -0.244098656648433, -2.6081194585706613, -0.7122667452605677, -0.5581364278203959, -1.1991627663390112, -2.876938417438849, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295475700577736, 0.9588204602625764, 0.8015834397600468, -1.2107984291261271, -2.2794706522647883, -0.2994086858988451, 1.8647869579812928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960827229942, -0.4403409242374828, 0.02349046859225637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8694804402221444e-06, 0.0005381159031892923, 6.606758408896761e-05, 0.0, 0.000668048509288048, 0.00035080699117424197, 8.105121039951375e-05, 0.0008441064376684413, -3.3435265540814266e-05, -0.0004296923678604655, -0.000287658607876933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01731726620848244, 0.015397409519414065, -0.04967365568268607, -0.003651174814689638, -0.027251216980177163, 0.01869854709098071, 0.059192647776113216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.821306158070047e-09, -1.6455303699486633e-09, -0.0005708382293685547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092229362213521, 0.23556419214109076, 0.8415193673058253, 0.0, -0.12353391477712479, -0.24408145874473222, -2.608115372253596, -0.7122244048578634, -0.5581381237752528, -1.1991843319310758, -2.8769528395699946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42872445430342665, 0.9595510565704616, 0.7992223359452336, -1.2109731199137916, -2.280777720365814, -0.2985065236544123, 1.8676104953770492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196082231266, -0.4403409243088011, 0.02346183822581013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9438665863407815e-06, 0.0005357429856686259, 2.283936561278392e-05, 0.0, 0.0006699568587426542, 0.0003439580740157031, 8.17263413041995e-05, 0.000846808054083768, -3.39190971396814e-05, -0.0004313118412897082, -0.000288442622914387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01646231508693933, 0.01461192615770454, -0.04722207629626339, -0.003493815753291094, -0.026141362020514175, 0.018043244888655965, 0.056470747915129293, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.83456558593435e-09, -1.426367202242299e-09, -0.000572607328924798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922303880110799, 0.23559038168015178, 0.8415199852882396, 0.0, -0.1235009259124147, -0.24406483268837104, -2.6081113018315367, -0.7121826869037292, -0.5581398408669545, -1.1992055894462346, -2.876967032815702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42791895589001544, 0.9602641198930109, 0.7969141609822934, -1.2111440345584141, -2.2820628385253374, -0.2976091306509349, 1.8703766996585587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960817519064, -0.4403409243703063, 0.02343363234899367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0515951175859435e-06, 0.0005237907812203649, 1.2359648284266457e-05, 0.0, 0.0006597772942017476, 0.000332521127223907, 8.140844119091067e-05, 0.0008343590826838142, -3.4341834033013567e-05, -0.0004251503031771353, -0.00028386491415034406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016109968268223928, 0.014261266450985874, -0.04616349925880549, -0.0034182928924479396, -0.02570236319046215, 0.017947860069547936, 0.055324085630191866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.587193975638144e-09, -1.2301036995276342e-09, -0.00056411753632922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922314643975465, 0.23561584225978577, 0.8415206281416071, 0.0, -0.12346865914893124, -0.24404875443383964, -2.6081072718949243, -0.7121418622418272, -0.5581415717556476, -1.1992263960601717, -2.8769809036549896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4271176920472807, 0.9609710640627841, 0.7946219475397546, -1.2113134147462656, -2.2833449298152786, -0.29670604552711033, 1.8731283167796038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960812893364, -0.44034092442329237, 0.023406033978459983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152772933227082e-06, 0.0005092115926796831, 1.2857067350550212e-05, 0.0, 0.0006453352696690721, 0.0003215650906277757, 8.059873225149452e-05, 0.0008164932380410139, -3.461777386295665e-05, -0.00041613227874423325, -0.0002774167857476666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016025276854695188, 0.014138883395464165, -0.045844268850776165, -0.0033876037570306798, -0.025641825798819465, 0.018061702476492185, 0.05503234242090225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.251399377513169e-09, -1.0597212265636223e-09, -0.0005519674106737503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092232580107623, 0.23564067171667163, 0.8415212349419124, 0.0, -0.1234370605731956, -0.24403306406223987, -2.608103288474411, -0.7121018685308353, -0.5581433072688579, -1.1992467787880954, -2.87699447765998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42631633281947695, 0.9616754935931877, 0.792333738387956, -1.2114820654238903, -2.2846310717664897, -0.29579816557776584, 1.8758799956162546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960808423015, -0.4403409244688435, 0.023379000395382613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2314201529564266e-06, 0.0004965891377175496, 1.2136006107188386e-05, 0.0, 0.0006319715147126685, 0.0003138074319952333, 7.966841026668133e-05, 0.000799874219836588, -3.4710264206142476e-05, -0.0004076545584751738, -0.0002714800998085875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016027184556074832, 0.014088590608071366, -0.045764183035973204, -0.003373013552493929, -0.025722839024224495, 0.01815759898688995, 0.055033576733016905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.940694945966608e-09, -9.110227440188435e-10, -0.000540671661547411]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209223372539627, 0.23566506806782841, 0.8415217812975562, 0.0, -0.12340594956291107, -0.24401758090343914, -2.6080993451677648, -0.7120624836986472, -0.5581450407705657, -1.1992668474692554, -2.8770078362267806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42551557505713944, 0.9623767297213253, 0.7900514091170274, -1.2116499838904833, -2.2859214864877115, -0.29489107317242, 1.8786305914415817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960804069877, -0.44034092450770895, 0.023352380809571575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2905772941065556e-06, 0.00048792702313550185, 1.0927112874049084e-05, 0.0, 0.0006222202056907677, 0.00030966317601457835, 7.88661329248291e-05, 0.0007876966437629345, -3.4670034157743676e-05, -0.0004013736231996911, -0.00026717133601586484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01601515524674981, 0.014024722562751344, -0.045646585418570494, -0.003358369331861143, -0.0258082944244407, 0.018141848106916394, 0.055011916506542455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.706274311049773e-09, -7.773093037112224e-10, -0.0005323917162207316]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922348953618178, 0.23568922979927492, 0.8415222566785925, 0.0, -0.123375129465284, -0.24400216448610904, -2.608095430822606, -0.712023463875547, -0.5581467688719711, -1.1992867246130448, -2.8770210672879366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42471767050002407, 0.9630727822489621, 0.7877811163116816, -1.2118169029211905, -2.28721408021122, -0.29399025899148507, 1.8813739028142424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960799793762, -0.4403409245403216, 0.023326009828649293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3399310956571104e-06, 0.00048323462893022737, 9.507620725404603e-06, 0.0, 0.0006164019525410937, 0.00030832834660205323, 7.828690317029863e-05, 0.000780396462003816, -3.456202810875578e-05, -0.0003975428757877269, -0.00026462122312433816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015958091142307503, 0.013921050552737518, -0.045405856106917414, -0.003338380614145172, -0.02585187447017159, 0.018016283618698822, 0.05486622745321367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.552228758823872e-09, -6.522531359252474e-10, -0.000527419618445673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092236089442465, 0.2357133007651516, 0.8415226672037902, 0.0, -0.12334445117290906, -0.24398673651659994, -2.6080915348528966, -0.7119846230807773, -0.5581484910085028, -1.199306504474441, -2.877034237148521, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42392436326708854, 0.9637620898156535, 0.785527656721029, -1.2119826123190947, -2.2885072294691815, -0.29309891318302905, 1.8841050985136476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196079556518, -0.4403409245668912, 0.023299761418517764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.388161294365743e-06, 0.0004814193175336523, 8.210503954310316e-06, 0.0, 0.0006135658474991242, 0.00030855939018207835, 7.791939418756594e-05, 0.0007768158953953921, -3.4442730633713985e-05, -0.0003955972279284372, -0.00026339721168615413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015866144658710776, 0.013786151333827379, -0.045069191813052134, -0.003314187958082865, -0.02586298515922863, 0.01782691616911975, 0.054623913988103075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.457162595218221e-09, -5.313923472491648e-10, -0.0005249682026306076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922373096431715, 0.2357373554602591, 0.8415230305637231, 0.0, -0.12331383313096314, -0.24397127446279795, -2.6080876499174175, -0.71194585879409, -0.5581502083641651, -1.1993262395279525, -2.8770473817984348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4231361474736072, 0.9644441377747965, 0.7832924464386829, -1.2121470755077381, -2.2898008375515504, -0.292217667083622, 1.8868230698752826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960791368715, -0.44034092458751367, 0.023273566174345575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4404014132461273e-06, 0.00048109390215006183, 7.267198659375373e-06, 0.0, 0.0006123608389183291, 0.00030924107603955115, 7.769870958462718e-05, 0.0007752857337444723, -3.4347113243743554e-05, -0.00039470107022578484, -0.0002628929982758232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015764315869626497, 0.013640959182861963, -0.04470420564692132, -0.003289263772868496, -0.025872161647381108, 0.017624921988140904, 0.05435942723269867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.392931709869209e-09, -4.124487802740948e-10, -0.0005239048834437878]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092238558825656, 0.23576141053205174, 0.8415233686300534, 0.0, -0.12328325243654976, -0.2439557920151657, -2.6080837724010726, -0.7119071414159466, -0.5581519227870049, -1.199345945387338, -2.8770605110628282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4223523698543891, 0.9651193702015691, 0.7810737984948897, -1.2123104169868437, -2.2910962516623736, -0.29134533396449097, 1.8895301632215622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960787200638, -0.4403409246022554, 0.023247404124884127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4983649688536877e-06, 0.0004811014358528989, 6.761326606055589e-06, 0.0, 0.0006116138882675735, 0.00030964895264502747, 7.755032689620944e-05, 0.0007743475628682688, -3.4288456795332206e-05, -0.00039411718771227295, -0.0002625852878715163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015675552384362555, 0.013504648535452373, -0.04437295887586491, -0.0032668295821129466, -0.02590828221646176, 0.017446662382620555, 0.054141866925591864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.336152004959027e-09, -2.9483383204032195e-10, -0.0005232409892289644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922398394839423, 0.23578544723407127, 0.8415237008592102, 0.0, -0.12325272323726047, -0.2439403182548261, -2.608079901591061, -0.7118684876951991, -0.5581536360211438, -1.1993656140432984, -2.8770736183330112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42157170330215116, 0.9657887980086253, 0.7788682009049951, -1.2124728538313292, -2.292395659042311, -0.2904799007452496, 1.8922307511121659, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960783064311, -0.44034092461119667, 0.023221286690121322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5613165727152883e-06, 0.00048073404039043435, 6.644583136598058e-06, 0.0, 0.0006105839857859857, 0.0003094752067921484, 7.741620023622234e-05, 0.0007730744149506638, -3.426468277858962e-05, -0.00039337311920644867, -0.00026214540366160043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01561333104475981, 0.013388556141123548, -0.04411195179789197, -0.003248736889710461, -0.025988147598741438, 0.01730866438482799, 0.054011757812075435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.272654326006525e-09, -1.788258857433844e-10, -0.0005223486952560803]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092241153103414, 0.23580943343363525, 0.8415240404833962, 0.0, -0.1232222746465587, -0.24392488207649005, -2.608076038413205, -0.7118299333489168, -0.5581553493164322, -1.1993852276726218, -2.8770866904437438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42079265955417344, 0.9664535785191612, 0.7766716961082093, -1.212634621195772, -2.293701407394966, -0.2896193457177761, 1.8949296662867212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960778965756, -0.440340924614439, 0.02319523811198458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.627238943820995e-06, 0.000479723991279697, 6.792483720689729e-06, 0.0, 0.0006089718140354803, 0.0003087235667211426, 7.726355711621118e-05, 0.000771086925645637, -3.426590576893101e-05, -0.00039227258646606824, -0.0002614422146470036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015580874959554462, 0.013295610210719745, -0.04393009593571532, -0.003235347288853942, -0.02611496705310561, 0.017211100549470552, 0.05397830349110793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.197111136692185e-09, -6.484728093278991e-11, -0.0005209715627347895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092242500054431, 0.23583333917995253, 0.8415243937262556, 0.0, -0.12319193475318685, -0.24390950385004634, -2.6080721843085497, -0.7117915131284361, -0.5581570633418861, -1.1994047687729104, -2.8770997147905937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4200139636292416, 0.9671147104640737, 0.7744808856812928, -1.2127959181453245, -2.295015497776658, -0.28876212112143645, 1.8976310505495397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960774910598, -0.4403409246120918, 0.02316928194668761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6939020335182154e-06, 0.00047811492634575376, 7.064857187734985e-06, 0.0, 0.0006067978674369437, 0.00030756452887392905, 7.70820931088602e-05, 0.0007684044096126242, -3.428050907739793e-05, -0.0003908220057691243, -0.0002604869369985441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015573918498637348, 0.013222638898248726, -0.043816208538330355, -0.00322593899105221, -0.026281807633830957, 0.017144491926792838, 0.05402768525636815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.110315293499276e-09, 4.6944804177953823e-11, -0.0005191233059394407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922438798573534, 0.2358571444272394, 0.8415247611308359, 0.0, -0.12316172246009313, -0.24389419335789833, -2.608068340507095, -0.7117532505645536, -0.558158778287458, -1.199424225430224, -2.8771126829367297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41923473532055916, 0.9677728866796532, 0.7722934161990574, -1.212956881883158, -2.2963393354168686, -0.2879073096273501, 1.9003377944197228, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960770902595, -0.4403409246042542, 0.023143434124516634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7596058447164707e-06, 0.000476104945737298, 7.348091605041611e-06, 0.0, 0.0006042458618744598, 0.00030620984296020646, 7.687602909510037e-05, 0.0007652512776494267, -3.429891143800084e-05, -0.0003891331462746232, -0.00025936292271699256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0155845661736487, 0.013163524311589642, -0.04374938964470688, -0.0032192747566692206, -0.02647675280421163, 0.017096229881726443, 0.054134877403664294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.01600633038393e-09, 1.5675137198967494e-10, -0.0005169564434195082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922452916000858, 0.2358808403621116, 0.8415251397821107, 0.0, -0.12313164583970654, -0.24387895172115687, -2.6080645077163536, -0.711715155813482, -0.5581604940444943, -1.1994435924773454, -2.87712559131105, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41845450336903484, 0.9684284818251855, 0.7701080173027351, -1.2131175865810657, -2.2976737120383386, -0.2870545511453888, 1.9030514941192362, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196076694342, -0.4403409245910031, 0.02311770150108781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8234854651376114e-06, 0.0004739186974440934, 7.573025496729262e-06, 0.0, 0.0006015324077317446, 0.00030483273482931615, 7.66558148236624e-05, 0.0007618950214334908, -3.4315140727767546e-05, -0.0003873409424277983, -0.0002581674864028675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015604639030486773, 0.01311190291064501, -0.043707977926445755, -0.0032140939581541406, -0.026687532429398322, 0.01705516963922575, 0.054273993990267506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.918348766056197e-09, 2.650229335057428e-10, -0.000514652468576475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922467343183218, 0.2359044269142091, 0.8415255254644389, 0.0, -0.12310170444313419, -0.24386377493927877, -2.608060686115852, -0.7116772284471309, -0.5581622103830651, -1.1994628701224501, -2.8771384401500866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4176731159377752, 0.9690816227511331, 0.7679242635833511, -1.2132780573832522, -2.299018936029712, -0.28620385908414797, 1.9057727319204802, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960763033183, -0.440340924572389, 0.023092083757146897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8854364718654023e-06, 0.0004717310419500043, 7.713646564592234e-06, 0.0, 0.0005988279314469956, 0.00030353563756180154, 7.643201002834777e-05, 0.0007585473270231177, -3.4326771416632615e-05, -0.00038555290209570716, -0.00025697678073433646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015627748625193033, 0.013062818518951868, -0.043675074387681916, -0.003209416043731131, -0.02690447982746789, 0.017013841224816428, 0.05442475602487812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.820471259658485e-09, 3.7228274721579084e-10, -0.0005123548788182946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922482072344842, 0.2359279089154134, 0.841525914222004, 0.0, -0.1230718930598605, -0.24384865728966337, -2.608056875514007, -0.7116394620836728, -0.55816392708018, -1.1994820616189485, -2.8771512318041363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4168906142633456, 0.9697322875982185, 0.7657422392854535, -1.2134382896662679, -2.3003750177240807, -0.28535542471059344, 1.90850147292552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960759171188, -0.4403409245484401, 0.023066576541881698]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9458323249921477e-06, 0.00046964002408588835, 7.775151300331361e-06, 0.0, 0.000596227665474031, 0.00030235299230778275, 7.621203690126238e-05, 0.0007553272691621398, -3.433394229827986e-05, -0.0003838299299675208, -0.0002558330809954987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015650033488590995, 0.01301329694170914, -0.043640485957952946, -0.003204645660315158, -0.027121633887366898, 0.016968687471091107, 0.05457482010079753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.723991917998616e-09, 4.789779770359519e-10, -0.0005101443053039941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922487188422875, 0.2359512926173417, 0.8414798981621372, 0.0, -0.12304217007769358, -0.2438328025892432, -2.608053233455713, -0.7116018612972712, -0.5581654649798811, -1.1995011740929382, -2.87716403092832, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41622679897001835, 0.9702865401809379, 0.763883358433907, -1.2135778829397672, -2.3015461478541615, -0.284671909354924, 1.9108411860728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075585609, -0.44034092452713464, 0.023041174375794907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0232156067228836e-06, 0.0004676740385663791, -0.0009203211973347449, 0.0, 0.0005944596433383856, 0.0003170940084034714, 7.284116588084856e-05, 0.0007520157280314512, -3.0757994020575036e-05, -0.0003822494797954897, -0.000255982483672668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013276305866545001, 0.011085051654385976, -0.03717761703092988, -0.002791865469985349, -0.023422602601618707, 0.013670307113389343, 0.04679426294614361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.630193781554256e-09, 4.2610865232925507e-10, -0.0005080433217358516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092248984882419, 0.235974268389336, 0.8414506529541362, 0.0, -0.1230129407403171, -0.24381756337189522, -2.6080496259565082, -0.7115648801886544, -0.5581669870332563, -1.199520018068767, -2.87717661581652, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4157054495725053, 0.970726134875539, 0.7624113404522476, -1.2136924119698704, -2.302488665425653, -0.28416729112142136, 1.9127088918606323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960753270093, -0.44034092451105267, 0.02301618802811448]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.320802629738785e-07, 0.00045951543988579204, -0.0005849041600194818, 0.0, 0.0005845867475296946, 0.00030478434695945265, 7.214998409164552e-05, 0.0007396221723374655, -3.044106750547131e-05, -0.00037687951657553657, -0.00025169776400109383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010426987950260405, 0.00879189389202301, -0.02944035963318739, -0.00229058060206577, -0.018850351429836387, 0.010092364670052284, 0.03735411575610158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.171997670780403e-09, 3.216397380081335e-10, -0.0004997269536085335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922491494170983, 0.23599624983988501, 0.8414483496448353, 0.0, -0.122984921306867, -0.24380364302824198, -2.608046030740962, -0.7115293881312232, -0.5581685710940243, -1.1995381647932162, -2.8771886485782794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4153133445449481, 0.9710617032434499, 0.7612911261863405, -1.2137835548633018, -2.303218483848184, -0.2838093796255577, 1.9141429507514227, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751444154, -0.4403409245013862, 0.022992208098654425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2906935816892777e-07, 0.00043962901098051926, -4.606618601843708e-05, 0.0, 0.0005603886690020853, 0.0002784068730651544, 7.19043109229564e-05, 0.0007098411486224862, -3.1681215360431484e-05, -0.0003629344889806832, -0.00024065523518950488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007842100551144033, 0.006711367358216193, -0.022404285318141592, -0.0018228578686265181, -0.014596368450615259, 0.007158229917273065, 0.02868117781580587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.651877703104973e-09, 1.933301689856042e-10, -0.00047959858920105706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492437373727, 0.23601658623147476, 0.8414590466242347, 0.0, -0.12295889779171289, -0.2437913255747105, -2.608042497371656, -0.7114963632547027, -0.5581702289630247, -1.1995551136100802, -2.8771997770817075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41502627397516445, 0.9713122651738108, 0.760458530364623, -1.2138548491255416, -2.303770441791338, -0.2835593787138501, 1.9152187220931172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119607504069, -0.44034092450048995, 0.02296989711802654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8864054873582224e-07, 0.000406727831794947, 0.0002139395879865806, 0.0, 0.0005204703030823638, 0.00024634907062953237, 7.066738611790935e-05, 0.0006604975304108868, -3.315738000833834e-05, -0.0003389763372812621, -0.0002225700685628714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005741411395673626, 0.005011238607218407, -0.016651916434352116, -0.0014258852447985985, -0.011039158863079185, 0.005000018234151651, 0.02151542683389112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0745040033420788e-09, 1.7924738970382162e-11, -0.00044621961255772425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492933419876, 0.23603475577432742, 0.8414750227616592, 0.0, -0.1229355231945582, -0.2437809814534243, -2.6080390312703785, -0.7114666078848317, -0.5581720073977583, -1.1995704589743537, -2.877209698784248, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4148198000911033, 0.9714968972861152, 0.7598487496944001, -1.2139100078181488, -2.304181407589278, -0.2833847366983969, 1.9160138213012863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960750336107, -0.4403409245145704, 0.02294979900678752]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.920922989975184e-08, 0.00036339085705321047, 0.00031952274849119864, 0.0, 0.00046749194309373803, 0.0002068824257242287, 6.932202555167622e-05, 0.000595107397419589, -3.5568694672535596e-05, -0.00030690728546846455, -0.00019843405081240186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004129477681223238, 0.0036926422460890037, -0.012195613404458027, -0.0011031738521428088, -0.008219315958802705, 0.003492840309064276, 0.015901984163380244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4158986410701592e-10, -2.8160915053321025e-10, -0.0004019622247804496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493099129635, 0.23605046525805473, 0.8414448279092318, 0.0, -0.12291510482198442, -0.2437709778967978, -2.608035990795053, -0.7114406115277784, -0.5581735692497372, -1.1995838798835885, -2.877218364229198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4146730376185007, 0.9716318981989475, 0.7594062208513683, -1.2139523496896159, -2.304484103164397, -0.28326203612539763, 1.916595816208237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751141298, -0.44034092454431645, 0.022932238233061203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.314195200306826e-08, 0.00031418967454627315, -0.0006038970485487139, 0.0, 0.0004083674514753187, 0.0002000711325302667, 6.0809506508185485e-05, 0.0005199271410681618, -3.123703957631058e-05, -0.000268418184694739, -0.0001733088989992726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002935249452052032, 0.0027000182566449277, -0.008850576860634755, -0.0008468374293380021, -0.006053911502375485, 0.0024540114599855816, 0.011639898139017498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6103848084768415e-09, -5.949203318875397e-10, -0.0003512154745262834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493104040848, 0.23606365717311636, 0.8413724547795586, 0.0, -0.12289772275178933, -0.2437611459551833, -2.6080335107422443, -0.711418514534015, -0.5581747862028298, -1.199595274141099, -2.8772257708797935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41456955499475034, 0.9717301605493174, 0.7590869279578832, -1.213984645147714, -2.3047052786869795, -0.2831748818362176, 1.9170190087748016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075219521, -0.4403409245856499, 0.022917307953974907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0" + }, + "execution_count": 33, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999943677873273, 0.036489651127809095, -0.34861191507695366, 0.0, -1.0029954720697876, 0.48869320376572917, -0.9525215184807941, -1.3886278121725906, -2.334452544500386, -0.4558788900739724, 0.11051798980155325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424639103, 0.01537723122151193, 1.7420423753144298, -2.031187242709937, -1.4888851823925482, -0.10085496898309822, 0.2189845498620707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529550045, -0.0006253905029041468, -0.0006249999999543101]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011264425345431811, -0.10782259036973244, 0.24007968118780842, 0.0, 0.03470669267139551, 0.02650595782943679, -0.0749999999999986, 0.07499999999999744, -0.06632406743743047, -0.02018751168584966, -0.07499999999999926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999737, 0.074999999999998, 0.07499999999999606, -0.012777139263307391, -0.04774843784840461, -2.521049782918791e-13, -0.04371418946734415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059100089, -0.012507810058082935, -0.012499999999997631]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998925805181444, 0.0267630596697571, -0.3278931585753566, 0.0, -1.0000224659428705, 0.49049653362158574, -0.9619301047404497, -1.379593523733744, -2.3410342122554755, -0.4572018850649818, 0.10116315485063393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8674174204432588, 0.025183583202972704, 1.751384115653074, -2.0317932410205013, -1.493464451596551, -0.10085496898310194, 0.21493079853658995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024960475280989564, -0.0025039454747618935, -0.0018977869579240155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00010219471025693422, -0.1945318291610399, 0.4143751300319408, 0.0, 0.05946012253834131, 0.03606659711713095, -0.1881717251931117, 0.18068576877693243, -0.13163335510178822, -0.026459899820186556, -0.18709669901838655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.17671844041302845, 0.19612703962921552, 0.18683480677288364, -0.012119966211281892, -0.09158538408005376, -7.442134995683418e-14, -0.0810750265096152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742876550287904, -0.037571099437154934, -0.025455739159394107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998493688783553, 0.014583839048681577, -0.30283958239639125, 0.0, -0.9965298716413223, 0.4921355227464133, -0.9760200982822472, -1.36680060810211, -2.349875174327609, -0.45803239691922115, 0.08685564365031923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8549868214394558, 0.03999234575967991, 1.7648047375765166, -2.0314752473307713, -1.4992752177285162, -0.10085496898347529, 0.20999822574163152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005922552841754735, -0.005952405107086799, -0.003193360879578438]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.642327957848494e-05, -0.2435844124215104, 0.5010715235793077, 0.0, 0.06985188603096355, 0.03277978249655097, -0.2817998708359508, 0.25585831263267966, -0.17681924144267328, -0.016610237084787073, -0.2861502240062941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24861198007606106, 0.2961752511341441, 0.26841243846885016, 0.006359873794598259, -0.11621532263930487, -7.467089435582319e-12, -0.09865145589916838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853010627311555, -0.06896919264649809, -0.025911478433088442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999809068351237, 0.0014335378704646243, -0.2761944917194697, 0.0, -0.9929074957979815, 0.49347927487126664, -0.9934337460668297, -1.3521735729677822, -2.3599662038298526, -0.457824273575296, 0.06884865106772532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8406534822932354, 0.058139594719090186, 1.7805125395519898, -2.029647170337682, -1.505313962569741, -0.10102857327294908, 0.20517189543805536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010643678979208298, -0.010710374037979753, -0.0038867220396985465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.06010542364428e-05, -0.26300602356433905, 0.5329018135384308, 0.0, 0.07244751686681615, 0.02687504249706601, -0.34827295569164807, 0.29254070268655696, -0.2018205900448637, 0.004162466878503277, -0.3601398516518781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2866667829244086, 0.3629449791882055, 0.31415603950946397, 0.0365615398617862, -0.12077489682449417, -0.0034720857894756426, -0.09652660607152291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09442252274907126, -0.09515937861785909, -0.013867223202402175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997690652879782, -0.011702002331867939, -0.24928874587665734, 0.0, -0.989246276057703, 0.49468681123771097, -1.0130856680342577, -1.3371594841759553, -2.370582763613108, -0.45628347991271506, 0.04830253205125776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8255901082630048, 0.07823517963514391, 1.7972253898468225, -2.026066250201851, -1.510779505665099, -0.10158468126685208, 0.20121590048948146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01641292307501113, -0.01652437680067441, -0.0038640671749981628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.000612651748077e-05, -0.26271080404665126, 0.5381149168562469, 0.0, 0.0732243948055711, 0.024150727328886127, -0.39303843934856075, 0.3002817758365387, -0.21233119566511, 0.030815873251618307, -0.41092238032935124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30126748060461117, 0.40191169832107443, 0.3342570058966499, 0.07161840271662138, -0.10931086190716179, -0.01112215987806014, -0.07911989897147827, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11538488191605661, -0.1162800552538931, 0.00045309729400767884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997283474068714, -0.02422006317593057, -0.22265032601038354, 0.0, -0.9854888087372059, 0.4959988791581555, -1.0342328168154162, -1.3226446897264197, -2.381293431749223, -0.45328812762035114, 0.026100264362257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8104723735088248, 0.09932762778084879, 1.8141873846479377, -2.020712517349157, -1.5151246688409317, -0.10266626822918933, 0.1986374242225254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023024727213398023, -0.023179169679737342, -0.003240362997743023]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.143576221380755e-05, -0.2503612168812526, 0.532768397325476, 0.0, 0.07514934640994225, 0.026241358408890046, -0.42294297562316907, 0.2902958889907117, -0.21421336272229458, 0.05990704584727803, -0.4440453537800151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3023546950835998, 0.42184896291409757, 0.3392398960223039, 0.10707465705388071, -0.08690326351665349, -0.021631739246744976, -0.05156952533912154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13223608276773788, -0.13309585758125864, 0.0124740835451028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996865980793582, -0.03577252767613231, -0.19642956701394904, 0.0, -0.9815406337022685, 0.4976208882400833, -1.056396033113364, -1.3090816174212576, -2.3918853969091396, -0.4488199833015818, 0.0028533308283817463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7956428661300832, 0.12084202839815208, 1.831009251468635, -2.013679421858163, -1.5180326510469635, -0.10435473103804188, 0.19771778927297087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030315445650636933, -0.03050174984173772, -0.002180320475781348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.349865502641323e-05, -0.2310492900040347, 0.5244151799286898, 0.0, 0.07896350069874844, 0.032440181638556685, -0.44326432595895465, 0.271261446103241, -0.21183930319833585, 0.08936288637538736, -0.4649386706775051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.29659014757483493, 0.43028801234606573, 0.3364373364139436, 0.14066190981987875, -0.058159644120635956, -0.03376925617705119, -0.018392698991090466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1458143687447782, -0.14645160324000756, 0.02120085043923349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996442330373115, -0.04616995896947086, -0.17062210968011732, 0.0, -0.9773194217804638, 0.49955824438821456, -1.07920000541233, -1.2966864109287906, -2.402273896109887, -0.44290888219037877, -0.021025607826192387, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7812463341514053, 0.1424741886154075, 1.8475146134884695, -2.0051054194168927, -1.519369528373308, -0.10669360940779955, 0.1985627728675731, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03815425881537758, -0.03835359792954218, -0.0008307438256598999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.473008409361587e-05, -0.20794862586677107, 0.5161491466766346, 0.0, 0.08442423843609374, 0.03874712296262459, -0.45607944597932065, 0.24790412984934107, -0.20776998401494684, 0.11822202222406095, -0.47757877309148267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2879306395735574, 0.4326432043451085, 0.3301072403966928, 0.17148004882540202, -0.02673754652688798, -0.04677756739515352, 0.016899671892044166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1567762632948129, -0.15703696175608922, 0.026991533002428958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996040725524014, -0.055314282637708795, -0.14516865212623695, 0.0, -0.9727456966265481, 0.5009982242991801, -1.1019427606501693, -1.2858660976682268, -2.412379732756123, -0.4355618582535085, -0.04519470760038505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.767324519208989, 0.1640966399781355, 1.8636348863947714, -1.9951358832689376, -1.5191345486479253, -0.10970712890896582, 0.20115281807469315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04643623664364146, -0.046624149490955655, 0.0006903032687336236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.0320969820218e-05, -0.1828864733647586, 0.5090691510776074, 0.0, 0.0914745030783143, 0.028799598219310777, -0.4548551047567852, 0.216406265211273, -0.202116732924724, 0.14694047873740462, -0.48338199548385324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2784362988483254, 0.43244902725455975, 0.3224054581260395, 0.19939072295909918, 0.004699594507654364, -0.060270390023325224, 0.05180090414240096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656395565652775, -0.1654110312282694, 0.03042094188787047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995656080170937, -0.06315356264304221, -0.1199941524971841, 0.0, -0.9677747180971222, 0.5012873611605031, -1.1241369183257128, -1.2768487140584996, -2.422146155899913, -0.42689116470085037, -0.06940616153652623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753877220547299, 0.18568829153512362, 1.8793483881907975, -1.983904792192392, -1.517416586876193, -0.11341034879709012, 0.20538601171981455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.055076911032641694, -0.05522545682713539, 0.002283205327204916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.692907061534153e-05, -0.15678560010666837, 0.5034899925810568, 0.0, 0.09941957058851723, 0.005782737226461488, -0.44388315351087204, 0.18034767219454395, -0.19532846287580571, 0.1734138710531634, -0.4842290787228237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26894597323380076, 0.43183303113976196, 0.3142700359205242, 0.22462182153091065, 0.03435923543464532, -0.07406439776248616, 0.08466387290242797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17281348778000474, -0.17202614672359462, 0.03185804116942584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995281641503582, -0.06966866451748287, -0.09502117513016206, 0.0, -0.9624003387814247, 0.500116271030617, -1.1455779972015496, -1.269654870766623, -2.431548357049536, -0.4170777138025503, -0.09350309815341745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7408879145352454, 0.2072870992331846, 1.8946485238828072, -1.9715281295513343, -1.5143590200051038, -0.11781302443341707, 0.21111215767328254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06400807277254862, -0.0640877832741035, 0.003868547243061622]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.488773347092766e-05, -0.13030203748881303, 0.4994595473404408, 0.0, 0.10748758631395008, -0.023421802597722835, -0.42882157751673766, 0.14387686583753134, -0.1880440229924549, 0.1962690179660015, -0.4819387323378244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2597861202410735, 0.43197615396121986, 0.3060027138401966, 0.24753325282115302, 0.06115133742178465, -0.08805351272653884, 0.11452291906935952, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17862323479813863, -0.17724652893936235, 0.03170683831713413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994913107957552, -0.07486978452803561, -0.07017347678394761, 0.0, -0.9566474214950237, 0.4974535442189808, -1.1662723818940892, -1.2641571779351852, -2.4405939888037196, -0.406312552106569, -0.11740332790066152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7283317732074577, 0.22895947583181858, 1.9095291082817134, -1.9581026453043, -1.5101332014272366, -0.12292019476310419, 0.21815816901528123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07317453423226578, -0.07315595397288652, 0.005390281978841689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.370670920623152e-05, -0.1040224002110549, 0.4969539669242888, 0.0, 0.11505834572802173, -0.0532545362327229, -0.4138876938507903, 0.10995385662875751, -0.1809126350836694, 0.2153032339196265, -0.4780045949448813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25112282655575346, 0.43344753197267905, 0.29761168797812365, 0.2685096849406872, 0.08451637155734373, -0.10214340659374235, 0.1409202268399741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18332922919434316, -0.18136341397566022, 0.030434694715601344]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999454778588323, -0.0787932511944504, -0.04537638636620607, 0.0, -0.9505610930258132, 0.4934320662590068, -1.186347623731432, -1.2601449452411397, -2.4493170870303422, -0.394757933766431, -0.1410787049015602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7161772892543037, 0.2507809650795023, 1.9239788941423313, -1.9437069608164215, -1.504919569294214, -0.1287315809038877, 0.22634589764778879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08253162230411247, -0.0823863518059898, 0.006815783357143117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.306441486449107e-05, -0.07846933332829581, 0.49594180835483076, 0.0, 0.12172656938421006, -0.08042955919948017, -0.401504836746858, 0.08024465388091005, -0.1744619645324521, 0.23109236680276088, -0.4735075400179733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24308967906307802, 0.4364297849536748, 0.28899571721235584, 0.2879136897575728, 0.10427264266044811, -0.11622772281567015, 0.1637545726501511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18714176143693387, -0.1846079566620657, 0.028510027566028558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999418401004553, -0.08149615548172884, -0.020556340685526725, 0.0, -0.9441966043754932, 0.4882542696256191, -1.205982998975845, -1.2573734263664906, -2.457768988172567, -0.3825317687870865, -0.16453548044579352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7043869252787127, 0.27282430441754935, 1.9379806416962566, -1.9284037276933006, -1.4988950104392036, -0.13524091820649173, 0.2355038109280024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09204320725190959, -0.09174447697766148, 0.008132419216196427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.275516754014441e-05, -0.054058085745568765, 0.49640091361358685, 0.0, 0.12728977300639832, -0.10355593266775534, -0.39270750488825773, 0.05543037749298321, -0.16903802284449532, 0.24452329958688943, -0.4691355108846665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23580727951181774, 0.44086678676094054, 0.28003495107850934, 0.30606466246241537, 0.12049117710021234, -0.13018674605208075, 0.18315826560427226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19023169895594233, -0.1871625034334337, 0.026332717181066216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993820843096527, -0.08304951929192882, 0.004359732278485691, 0.0, -0.9376112471486444, 0.48212994460053066, -1.2253658774053524, -1.2555963712456997, -2.466009239976215, -0.36970820743538035, -0.18779826770983304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6929184906149766, 0.2951523694979101, 1.9515121768008965, -1.9122422732104816, -1.4922250618411221, -0.14243568346670238, 0.24547391998940069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10168012295086909, -0.10120299526375542, 0.009342140285319461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.263338980055095e-05, -0.031067276203999572, 0.4983214592802483, 0.0, 0.13170714453697593, -0.12248650050176803, -0.3876575685901491, 0.035541102415818024, -0.16480503607295707, 0.256471227034123, -0.4652557452807905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22936869327472115, 0.4465613016072156, 0.27063070209279794, 0.32322908965637986, 0.13339897196162795, -0.1438953052042129, 0.19940218122796569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19273831397919, -0.18917036572187879, 0.024194421382460668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999345787218696, -0.08353142067439112, 0.029445008079205522, 0.0, -0.9308586256850422, 0.47524219487126584, -1.244668886932497, -1.2545853835584841, -2.4740982777286065, -0.35632634252206563, -0.21089833098617597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6817271814852262, 0.31781441248440706, 1.9645481115374919, -1.8952614045937972, -1.4850596725245517, -0.15029731022491274, 0.2561152164303628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1114188792209438, -0.11074019912926589, 0.010455772812928171]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.259418191355444e-05, -0.009638027649246223, 0.5017055160143966, 0.0, 0.1350524292720445, -0.13775499458529636, -0.38606019054289176, 0.0202197537443123, -0.16178075504782638, 0.2676372982662945, -0.4620012655268586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22382618259500872, 0.4532408597299385, 0.26071869473190895, 0.33961737233368844, 0.14330778633140898, -0.1572325351642074, 0.2128259288192421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1947751254014942, -0.1907440773102094, 0.02227265055217421]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999310607111454, -0.08302938996233994, 0.05477321513919481, 0.0, -0.923991414112252, 0.46773330417573744, -1.2640402128919723, -1.2541392907820497, -2.482092733130743, -0.34240177658041, -0.23386587648540366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.670773099558801, 0.3407370161374479, 1.9768575873766403, -1.877623985725392, -1.4775504600158724, -0.1588547607254304, 0.2672813611253824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12124067996820441, -0.12033872601129876, 0.011496409058730188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.036021448414886e-05, 0.010040614241023614, 0.5065641411997858, 0.0, 0.13734423145580163, -0.1501778139105684, -0.38742651918950577, 0.00892185552869019, -0.15988910804273, 0.2784913188331126, -0.459350909984554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21908163852850127, 0.4584520730608169, 0.24618951678296816, 0.3527483773681055, 0.1501842501735842, -0.17114901001035326, 0.2233228939003923, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19643601494521215, -0.19197053764065736, 0.020812724916040352]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992804213393903, -0.08165764022566474, 0.08041948891832457, 0.0, -0.9170770735508773, 0.45970313497894394, -1.283601065526524, -1.254086813416885, -2.490043326135137, -0.3279381466345287, -0.2567255882798957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6600365308914813, 0.3634496468522489, 1.9875244374976193, -1.859987029478487, -1.4699013151136944, -0.1682919919079088, 0.2787573864212014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13113083499134293, -0.12998432922857048, 0.012517509370653924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0371544126995355e-05, 0.027434994733504064, 0.512925475582595, 0.0, 0.13828681122749548, -0.16060338393586998, -0.3912170526910351, 0.0010495473032916588, -0.15901186008788104, 0.28927259891762647, -0.4571942358898413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21473137334639292, 0.45425261429602043, 0.21333700241957979, 0.35273912493810033, 0.15298289804356144, -0.1887446236495683, 0.2295205059163795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1978031004627706, -0.19291206434543448, 0.020422006238474722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992545743305098, -0.0795159245272511, 0.10646074018709453, 0.0, -0.9101708458552307, 0.45121181250340664, -1.3034525260914236, -1.254290785018126, -2.4979930325894326, -0.31293292071170853, -0.2794942992600252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6494984100499197, 0.38552614818554565, 1.995875388686491, -1.842962512642937, -1.4623139445105957, -0.1786552829958554, 0.2903352443415077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14107795986408048, -0.13966523005111176, 0.013562634334371814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.169401776087522e-05, 0.04283431396827265, 0.5208250253753994, 0.0, 0.13812455391293332, -0.16982644951074582, -0.39702921129799257, -0.004079432024817522, -0.15899412908591287, 0.30010451845640373, -0.45537421960259006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2107624168312294, 0.44153002666593455, 0.16701902377743577, 0.340490336711002, 0.15174741206197195, -0.20726582175893182, 0.23155715840612628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19894249745475076, -0.19361801645082535, 0.02090249927435781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992322813680996, -0.07670867382958221, 0.1329763188290542, 0.0, -0.9032348264408785, 0.44214690901905485, -1.323493252842749, -1.254855348925615, -2.5059698634130587, -0.2980366560047832, -0.3021668847623032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.639108140516877, 0.40669613074814553, 2.001651537455167, -1.8269615651281002, -1.4549582247240107, -0.18982475365300422, 0.30184944505258826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15107350323247298, -0.14937142693135094, 0.014685286317639549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4585924820379004e-05, 0.05614501395337779, 0.5303115728391934, 0.0, 0.13872038828704258, -0.18129806968703563, -0.40081453502650954, -0.0112912781497776, -0.15953661647252596, 0.2979252941385066, -0.45345171004555895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20780539066085135, 0.42339965125199724, 0.11552297537352055, 0.32001895029673716, 0.1471143957317011, -0.22338941314297658, 0.23028401422161135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991086736785002, -0.19412393760478375, 0.02245303966535469]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992130626790985, -0.07340491572848924, 0.15994061314862004, 0.0, -0.8962724789649682, 0.4324964947242017, -1.3438263294093244, -1.2556221171898703, -2.514013184406461, -0.2835484250369043, -0.3247341376957751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6288354085764698, 0.42682450613392386, 2.0049347917272113, -1.8121833806064307, -1.4479642065666531, -0.20157012497956966, 0.31318554591657793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16111059208723302, -0.15909494212136988, 0.01586729616881353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8437378001899175e-05, 0.06607516202185941, 0.5392858863913167, 0.0, 0.13924694951820532, -0.19300828589706293, -0.4066615313315085, -0.015335365285106062, -0.1608664198680467, 0.28976461935757797, -0.4513450586694377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20545463880814627, 0.40256750771556626, 0.06566508544089172, 0.2955636904333909, 0.1398803631471516, -0.23490742653130897, 0.22672201727979394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007417770952007, -0.19447030380037839, 0.023640197023479626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991966840970793, -0.06977970537894607, 0.18726994136662176, 0.0, -0.8892701283554084, 0.42224521192470754, -1.3645891160146304, -1.256394921929232, -2.5221558967836404, -0.2696095747926342, -0.3471787210740257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6186465895692452, 0.4458749683982276, 2.0060105202825427, -1.7986622006434627, -1.4414223202292344, -0.21361339867696572, 0.32427683434982835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1711835067910226, -0.1688296131239169, 0.017074813798622437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.275716403852687e-05, 0.07250420699086339, 0.5465865643600344, 0.0, 0.14004701219119592, -0.20502565598988312, -0.4152557321061212, -0.015456094787236955, -0.16285424754359026, 0.27877700488540236, -0.44889166756501203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20377638014449317, 0.3810092452860746, 0.021514571106627384, 0.2704235992593596, 0.13083772674837285, -0.240865473947921, 0.22182576866500847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2014582940757915, -0.19469342005094056, 0.024150352596178155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991829704491304, -0.06595164889716351, 0.21486738391251042, 0.0, -0.8821869876742153, 0.4113580694793555, -1.3858915903241376, -1.2570265264617904, -2.5304170095375724, -0.25627574742973624, -0.36947639220324785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6085015888525278, 0.46387136236181853, 2.005249868742743, -1.7863216674809272, -1.4353896885281745, -0.22567821158055126, 0.3350945463214575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18128738829199612, -0.17857079626743272, 0.01827446757476247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.742729589774109e-05, 0.07656112963565102, 0.5519488509177736, 0.0, 0.14166281362386218, -0.21774284890704082, -0.4260494861901423, -0.012632090651166567, -0.165222255078642, 0.26667654725795925, -0.44595342258444315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.202900014334348, 0.3599278792718181, -0.015213030795990373, 0.24681066325070852, 0.12065263402119997, -0.24129625807171087, 0.21635423943258303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20207763001947027, -0.19482366287031647, 0.02399307552280062]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999171936687081, -0.06200489325961712, 0.24262760650810797, 0.0, -0.8749077381951124, 0.3997031550632148, -1.4076775335683605, -1.25758594128843, -2.5387972096710043, -0.24417857712991742, -0.391590489618162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.598342974240442, 0.48087099638066244, 2.003027721377976, -1.7750238484235246, -1.4298975236623708, -0.2375200347171883, 0.34563704259039363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19141825256944675, -0.1883148717070868, 0.019458676694438536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2067524098460056e-05, 0.07893511275092788, 0.555204451911951, 0.0, 0.1455849895820586, -0.23309828832281398, -0.43571886488445577, -0.011188296532793842, -0.16760400266863723, 0.24194340599637676, -0.4422819482982835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20317229224171607, 0.33999268037687863, -0.044442947295344856, 0.22595638114805344, 0.10984329731607509, -0.23683646273274064, 0.2108499253787216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20261728554901254, -0.19488150879308166, 0.023684182393521297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991632893154915, -0.057955381131714064, 0.27043383512585756, 0.0, -0.867367996397315, 0.3872512299726996, -1.429980287645491, -1.2580481042981049, -2.5472886953391627, -0.23334210046732623, -0.4134925815781258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.588134021490493, 0.49694044611680416, 1.9996814247534958, -1.7646048459974841, -1.4249597077185387, -0.24894317319441417, 0.3559190350014655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20157257289412323, -0.1980592924005522, 0.020596362724224826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7294743179113573e-05, 0.0809902425580611, 0.5561245723549918, 0.0, 0.1507948359559485, -0.24903850181030343, -0.4460550815426122, -0.009243260193495056, -0.16982971336316888, 0.21672953325182365, -0.43804183919927536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2041790549989801, 0.321388994722834, -0.06692593248960249, 0.20838004852081085, 0.09875631887663844, -0.2284627695445175, 0.2056398482214377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20308640649352938, -0.1948884138693078, 0.022753720595725828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991570323469426, -0.053798476309639034, 0.29815606018178514, 0.0, -0.8595176351390179, 0.37399993210151256, -1.4528474884205413, -1.2583752085214903, -2.5558745158296525, -0.22360631004274767, -0.43515990202702315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5778455511123288, 0.5121486757206983, 1.9954893594833063, -1.7549029483419794, -1.4205778231805546, -0.2598038304006368, 0.36596427551383576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21174720324770274, -0.20780235697116883, 0.0216640683540259]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2513937097453594e-05, 0.08313809644150058, 0.5544445011185514, 0.0, 0.1570072251659406, -0.2650259574237416, -0.4573440155010057, -0.006542084467708544, -0.17171640980979766, 0.19471580849157094, -0.4333464089779465, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2057694075632873, 0.30416459207788243, -0.08384130540378956, 0.19403795311009459, 0.08763769075968289, -0.2172131441244532, 0.2009048102474056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2034926070715904, -0.1948612914123327, 0.021354112596021484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991532140068302, -0.0495261124340122, 0.32565129367259676, 0.0, -0.8513100937361373, 0.3599504123409985, -1.4763174109024948, -1.2585407040120304, -2.564530809104911, -0.21478922970344114, -0.4565740300787786, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5674527919006813, 0.5265628008053821, 1.9906665842974844, -1.7457735158233119, -1.4167452974479746, -0.27000673079348886, 0.375800257381472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22193937709696854, -0.21754296453507113, 0.02265058158026335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.636680224744883e-06, 0.08544727751253674, 0.5499046698162328, 0.0, 0.16415082805761122, -0.28099039521028146, -0.4693984496390691, -0.0033099098108013477, -0.17312586550517142, 0.17634160678613053, -0.42828256103510925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20785518423294885, 0.288282501693675, -0.09645550371643657, 0.1825886503733485, 0.07665051465159964, -0.2040580078570406, 0.1967196373527248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20384347698531594, -0.19481215127804613, 0.019730264524749012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991519586375045, -0.04514634070765176, 0.3514006435865091, 0.0, -0.8426592115557481, 0.3450548782274425, -1.5003302905499343, -1.2586417207195475, -2.5732270149977454, -0.2073179997627597, -0.4777153494071629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569252279431307, 0.5402475213617974, 1.9853689104517105, -1.737095556272282, -1.41345007180058, -0.279497516553597, 0.3854550071751034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23214684001108826, -0.2272802767874083, 0.023568252139719102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.510738651493572e-06, 0.08759543452720886, 0.5149869982782466, 0.0, 0.1730176436077857, -0.2979106822711192, -0.4802575929487916, -0.002020334150341435, -0.17392411785668363, 0.1494245988136289, -0.42282638656768645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.210551279151014, 0.27369441112830695, -0.10595347691547766, 0.17355919102059403, 0.06590451294789099, -0.18981571520216345, 0.1930949958726276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2041492582823945, -0.19474624504674332, 0.018353411189115012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991531433682683, -0.040652203443944004, 0.3734640331474745, 0.0, -0.8335255223283966, 0.32932626206854554, -1.5248929540006286, -1.2586880015078965, -2.581930858881691, -0.20105999855085718, -0.498573411877532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5462492593169215, 0.5532608933159537, 1.9797051056484585, -1.7287711810021689, -1.4106774840942202, -0.28825605805658827, 0.3949547180241143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24236763948430182, -0.23701378075307267, 0.02441571502677804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.369461527810091e-06, 0.08988274527415509, 0.4412677912193081, 0.0, 0.18267378454702882, -0.3145723231779398, -0.4912532690138861, -0.0009256157669812709, -0.1740768776789138, 0.12516002423805006, -0.4171612494073814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2135193725241847, 0.26026743908312594, -0.11327609606504076, 0.16648750540226392, 0.055451754127197606, -0.17517083005982564, 0.18999421698021818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20441598946427111, -0.19467007931328703, 0.016949257741178766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991568038104338, -0.03604378387140768, 0.39102189623055855, 0.0, -0.8238822059508757, 0.3127923029678555, -1.5500276807358593, -1.2586642221456124, -2.5906074666517895, -0.19576593852907737, -0.5191436384328104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5354166890823266, 0.5656565402075744, 1.9737468833513334, -1.7207250504230756, -1.4084109998532808, -0.29628753156221943, 0.4043231753796419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25260010035560265, -0.24674318402336615, 0.02519559589684357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.320884331225334e-06, 0.09216839145072646, 0.35115726166168076, 0.0, 0.1928663275504183, -0.33067918201380153, -0.502694534704615, 0.0004755872456812329, -0.17353215540196934, 0.10588120043559658, -0.4114045311055688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21665140469189534, 0.2479129378324135, -0.11916444594250003, 0.16092261158186555, 0.045329684818788706, -0.1606294701126236, 0.1873691471105526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20464921742601713, -0.1945880654058694, 0.015597617401310607]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991629762965907, -0.0313301511200436, 0.4042356347770096, 0.0, -0.8137036635729823, 0.2954815505203647, -1.5757550714762791, -1.2585520824471372, -2.599220977602953, -0.19121333064802526, -0.539425331861611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5244213501439687, 0.5774842648355991, 1.9675384844805521, -1.7129005387961165, -1.4066329340866166, -0.30361497808066934, 0.41358166513866096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26284282183271745, -0.25646830713754026, 0.025915311458413366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2344972314041837e-05, 0.0942726550272815, 0.26427477092902024, 0.0, 0.2035708475578688, -0.3462150489498161, -0.5145478148083986, 0.0022427939695019595, -0.17227021902327067, 0.09105215762104218, -0.4056338685760125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21990677876715797, 0.2365544925604943, -0.12416797741562423, 0.15649023253918076, 0.03556131533328266, -0.14654893036899808, 0.18516979518038082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20485442954229588, -0.19450246228348259, 0.014394311231395939]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991716731154052, -0.026525558340783968, 0.41380240247527866, 0.0, -0.8029623156404427, 0.2774207428798835, -1.6020897913705852, -1.2583369909018103, -2.607736646785377, -0.1872381734880999, -0.5594203751179667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5132583434356306, 0.5887901948276059, 1.9611049586567002, -1.7052552910862158, -1.405324980846817, -0.3102732739851018, 0.42274918911505466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.273094660675004, -0.2661890497572536, 0.026584619763713735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.739363762884511e-05, 0.09609185558519262, 0.19133535396538198, 0.0, 0.21482695865079082, -0.36121615280962405, -0.5266943978861184, 0.0043018309065368885, -0.17031338364847823, 0.0795031431985073, -0.3999008651271129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2232601341667642, 0.22611859984013546, -0.12867051647703923, 0.15290495419801506, 0.026159064795992434, -0.13316591808864933, 0.1833504795278738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20503677684573077, -0.19441485239426728, 0.013386166106007354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991828863620853, -0.021645009132675964, 0.4205907108636889, 0.0, -0.791628159543138, 0.258635880996209, -1.6290408846014002, -1.2580090366093195, -2.6161224405769827, -0.18372994186970218, -0.5791323817827055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5019239113415281, 0.5996168454478135, 1.9544588074527132, -1.6977572570550705, -1.404468556059473, -0.31630444289788495, 0.4318428320375456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28335470022604436, -0.27590532282194086, 0.027213481376127325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.242649336002097e-05, 0.09761098416216009, 0.13576616776820377, 0.0, 0.22668312194609339, -0.3756972376734905, -0.5390218646163004, 0.006559085849813688, -0.16771587583211528, 0.07016463236795442, -0.39424013329477636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22668864188205057, 0.21653301240415293, -0.1329230240797412, 0.1499606806229051, 0.01712849574688053, -0.12062337825566287, 0.18187285844981813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2052007910208073, -0.19432546129374453, 0.01257723224827178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991965916541216, -0.016701056200382057, 0.4254225939679053, 0.0, -0.7796690759648334, 0.23915418238325292, -1.6566134421122871, -1.25756206611305, -2.624349893978199, -0.18061804771119994, -0.5985661845110753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904153737741563, 0.6100031613137556, 1.947604948074933, -1.6903814793287308, -1.404045026353251, -0.32175417684037083, 0.44087815263000113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29362221457316656, -0.285617048995376, 0.027810817361409907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7410584072310096e-05, 0.0988790586458781, 0.09663766208432883, 0.0, 0.23918167156609368, -0.3896339722591212, -0.5514511502177396, 0.008939409925390817, -0.16454906802433, 0.062237883170044736, -0.3886760545673955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23017075134743417, 0.20772631731884392, -0.1370771875556067, 0.1475155545267934, 0.008470594124443212, -0.10899467884971732, 0.18070641184911032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20535028694244367, -0.1942345234687028, 0.011946719705651644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992127501286358, -0.011702208613917686, 0.4289739422232274, 0.0, -0.7670512784878643, 0.21900591760066124, -1.684810411942989, -1.2569922982686135, -2.632394354661889, -0.17785914352096863, -0.617727581249097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787309925001368, 0.6199845755451108, 1.9405442054172986, -1.683107685070384, -1.4040358776467259, -0.3266693798282774, 0.44986952770788047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30389663225850994, -0.2953241545968568, 0.028383949432997407]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2316949028507026e-05, 0.09997695172928742, 0.0710269651064412, 0.0, 0.25235594953938256, -0.4029652956518339, -0.563939396614037, 0.011395356888729244, -0.1608892136737929, 0.0551780838046262, -0.3832279347604332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23368762548039063, 0.19962828462710325, -0.14121485315268698, 0.14547588516693374, 0.0001829741305017802, -0.09830405975813139, 0.17982750155758723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548835370686713, -0.1941421120296164, 0.01146264143174999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992313101318812, -0.006652692565644477, 0.4317498358492036, 0.0, -0.7537397487466786, 0.19822584140021687, -1.7136341431009776, -1.2562970072993924, -2.6402348296879428, -0.17542754335129496, -0.6366232662843543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4668697844299083, 0.6295930893252552, 1.933275611045951, -1.6759185806028578, -1.404422861464175, -0.33109652878027634, 0.458830413805529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31417750276953854, -0.30502657383305176, 0.02893846063414057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.712000649054735e-05, 0.10099032096546418, 0.05551787251952504, 0.0, 0.2662305948237139, -0.4156015240088871, -0.5764746231597715, 0.01390581938442012, -0.15680950052107492, 0.04863200339347323, -0.37791370070514646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2372241614045679, 0.19217027560288796, -0.1453718874269521, 0.14378208935052617, -0.00773967634898096, -0.08854297903997929, 0.1792177219529715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056174102205722, -0.1940483847238996, 0.011090224022863238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999252208256924, -0.0015530650799208427, 0.43409950235886813, 0.0, -0.7396986511357861, 0.17685419495564528, -1.7430875667126164, -1.255473436518051, -2.6478536261191183, -0.1733086480035227, -0.6552608821508061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4548313208956247, 0.638857379542875, 1.9257978066239203, -1.6687987189318956, -1.4051881357602882, -0.3350806539796887, 0.46777352030281205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32446446710359783, -0.3147242513390845, 0.02947827750528296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.179625008542345e-05, 0.10199254971447269, 0.04699333019329052, 0.0, 0.2808219522178488, -0.4274329288914317, -0.5890684722327764, 0.01647141562682765, -0.1523759286235147, 0.04237790695544556, -0.37275231732903635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24076927068567405, 0.1852858043523969, -0.14955608844061632, 0.14239723341924326, -0.015305485922267837, -0.07968250398824721, 0.17886212994566003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20573928668118585, -0.19395355012065485, 0.010796337422847802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992753700588597, 0.003598798511559146, 0.43624739217648045, 0.0, -0.724891741690841, 0.15493734916362287, -1.77317503344434, -1.2545179696671447, -2.65523591858819, -0.17149465918198545, -0.6736491402359694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4426155419967504, 0.6478029342278301, 1.9181098129680592, -1.6617337984280063, -1.4063144055645729, -0.33866476616335506, 0.4767109036375887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3347572324029258, -0.3244171475426142, 0.030005856709231834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6323603871767203e-05, 0.10303727182959976, 0.04295779635224643, 0.0, 0.2961381888989033, -0.43833691584044815, -0.6017493346344696, 0.01910933701812804, -0.1476458493814388, 0.036279776430745134, -0.36776516170326684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24431557797748968, 0.17891109369910227, -0.15375987311722422, 0.14129841007778507, -0.0225253960856932, -0.07168224367332676, 0.17874766669553313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20585530598655982, -0.19385792407059352, 0.010551584078977523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999300727479941, 0.008804094513933344, 0.43832674680155004, 0.0, -0.7092734812854777, 0.1325250230096199, -1.8038896617668416, -1.2534467156304505, -2.662369107290451, -0.170136386354041, -0.6917974923403458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4302206397529396, 0.656452392197265, 1.91021119496771, -1.654710318457212, -1.4077850093685291, -0.3418894014845274, 0.48565401651967277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34505557801701003, -0.3341052161568823, 0.03052500721608979]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.071484216269138e-05, 0.10410592004748395, 0.041587092501391226, 0.0, 0.3123652081072662, -0.4482465230800592, -0.6142925664500328, 0.02142508073388495, -0.14266377404522404, 0.02716545655888939, -0.3629670420875271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.247898044876214, 0.1729891593886999, -0.15797236000698112, 0.1404695994158832, -0.029412076079125125, -0.06449270642344677, 0.17886225764168148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596691228168415, -0.1937613722853621, 0.01038301013715913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993281607735924, 0.014069201764168223, 0.440554074676966, 0.0, -0.6928109809552064, 0.10967925831495132, -1.8352409943354022, -1.2522513346602826, -2.6692418402322686, -0.16918147937709843, -0.7097178193704274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4176478262465135, 0.6648252180781782, 1.9021025352490581, -1.6477151275537387, -1.4095841982762256, -0.3447930230988332, 0.4946136536266191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35535929515115294, -0.3437884526041532, 0.031034178355589064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.4866587303167144e-05, 0.10530214500469758, 0.044546557508319394, 0.0, 0.329250006605426, -0.4569152938933719, -0.627026651371214, 0.023907619403360444, -0.1374546588363505, 0.0190981395388514, -0.3584065406016334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2514562701285214, 0.1674565176182633, -0.16217319437304076, 0.13990381806946717, -0.035983778153928975, -0.05807243228611571, 0.17919274213892625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20607434268285799, -0.19366472894541778, 0.010183422789985429]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993575682648196, 0.019400616468993246, 0.44289768829019843, 0.0, -0.6754744605295335, 0.08646953830834081, -1.8672451722132992, -1.2509139006384626, -2.6758434597702183, -0.1685470814504019, -0.7274240181573949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4048984576701506, 0.6729382830732726, 1.8937852932352317, -1.640735717797071, -1.4116971315210167, -0.3474117904117522, 0.5035999569603018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3656681770246601, -0.3534668961450138, 0.031531318896992885]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.8814982454298406e-05, 0.10662829409650044, 0.04687227226464876, 0.0, 0.3467304085134582, -0.46419440013220997, -0.6400835575579383, 0.02674868043639765, -0.1320323907589963, 0.012687958533930593, -0.3541239757393488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2549873715272559, 0.16226129990188878, -0.16634484027652924, 0.1395881951333539, -0.04225866489582044, -0.05237534625838001, 0.17972606667365373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617763747014317, -0.1935688708172126, 0.009942810828076472]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993888393816484, 0.0248040893394555, 0.44529375356535134, 0.0, -0.657234770570855, 0.06297094490393922, -1.8999212050323753, -1.249412458692867, -2.682164551083141, -0.16816676905990524, -0.7449317767870256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3919731590322595, 0.6808061382983573, 1.8852615233704535, -1.6337601318767279, -1.4141099807966149, -0.3497796362304216, 0.5126224001403346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37598173324735323, -0.36314035844652015, 0.03201440817113183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.254223365770543e-05, 0.10806945740924509, 0.04792130550305777, 0.0, 0.3647937991735709, -0.4699718680880319, -0.6535206563815221, 0.03002883891191481, -0.12642182625846027, 0.007606247809932947, -0.35015517259261514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2585059727578234, 0.15735710450169496, -0.17047539729556585, 0.1395117184068595, -0.048256985511962884, -0.04735691637338743, 0.18044886360065446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20627112445386322, -0.19346924603012725, 0.00966178548277895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994218755304446, 0.03028111445937137, 0.4476983151298864, 0.0, -0.638051332776127, 0.03926257745153229, -1.9332743876008847, -1.2477508441344103, -2.688197452370262, -0.16810928445998144, -0.7622579496811501, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3788697670593844, 0.6884412863522363, 1.8765336079476393, -1.6267770578307548, -1.4168099483184164, -0.35192815298540625, 0.521689746529341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38629983835555937, -0.3728089685767702, 0.03248476983167084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.607229759236975e-05, 0.10954050239831736, 0.04809123129070107, 0.0, 0.3836687558945604, -0.4741673490481384, -0.6670636513701855, 0.03323229116913221, -0.12065802574241588, 0.001149691998475956, -0.3465234578824916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2620678394575032, 0.15270296107757883, -0.17455830845628348, 0.13966148091946143, -0.053999350436031546, -0.04297033509969325, 0.1813469277801277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063621021641231, -0.19337220260500151, 0.009407233210780217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994565462695438, 0.035833492498871876, 0.4500905981744083, 0.0, -0.6178842585120434, 0.015431057167064749, -1.9673061459951764, -1.2459416831053933, -2.6939362728567957, -0.16848615907127737, -0.7794214344100959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3655861790610817, 0.695854000809875, 1.8676041606193066, -1.6197754582617239, -1.4197854587358523, -0.35388704398114024, 0.5308099776510703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3966223687317779, -0.382472854002744, 0.03294257592190131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.934147819820369e-05, 0.11104756079001019, 0.04784566089043712, 0.0, 0.40334148528167124, -0.47663040568935083, -0.6806351678858344, 0.03618322058034058, -0.11477640973067882, -0.007537492225918648, -0.3432696945789163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26567175996605197, 0.1482542891527731, -0.1785889465666572, 0.14003199138061714, -0.05951020834871641, -0.03917781991467974, 0.18240462243458555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064506075243705, -0.1932777085194761, 0.009156121804609322]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994927114146885, 0.04146423281254037, 0.4524652423308594, 0.0, -0.5967002839762974, -0.008428315810264247, -2.002019540532723, -1.2439956941687156, -2.6993758339653144, -0.16940299491767172, -0.7964438610998594, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3521212162123777, 0.7030525069188116, 1.8584760797939717, -1.6127446918799009, -1.4230261952653138, -0.35568434019006, 0.539990275195647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4069491874556222, -0.3921321596665384, 0.0333861414163522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.233029028954226e-05, 0.1126148062733699, 0.04749288312902246, 0.0, 0.42367949071492217, -0.4771874595465799, -0.694267890750924, 0.038919778733553526, -0.10879122217037608, -0.018336716927886926, -0.3404485337952699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2692992569740784, 0.14397012217873117, -0.18256161650669792, 0.14061532763645895, -0.0648147305892294, -0.035945924178395046, 0.1836059508915353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20653637447688533, -0.19318611327588817, 0.008871309889017753]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995302292547737, 0.04717719163981723, 0.45482467173455715, 0.0, -0.5744743481247945, -0.03221191560342329, -2.0374207516577627, -1.2419173313528997, -2.704510349690118, -0.17094461988618306, -0.8133500607854194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.338474363592058, 0.710043323425046, 1.849152611281147, -1.6056747744240032, -1.4265230589240911, -0.3573465118464638, 0.5492370613052514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4172801236089696, -0.40178706148223914, 0.03381250417578785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.50356801704552e-05, 0.1142591765455371, 0.0471885880739552, 0.0, 0.4445187170300572, -0.47567199586318076, -0.7080242225007946, 0.041567256316315505, -0.10269031449607864, -0.030832499370226814, -0.3381239937112001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27293705240639565, 0.13981633012468742, -0.18646937025649496, 0.14139834911795557, -0.06993727317554597, -0.03324343312807645, 0.18493572219208787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2066187230669484, -0.1930980363140145, 0.008527255188713103]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995689562569696, 0.0529764013584553, 0.4571740315963459, 0.0, -0.5511892882837658, -0.05580878834381451, -2.0735186015691505, -1.2397038596385224, -2.70933229877117, -0.17317392474171134, -0.8301683189783522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3246456650861915, 0.716831383794669, 1.8396373038523934, -1.5985564082349324, -1.4302681534635762, -0.3588985346995499, 0.558555999158406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42761497664776876, -0.4114377704488579, 0.03421828106622663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.745400439178555e-05, 0.1159841943727615, 0.046987197235774894, 0.0, 0.4657011968205729, -0.4719374548078243, -0.7219569982277539, 0.04426943428754573, -0.09643898162103368, -0.044586097110565416, -0.33636516385865606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2765739701173271, 0.1357612073924629, -0.19030614857507142, 0.1423673237814152, -0.07490189078970134, -0.03104045706172176, 0.18637875706309256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20669706077598285, -0.1930141793323752, 0.008115537808775676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996089890845417, 0.05888883692989693, 0.4595184800629568, 0.0, -0.526901883015525, -0.07893182781676603, -2.110092321432455, -1.2373198520905968, -2.7134998146319544, -0.17613304333447521, -0.8465907922731724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.310653127481421, 0.7234196128227636, 1.8299352386537378, -1.5913806634700793, -1.4342550396317781, -0.36036587707562534, 0.5679520932180644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4379532912986751, -0.421084771078369, 0.03457703990224904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.006565514422405e-05, 0.11824871142883255, 0.046888969332218, 0.0, 0.485748105364817, -0.4624607894590302, -0.7314743972660956, 0.047680150958511774, -0.08335031721568739, -0.05918237185527777, -0.32844946589640434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27985075209540916, 0.13176458056189136, -0.19404130397311342, 0.14351489529706157, -0.07973772336403934, -0.029346847521508145, 0.18792188119316772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20676629301812666, -0.1929400125902228, 0.007175176720448172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999650598841945, 0.06497439219545284, 0.4618620525147836, 0.0, -0.5017975861345425, -0.10103100307083646, -2.1465184654326808, -1.234674623861658, -2.7161027121378716, -0.17985000619381897, -0.8617340947443358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2965438552155464, 0.7298096042905275, 1.8200545056691093, -1.5841400898195637, -1.4384785532693973, -0.36177571462075087, 0.5774299590274339, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4482940391134155, -0.43072916432052577, 0.034829289387686035]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.3219514806687e-05, 0.12171110531111831, 0.046871449036536506, 0.0, 0.5020859376196491, -0.4419835050814085, -0.7285228800045104, 0.05290456457877694, -0.052057950118340725, -0.07433925718687479, -0.30286604942326895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28218544531749395, 0.1277998293552787, -0.1976146596925673, 0.14481147301031166, -0.0844702727523845, -0.028196750902510892, 0.18955731618739077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2068149562948069, -0.19288786484313503, 0.0050449897087399016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996936354723793, 0.07126622309335441, 0.4642074181845505, 0.0, -0.4760551418039262, -0.12167984801784872, -2.1822476332991476, -1.2316783456747256, -2.716361757472941, -0.18434645519981743, -0.8748556332219445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.282349992373356, 0.7360038559743707, 1.8100036805633035, -1.5768306365002767, -1.4429338617451328, -0.36315222153362153, 0.5869939497017014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4586358746761437, -0.44037239127138705, 0.0349420811878866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.607326086861515e-05, 0.12583661795803136, 0.046907313395338227, 0.0, 0.5148488866123256, -0.4129768989402451, -0.7145833573293369, 0.05992556373864878, -0.005180906701383242, -0.08992898011996939, -0.26243076955217426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28387725684381143, 0.12388503367686289, -0.20101650211611713, 0.14618906638573945, -0.08910616951470839, -0.027530138257413045, 0.1912798134853488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683671125456485, -0.19286453901722592, 0.0022558360040113136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997379143001764, 0.07776899639084262, 0.46655600538470354, 0.0, -0.4498147428041323, -0.1406513385680828, -2.2169279753438587, -1.228267958933324, -2.7138063538676853, -0.18962681856315414, -0.8855349017778712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2680810973387941, 0.7420045623063706, 1.7997893976568422, -1.5694488605442787, -1.4476169525708655, -0.36451601216623863, 0.5966479672555021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46897740788126946, -0.4500159440950995, 0.03491072156614704]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.855765559401911e-05, 0.13005546594976414, 0.046971744003060124, 0.0, 0.5248079799958779, -0.3794298110046814, -0.6936068408942236, 0.0682077348280285, 0.05110807210511245, -0.1056072672667343, -0.21358537111853512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2853779006912345, 0.12001412663999692, -0.20428565812922733, 0.1476355191199587, -0.09366181651465605, -0.02727581265234201, 0.19308035107601457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683066410251555, -0.1928710564742491, -0.00062719243479135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997859488869993, 0.08449411927742755, 0.46890829058041245, 0.0, -0.423228987139392, -0.15802175540469443, -2.249987385598714, -1.2241457216270608, -2.7084187345750443, -0.1957180323196668, -0.893782711064083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.253748187745712, 0.7478123549353348, 1.7894169406863398, -1.5619896511407834, -1.4525252844554515, -0.36588689044702444, 0.6063954373352898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4793171384805335, -0.4596614333567058, 0.03472380389854716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.606917364578337e-05, 0.1345024577316986, 0.047045703914178304, 0.0, 0.5317151132948059, -0.3474083367322327, -0.6611882050971059, 0.08244474612526588, 0.10775238585281527, -0.12182427513025361, -0.1649561857242356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.286658191861644, 0.11615585257928451, -0.20744913941004678, 0.14918418806990458, -0.09816663769171755, -0.027417565615715768, 0.19494940159575466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2067946119852808, -0.19290978523212576, -0.0037383533519975355]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998346517918872, 0.09141406724463508, 0.4712641065329575, 0.0, -0.3963772718905486, -0.17371562945071847, -2.2814760175244753, -1.219360925440738, -2.7002327508410016, -0.20256769550311668, -0.8997134077907735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.239329617790521, 0.7534266524824335, 1.7788887401772873, -1.5544474328996274, -1.4576573351045903, -0.3672799495537857, 0.6162389829320788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48965387642560615, -0.4693104482638417, 0.03440900117209651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.740580977579372e-05, 0.13839895934415067, 0.047116319050902106, 0.0, 0.5370343049768674, -0.31387748092048084, -0.629772638515227, 0.0956959237264568, 0.16371967468085852, -0.13699326366899722, -0.11861393453380784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28837139910381737, 0.11228595094197273, -0.21056401018104937, 0.15084436482312133, -0.1026410129827759, -0.027861182135225065, 0.19687091193577935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20673475890145315, -0.19298029814271903, -0.006296054529012879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998837262983027, 0.0984876371474542, 0.4736228512128817, 0.0, -0.36931688053387773, -0.18773598357623295, -2.3116213955634004, -1.2140251347964188, -2.6893801310269607, -0.21009366952295444, -0.903551021511901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2247864723311725, 0.7588446208607488, 1.7682046484249256, -1.5468142979099502, -1.463013101024749, -0.3687074540384244, 0.6261802995106079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49998676525617464, -0.47896382469304655, 0.03400803337286887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.814901283098824e-05, 0.14147139805638256, 0.04717489359848419, 0.0, 0.5412078271334178, -0.2804070825102892, -0.6029075607785047, 0.1067158128863861, 0.21705239628081968, -0.15051948039675508, -0.07675227442255034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2908629091869693, 0.10835936756630725, -0.21368183504723234, 0.1526626997935423, -0.1071153184031709, -0.028550089692774814, 0.1988263315705836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20665777661136933, -0.19306752858409676, -0.008019355984552914]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999333034850686, 0.105673669795564, 0.4759836606629676, 0.0, -0.3420989319308359, -0.2001784404608327, -2.3406676079286513, -1.2082366255708006, -2.676068847338364, -0.2181991233110978, -0.9055950446480462, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.210074347685301, 0.7640609965663732, 1.7573630303574068, -1.53907990480734, -1.4685941695923914, -0.3701801278166298, 0.636220089338161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5103153663581976, -0.4886219727508629, 0.03356302377694085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.915437353183409e-05, 0.14372065296219605, 0.047216189001717875, 0.0, 0.5443589720608369, -0.2488491376919947, -0.5809242473050138, 0.11577018451236276, 0.2662256737719409, -0.16210907576286726, -0.04088046272290302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2942424929174305, 0.10432751411248795, -0.2168323613503749, 0.1546878620522016, -0.11162137135285063, -0.02945347556410772, 0.2007957965510602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20657202204046005, -0.19316296115632664, -0.00890019191856041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999985724046607, 0.11296025548712392, 0.47834557029358193, 0.0, -0.314801405808413, -0.21118625359244553, -2.3685314160903346, -1.2018226217381398, -2.660668603774185, -0.2268306392523497, -0.906272283081831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.195169438262761, 0.7690689721673792, 1.746363206779349, -1.531232376173149, -1.474403504951756, -0.3717100360535933, 0.6463583943527268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5206393882958547, -0.49828517094116875, 0.03308743223331075]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010484112307689969, 0.1457317138311984, 0.04723819261228707, 0.0, 0.5459505224484582, -0.22015626263225668, -0.5572761632336668, 0.12828007665321645, 0.3080048712835719, -0.17263031882503777, -0.013544768675696726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.298098188450805, 0.10015951202012112, -0.21999647156115473, 0.15695057268381932, -0.11618670718729492, -0.030598164739270173, 0.20276610029131695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20648043875314065, -0.19326396380611774, -0.00951183087260194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000386188984348, 0.1203205677287292, 0.48070759131574803, 0.0, -0.287474989770132, -0.22085635045821775, -2.3954222793204267, -1.1948892232481507, -2.643436904418872, -0.23587381765469737, -0.9059314193362062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.180038166023946, 0.7738608510681475, 1.7352056038860497, -1.5232611904860027, -1.4804446693925655, -0.3733069528951633, 0.6565944608268954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5309588079582727, -0.5079534101611066, 0.032609806416965675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010578970365539403, 0.14720624483210576, 0.04724042044332186, 0.0, 0.5465283207656204, -0.19340193731544422, -0.5378172646018428, 0.1386679697997807, 0.34463398710626403, -0.18086356804695347, 0.006817274912495987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30262544477629516, 0.09583757801536633, -0.22315205786598608, 0.15942371374292477, -0.12082328881618842, -0.031938336831399336, 0.20472132948337274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063883932483591, -0.1933647843987567, -0.009552516326901475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000916494083057, 0.12770763567726107, 0.4830687392069244, 0.0, -0.26019308643958283, -0.22931048175714647, -2.4215463400455506, -1.1875815492128718, -2.6246036628231084, -0.24515225513938024, -0.9048815573555332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1647218529199097, 0.7783765005428815, 1.723859375416625, -1.5150999797468971, -1.486737404398827, -0.37496984157688623, 0.6669070107583583, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5412740650655505, -0.5176261007453624, 0.03217890689697536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010606101974169083, 0.1477413589706372, 0.04722295782352715, 0.0, 0.5456380666109822, -0.16908262597857465, -0.522481214502478, 0.1461534807055757, 0.37666483191527816, -0.1855687496936574, 0.020997239613460877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30632626208072616, 0.09031298949467995, -0.22692456938849484, 0.16322421478210972, -0.12585470012523042, -0.03325777363445849, 0.20625099862925758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20630514214555695, -0.19345381168511577, -0.008617990399806234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001438740509397, 0.13491240604240237, 0.4854280578776173, 0.0, -0.23325017153039881, -0.23668803750654724, -2.4469621100956136, -1.180043409121759, -2.604441923727538, -0.2542616803190728, -0.9034046231800951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1500139995816223, 0.7820642540186723, 1.711999903987663, -1.5061554522402196, -1.4934494542740804, -0.37658879725504163, 0.6770756911532064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5515865469940715, -0.5272662582455687, 0.03200561485251141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444928526822455, 0.1440954073028262, 0.04718637341385814, 0.0, 0.5388582981836805, -0.14755111498801532, -0.5083154010012589, 0.15076280182225638, 0.4032347819114077, -0.18218850359385164, 0.029538683508763354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2941570667657477, 0.07375506951581443, -0.23718942857923855, 0.17889055013354835, -0.13424099750506613, -0.03237911356310805, 0.20337360789696188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2062496385704195, -0.1928031500041254, -0.0034658408892790024]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001956923917136, 0.14209490819490286, 0.48778483406484985, 0.0, -0.20719014955641507, -0.2431537045007487, -2.4717559018778976, -1.1723466381173246, -2.5832851837647595, -0.26272698890159707, -0.9018119287954139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1362925875347156, 0.7846942107354439, 1.6995945594881667, -1.4962533594938423, -1.500654434469294, -0.37804175814020746, 0.6869377230363743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5618772554935478, -0.5362481924237863, 0.03193009384487926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001036366815479113, 0.14365004305001008, 0.047135523744650826, 0.0, 0.5212004394796748, -0.12931333988402918, -0.4958758356456816, 0.15393542008868819, 0.42313479925557457, -0.16930617165048542, 0.031853887693621664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2744282409381327, 0.052599134335431535, -0.24810688998992422, 0.1980418549275443, -0.1440996039042721, -0.029059217703316893, 0.1972406376633577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20581416998952623, -0.17963868356435048, -0.001510420152642911]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20002491398495875, 0.1494178801698363, 0.49014213867983025, 0.0, -0.18248615642303045, -0.24874252779424932, -2.495791256850934, -1.1643342319297219, -2.561549609322388, -0.27017462278306265, -0.9004516927928198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1235910388524077, 0.7862627988346579, 1.686786930289798, -1.4854969415594632, -1.5083462475227143, -0.3792270963843562, 0.6964032961833078, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5721284937799476, -0.544042023523245, 0.03174277720679715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010689491574809543, 0.14645943949866824, 0.047146092299607985, 0.0, 0.494079862667692, -0.11177646587001251, -0.4807070994607294, 0.1602481237520551, 0.43471148884742883, -0.14895267762931144, 0.027204720051883843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25403097364615596, 0.031371761984279836, -0.2561525839673737, 0.21512835868758007, -0.15383626106840426, -0.023706764882974334, 0.1893114629386691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2050247657279953, -0.15587662198917399, -0.00374633276164229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000302436587149, 0.1568804363366327, 0.4925089959261279, 0.0, -0.15942620646426864, -0.2535716429058741, -2.5191037233799887, -1.1561081590561926, -2.5395311185199434, -0.2762882019431225, -0.8995733094187667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1117286539701878, 0.7868744141902151, 1.6737792940401723, -1.474100709544747, -1.5164731868474546, -0.3800749465354888, 0.705439711141863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.582334625025694, -0.5505038053914475, 0.031328551739566904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010659347512320952, 0.14925112333592852, 0.04733714492595309, 0.0, 0.46119899917523643, -0.09658230223249553, -0.4662493305810919, 0.16452145747058344, 0.4403698160488929, -0.12227158320119691, 0.017567667481062112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23724769764439968, 0.012232307111143079, -0.26015272499251113, 0.2279246402943277, -0.16253878649480763, -0.016957003022651775, 0.1807282991711045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.204122624914929, -0.12923563736404983, -0.008284509344604833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000355409762551, 0.1643493632969471, 0.4948989781480506, 0.0, -0.138134306608576, -0.25778286324663996, -2.541755761063006, -1.1478203450866038, -2.517453701537978, -0.2808626769029118, -0.8993496529219878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1004377528853015, 0.7866677740581992, 1.6607635289911855, -1.4622859299485154, -1.5249653079719356, -0.38055155981383115, 0.7140521457823096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5924971178994362, -0.5556901650508949, 0.03066177407118626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010594635080377414, 0.14937853920628794, 0.047799644438453984, 0.0, 0.42583799711385245, -0.08422440681531787, -0.45304075366034996, 0.16575627939177673, 0.4415483396393033, -0.09148949919578589, 0.00447312993557779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22581802169772486, -0.004132802640316704, -0.2603153009797381, 0.2362955919246301, -0.16984242248962297, -0.00953226556684723, 0.17224869280893232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324985747484237, -0.1037271931889466, -0.01333555336761289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004081292641204, 0.17163111684490254, 0.4973273540293955, 0.0, -0.11861098806654552, -0.261506003937954, -2.563792455725704, -1.1396190617008346, -2.4954889007469143, -0.2838319038624897, -0.8998890469110882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0894421809363275, 0.7857788657157315, 1.6478909021820578, -1.4502320834056803, -1.5337515051369732, -0.3806565744431942, 0.7222674722419069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6026210959822068, -0.559746501253625, 0.029776897416194534]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010543900313926698, 0.14563507095910855, 0.048567517626897164, 0.0, 0.3904663708406098, -0.0744628138262803, -0.44073389325396295, 0.1640256677153848, 0.4392960158212723, -0.059384539191558075, -0.010787879782008984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21991143897947918, -0.017778166849353613, -0.2574525361825549, 0.2410769308567017, -0.17572394330075108, -0.0021002925872602293, 0.16430652919194655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20247956165541275, -0.08112672405460414, -0.01769753309983457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004606432832564, 0.1785368757147403, 0.4998084022537411, 0.0, -0.10078082637104352, -0.264847160038961, -2.5852379440488384, -1.131630598596612, -2.4737657902986205, -0.28524416183276086, -0.9012452613483256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.078500262559309, 0.7843260714150962, 1.6352650158000486, -1.4380627524161154, -1.5427684175926506, -0.3804169066440311, 0.7301226067745017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6127129574718959, -0.5628429113478618, 0.028737698239593924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001050280382721323, 0.1381151773967553, 0.04962096448691232, 0.0, 0.35660323391003995, -0.06682312202014098, -0.4289097664626888, 0.15976926208445047, 0.43446220896587195, -0.02824515940542372, -0.027124288744748738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21883836754036934, -0.029055886012705798, -0.2525177276401867, 0.24338661979130038, -0.1803382491135461, 0.004793355983261567, 0.1571026906518956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20183722979378182, -0.06192820188473633, -0.020783983532012218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005129930180776, 0.1849245954383537, 0.5023535969404489, 0.0, -0.0845365476780033, -0.26789192708329723, -2.606108693073243, -1.1239444492086228, -2.452378330247755, -0.2852004259172213, -0.903428031037695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0674226840202274, 0.7824081342080057, 1.6229472251942958, -1.4258507451503226, -1.5519634683297958, -0.3798798984965973, 0.7376575659920607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6227788903479773, -0.5651382965458367, 0.027612209173982813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010469946964228746, 0.12775439447226813, 0.05090389373415543, 0.0, 0.32488557386080436, -0.06089534088672406, -0.4174149804880978, 0.1537229877597814, 0.42774920101731634, 0.0008747183107913163, -0.04365539378738713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22155157078163232, -0.038358744141811715, -0.24635581211505642, 0.24424014531585422, -0.18390101474290552, 0.010740162948676057, 0.15069918435117943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2013186575216267, -0.0459077039594976, -0.02250978131222222]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005652136933838, 0.1907115542078159, 0.5049708022133425, 0.0, -0.06976173780440523, -0.27070753685227544, -2.6264208198234114, -1.116616946684467, -2.4313907896673914, -0.2838218803566358, -0.906412585221189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0560736135802962, 0.7801058082827312, 1.6109657132036308, -1.4136290432962257, -1.5612950664604608, -0.37910605441542466, 0.7449113819247415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6328242153560852, -0.5667667343942321, 0.026461026087480004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444135061213921, 0.1157391753892438, 0.052344105457870035, 0.0, 0.29549619747196143, -0.05631219537956404, -0.40624253500336754, 0.14655005048311465, 0.4197508116072699, 0.02757091121170977, -0.05969108366987838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22698140879862486, -0.046046518505490075, -0.23963023981329837, 0.24443403708193845, -0.18663196261329876, 0.015476881623452673, 0.14507631865361617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200906500162158, -0.032568756967906835, -0.023023661730056176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006173377981204, 0.19586946360562876, 0.5076644609626558, 0.0, -0.05634179204398947, -0.27334548158613015, -2.646193322366273, -1.1096790839813315, -2.410842927702957, -0.2812329746831892, -0.9101485177967618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0443638223042633, 0.7774845919923008, 1.5993249042842526, -1.4014024614291, -1.570731417155611, -0.3781624858127281, 0.751920026015881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6428532286355354, -0.5678352846961159, 0.025332638215552584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010424820947313969, 0.10315818795625725, 0.05387317498626852, 0.0, 0.26839891520831505, -0.05275889467709448, -0.3954500508572305, 0.138757254062713, 0.4109572392886899, 0.051778113468932276, -0.07471865151145703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23419582552065923, -0.05242432580860899, -0.23281617838756566, 0.24453163734251182, -0.1887270139030052, 0.018871372053931603, 0.14017288182279053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005802655890033, -0.02137100603767564, -0.02256775743854842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006693974018563, 0.20041148659983554, 0.5104356354131638, 0.0, -0.04416856961827303, -0.2758444403769414, -2.6654490711305923, -1.103143801672166, -2.3907551627710806, -0.2775528776658062, -0.9145677909379701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.032240873995808, 0.7745974410638581, 1.588013709038981, -1.3891577880418844, -1.5802488161344124, -0.37711757562047643, 0.7587156306949181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6528692669109263, -0.5684268272253782, 0.024262524580118537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010411920747207684, 0.09084045988413576, 0.0554234890101607, 0.0, 0.24346444851432894, -0.049979175816224464, -0.3851149752863885, 0.1307056461833094, 0.4017552986375233, 0.07360194034765936, -0.08838546282416829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2424589661691047, -0.05774301856885468, -0.2262239049054323, 0.24489346774431225, -0.19034797957602634, 0.020898203845033683, 0.13591209358074058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032076550781866, -0.011830850585245457, -0.02140227270868092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007214257134473, 0.2043774343813399, 0.5132834444778108, 0.0, -0.033141879221293254, -0.27823311442357535, -2.684214783748266, -1.0970116831686958, -2.3711334911723347, -0.27289151361168223, -0.9195916030855968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0196792372387637, 0.7714870996542419, 1.577012080120262, -1.3768717128358068, -1.5898299178620672, -0.376037003117718, 0.7653264677326032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6628748614477549, -0.5686045085855391, 0.023274225345194223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010405662318178713, 0.07931895563008712, 0.05695618129293898, 0.0, 0.22053380793959546, -0.04777348093267944, -0.3753142523534738, 0.12264237006940129, 0.3924334319749157, 0.09322728108248012, -0.10047624295253367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.251232735140885, -0.06220682819232286, -0.22003257837437873, 0.24572150412155103, -0.191622034553094, 0.02161145005516844, 0.13221674075370154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001118907365725, -0.003553627203219339, -0.019765984698486314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007734580778586, 0.20782070618049545, 0.5162057356413299, 0.0, -0.02316952921589255, -0.2805327086574647, -2.7025206472294165, -1.0912751301891823, -2.3519738846130913, -0.26734808709481267, -0.9251359659670314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0066716891018626, 0.7681879876718668, 1.5662958363212114, -1.364516539676587, -1.5994622264425942, -0.3749810550619353, 0.7717773035049438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728719094996554, -0.5684161418783988, 0.022381311534141354]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010406472882246143, 0.06886543598311097, 0.0584458232703806, 0.0, 0.19944700010801403, -0.04599188467778787, -0.36611726962300406, 0.11473105959026818, 0.3831921311848679, 0.11086853033739165, -0.11088725762869056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26015096273802274, -0.06598223964750083, -0.21432487598101155, 0.24710346318439644, -0.19264617161054026, 0.021118961115654065, 0.1290167154468116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994096103801032, 0.003767334142805944, -0.017858276221057384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008255327007832, 0.2107984551058236, 0.5192101868201725, 0.0, -0.014166840177746965, -0.2827589651423013, -2.7203998728202277, -1.085921389661834, -2.333265997210729, -0.2610109256209237, -0.9311159707638332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.993222525276789, 0.76472770791297, 1.5558399599130788, -1.3520640084958147, -1.609136898369661, -0.3740030351449078, 0.7780898891731596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6828618146769264, -0.5678979208460078, 0.02158961746419203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010414924584927073, 0.059554978506562724, 0.060089023576853036, 0.0, 0.18005378076291173, -0.044525129696731926, -0.35758451181622114, 0.10707481054696666, 0.3741577480472417, 0.12674322947777925, -0.11960009593603711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2689832765014719, -0.06920559517793774, -0.2091175281626519, 0.24905062361544741, -0.19349343854133583, 0.01956039834054967, 0.12625171336431662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19979810354541996, 0.01036442064782242, -0.015833881398986463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008787845500087, 0.21333432017666262, 0.522278620524105, 0.0, -0.005963419259842758, -0.2847067784692105, -2.737706908660592, -1.0808938141815105, -2.3150267722676117, -0.25438667800412285, -0.9374635516762867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9793618168468088, 0.7611051078601969, 1.545609423592007, -1.3394608678986315, -1.6188542055022237, -0.3731361931769705, 0.784273511539081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6928467960164502, -0.5671346529160782, 0.02093020073211555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010650369845106335, 0.050717301416780575, 0.06136867407865102, 0.0, 0.16406841835808414, -0.038956266538184035, -0.34614071680728536, 0.10055150960646979, 0.3647844988623467, 0.13248495233601743, -0.12695161824906995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27721416859960457, -0.07245200105546167, -0.20461072642143427, 0.2520628119436626, -0.194346142651256, 0.01733683935874627, 0.12367244731842914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19969962679047468, 0.015265358598590295, -0.013188334641529539]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000932460772157, 0.2154911957901415, 0.5254075520960675, 0.0, 0.0015154044261366864, -0.28641516619292723, -2.7544320930412285, -1.076174171725622, -2.2972498271597006, -0.24759982073920533, -0.9441141009023792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9651278873460428, 0.757327427091728, 1.535580448860818, -1.326672138264618, -1.628612812424153, -0.37240896197700574, 0.7903376336523634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7028278828753675, -0.5661656331890602, 0.020389486558202795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010735244429674809, 0.04313751226957778, 0.0625786314392504, 0.0, 0.14957647371958888, -0.03416775447433472, -0.33450368761273663, 0.09439284911777152, 0.35553890215822376, 0.13573714529835043, -0.13301098452185098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2846785900153182, -0.07555361536937943, -0.20057949462378213, 0.25577459268027014, -0.19517213843858824, 0.01454462399929483, 0.12128244226564817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.199621737178345, 0.019380394540359974, -0.010814283478255146]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000986504638207, 0.2173348800863795, 0.5285963538711298, 0.0, 0.008311286985787932, -0.2879703140158385, -2.770613356296178, -1.071752895513645, -2.2799188962291113, -0.24064150349451635, -0.9510100879683961, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9505529498723302, 0.7534056826233598, 1.5257378740419243, -1.3136770586139697, -1.63841007581735, -0.37184397678607, 0.7962921332243709, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7128055169800916, -0.5650064298475672, 0.019945411914984862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010808773209972387, 0.036873685924759945, 0.06377603550124566, 0.0, 0.13591765119302487, -0.031102956458224976, -0.32362526509899225, 0.08842552423953609, 0.3466186186117867, 0.13916634489377944, -0.13791974132033838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2914987494742535, -0.07843488936736323, -0.19685149637787305, 0.25990159301296684, -0.19594526786394395, 0.011299703818714464, 0.11908999144014908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19955268209448396, 0.023184066829859785, -0.008881492864358671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001040952281578, 0.21892164502751066, 0.5318443998538492, 0.0, 0.014455434372994066, -0.2894449297458632, -2.7863038589103057, -1.0676217341506595, -2.263014026217533, -0.23346849295648808, -0.9581014231716674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9356598942300804, 0.7493518268839664, 1.5160721145437042, -1.3004642700198759, -1.6482428027961602, -0.37145864779806914, 0.8021471910765554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7227798395497232, -0.5636600458570635, 0.019578016659266558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010889528674247463, 0.03173529882262352, 0.0649609196543887, 0.0, 0.12288294774412264, -0.029492314600493903, -0.313810052282559, 0.08262322725971165, 0.33809740023156404, 0.14346021076056528, -0.14182670406542525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2978611128449939, -0.08107711478786886, -0.19331518996440414, 0.2642557718818771, -0.19665453957620216, 0.007706579760017614, 0.11710115704369055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19948645139263124, 0.026927679810074084, -0.007347905114366092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001095818476272, 0.2202943968225748, 0.535150869996002, 0.0, 0.019976112404964497, -0.2908868408754237, -2.801560742506763, -1.0637723948338313, -2.246514853532375, -0.2260387914595803, -0.9653442577370467, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9204627132754218, 0.7451771967137655, 1.5065767335510407, -1.2870279213106035, -1.6581079764407811, -0.3712661111733493, 0.8079130441774274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7327508384249672, -0.5621229025816208, 0.01927182718937029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010973238938801623, 0.027455035901282798, 0.06612940284305621, 0.0, 0.11041356063940856, -0.028838222591209578, -0.3051376719291418, 0.07698678633656415, 0.3299834537031666, 0.1485940299381555, -0.14485669130758602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3039436190931732, -0.08349260340401757, -0.189907619853269, 0.26872697418544794, -0.19730347289241743, 0.003850732494397405, 0.11531706201743988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19941997750488044, 0.030742865508854446, -0.0061237893979253916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20011511096299092, 0.2214825190671099, 0.5385151065100857, 0.0, 0.02490084713840034, -0.2923229338625861, -2.8164412711336357, -1.060196351782816, -2.2304025030501005, -0.21832156697497618, -0.9726993825050722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9049681306376484, 0.740891755553815, 1.4972467377444765, -1.2733648666517141, -1.6680033011218867, -0.3712761292836445, 0.8135997040895893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7427184266565153, -0.560388285861029, 0.019015717754810958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011058230727444141, 0.023762444890702263, 0.06728473028167319, 0.0, 0.09849469466871684, -0.028721859743248285, -0.2976105725374558, 0.07152086102030841, 0.32224700964548914, 0.15434448969208248, -0.14710249536050946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30989165275546887, -0.08570882319900835, -0.1865999161312844, 0.27326109317778985, -0.19790649362210908, -0.00020036220590430396, 0.11373319824323874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935176463096194, 0.03469233441183588, -0.0051221886911865955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012068354139295, 0.22250349531401678, 0.5419369045324964, 0.0, 0.029256928531896972, -0.29376602433815924, -2.8310013768663658, -1.0568847414431133, -2.2146607151661373, -0.21029745116627052, -0.9801307890007165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8891775148909307, 0.7365037811966567, 1.4880774850525833, -1.2594727666522887, -1.677927543943993, -0.37149579637202673, 0.8192166918784729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.752682486082162, -0.5584484377725315, 0.018802084615086322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011145156804087516, 0.020419524938137586, 0.06843596044821347, 0.0, 0.08712162786993259, -0.02886180951146266, -0.2912021146546042, 0.06623220679405235, 0.3148357576792621, 0.1604823161741131, -0.14862812991288768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3158123149343549, -0.08775948714316552, -0.18338505383786374, 0.2778419999885099, -0.19848485644212302, -0.00439334176764448, 0.112339755777672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19928118851293328, 0.0387969617699493, -0.004272662794492707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012628164617755, 0.22332134060079772, 0.54541662471814, 0.0, 0.03317120156856523, -0.29518464960895535, -2.8451380890300952, -1.053961604220274, -2.1992726208632316, -0.20265878664500153, -0.9876002580722529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8730997429735209, 0.7319946575093498, 1.4790548783712623, -1.2453195416574887, -1.687887002196704, -0.37191213155652425, 0.8247616904031708, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7626439397110358, -0.556356609092534, 0.018669902169850008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001119620956917603, 0.01635690573561878, 0.06959440371287186, 0.0, 0.07828546073336504, -0.02837250541592201, -0.282734243274592, 0.05846274445678641, 0.30776188605811694, 0.15277329042537996, -0.14938938143072922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32155543834819605, -0.0901824737461377, -0.18045213362641968, 0.28306449989600013, -0.1991891650542251, -0.00832670368995064, 0.11089997049395796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19922907257747532, 0.04183657359994846, -0.002643648904726283]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013192442139177, 0.2239482275425103, 0.5489548371269524, 0.0, 0.0366715792278375, -0.296586524353173, -2.8588493933976524, -1.0514203929343469, -2.184236114366281, -0.1954379262848652, -0.9950902730344263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8567527786674105, 0.7273588576734159, 1.4701719485389229, -1.230888881533351, -1.6978848911636142, -0.37251543196268055, 0.8302341701041117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7726029312808944, -0.5541258337645512, 0.018610119682379557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001128555042845191, 0.0125377388342514, 0.07076424817624641, 0.0, 0.07000755318544544, -0.028037494884353635, -0.27422608735114595, 0.050824225718544155, 0.3007301299390082, 0.14441720720272663, -0.1498002992434688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32693928612220846, -0.09271599671867779, -0.17765859664678813, 0.28861320248275546, -0.1999577793382039, -0.012066008123126602, 0.1094495940188172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917983139717088, 0.044615506559656834, -0.0011956497494090225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013761457522716, 0.22440734591479483, 0.5525510066268541, 0.0, 0.03975911638397082, -0.29798216934315713, -2.8721656295211786, -1.0492191300271183, -2.1695526216527776, -0.18848173123026996, -1.0025971718647806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8401509814292484, 0.7225974376254728, 1.461426296142665, -1.2161747018287186, -1.7079221563356972, -0.3732971774069232, 0.8356348772421495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7825592728935553, -0.5517519790258053, 0.018604268532772555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011380307670761093, 0.009182367445690917, 0.07192338999803456, 0.0, 0.06175074312266636, -0.027912899799682093, -0.2663247224705193, 0.044025258144572164, 0.29366985427007, 0.13912390109190506, -0.15013797660708325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3320359447632418, -0.09522840095886133, -0.17491304792515783, 0.2942835940926487, -0.20074530344166105, -0.01563490888485266, 0.1080141427607551, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19912683225321814, 0.04747709477491714, -0.00011702299214006178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014335289543783, 0.22472031035488813, 0.5562052394000923, 0.0, 0.042430718224349184, -0.2993775663249582, -2.885124494559544, -1.0473129015067846, -2.155222804147192, -0.1816201348745458, -1.01012474190697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8233031935612874, 0.7177142448998596, 1.4528175204778178, -1.2011759013625687, -1.7179983908228533, -0.374249479327445, 0.8409652330108597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925126832685195, -0.5492244957458804, 0.018635373875526565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011476640421320383, 0.006259288801865879, 0.07308465546476407, 0.0, 0.05343203680756739, -0.027907939636021756, -0.25917730076730283, 0.03812457040667647, 0.28659635011170964, 0.13723192711448282, -0.1505514008437909, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.33695575735921823, -0.09766385451226353, -0.17217551329694306, 0.2999760093229975, -0.2015246897431223, -0.019046038410436672, 0.10660711537420353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906820749928394, 0.05054966559849752, 0.0006221068550801514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014914122512492, 0.22490281905863652, 0.5599181172915517, 0.0, 0.044685009011025914, -0.3007746371064331, -2.897763192892381, -1.0456630527405861, -2.1412454289020606, -0.1747151974114972, -1.0176787139885983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8062133777782159, 0.7127138428914443, 1.4443454795666644, -1.1858927542576552, -1.7281125254817933, -0.37536492761112034, 0.8462267964200866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8024628663707979, -0.5465312346100106, 0.018690277971370874]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011576659374156097, 0.0036501740749680742, 0.0742575578291891, 0.0, 0.04508581573353464, -0.027941415629497295, -0.25277396665674096, 0.03299697532397076, 0.2795475049026293, 0.13809874926097254, -0.15107944163256468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3417963156614319, -0.100008040168305, -0.1694408182230674, 0.30566294209827055, -0.20228269317880074, -0.022308965673506504, 0.10523126818453868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1990036620455675, 0.05386522271739528, 0.0010980819168861728]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20015498241295324, 0.22496358788852341, 0.5636906952949815, 0.0, 0.046523124895129254, -0.30217304171259973, -2.910116870810712, -1.0442383548647112, -2.127617660175425, -0.16766711338600437, -1.025262800625812, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7888816327849963, 0.7076004604520697, 1.4360093419839672, -1.170324783273599, -1.7382632426248827, -0.3766364801543263, 0.8514208330493006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8124095464110179, -0.5436605129536562, 0.018759558823811803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011682375656639517, 0.0012153765977381483, 0.0754515600685947, 0.0, 0.036762317682066795, -0.027968092123332625, -0.2470735583666168, 0.028493957517499034, 0.2725553745327172, 0.1409616805098563, -0.15168173274427474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3466348998643898, -0.10226764878749364, -0.16672275165394146, 0.31135941968112435, -0.20301434286178807, -0.02543105086411955, 0.10388073258428018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19893360080440123, 0.05741443312708689, 0.0013856170488185833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001608631206162, 0.22486724977568132, 0.5675244651508963, 0.0, 0.04804091382447449, -0.3035412422848025, -2.922052328864245, -1.043124700167149, -2.114336383673618, -0.16144541042735452, -1.0328762966158225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7713251667984461, 0.7023538524834112, 1.4278003950431948, -1.1544406355268644, -1.7484541924423087, -0.3780359169281584, 0.8565366409104427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8223535527855577, -0.5406644830067112, 0.018874481121896925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011761415325926333, -0.0019267622568418198, 0.0766753971182944, 0.0, 0.030355778586904754, -0.02736401144405591, -0.23870916107066367, 0.022273093951243095, 0.2656255300361335, 0.1244340591729968, -0.15226991980021082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35112931973100436, -0.10493215937317057, -0.16417893881545068, 0.3176829549346932, -0.20381899634852044, -0.02798873547664122, 0.1023161572228418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19888012749079415, 0.05992059893890097, 0.0022984459617024834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20016679470852397, 0.22461810660336734, 0.5714204886721297, 0.0, 0.0492515606625755, -0.3048795567549562, -2.9335321144560953, -1.0423074447214344, -2.10140738073954, -0.15596642624339424, -1.0405372644415392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7535642511419999, 0.6969653494000717, 1.4197151124779401, -1.1382226627253809, -1.7586848946400433, -0.37953926699620993, 0.8615644584658677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8322950464256667, -0.5375590699744391, 0.019029445546714298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011863175815503065, -0.0049828634462796215, 0.0779204704246687, 0.0, 0.024212936762020215, -0.026766289403073663, -0.229595711837008, 0.01634510891429119, 0.25858005868156314, 0.1095796836792056, -0.15321935651433463, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3552183131289241, -0.10777006166679028, -0.16170565130509318, 0.3243594560296713, -0.2046140439546916, -0.030067001361030556, 0.10055635110850149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1988298728021799, 0.06210826064544102, 0.003099288496347424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200172776239212, 0.2242322692592346, 0.5753793197616183, 0.0, 0.050143828812840734, -0.3061910582581071, -2.944550534505061, -1.041743376056535, -2.0888357341121013, -0.15093367718695333, -1.048277236264781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7356141941268067, 0.691432512186373, 1.4117532741877563, -1.121661763852356, -1.7689514159459603, -0.3811251082443771, 0.86649506189296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8422339086677469, -0.5343440199178914, 0.019210896739374525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001196306137608304, -0.007716746882654741, 0.07917662178977203, 0.0, 0.0178453630053046, -0.026230030063017495, -0.2203684009793198, 0.011281373297985921, 0.25143293254877075, 0.1006549811288182, -0.15479943646483557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3590011403038624, -0.11065674427397341, -0.15923676580367516, 0.3312179774604951, -0.2053304261183416, -0.031716824963344104, 0.09861206854184656, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19877724484160614, 0.06430100113095442, 0.003629023853204522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017880771966834, 0.2237276625238269, 0.5794013303291399, 0.0, 0.050699909006210096, -0.30747661967759615, -2.9551116517246165, -1.0413867886406278, -2.0766216597974223, -0.14608404137141487, -1.0561326296271798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7174848001385788, 0.6857562710597147, 1.4039161304800842, -1.10475315105645, -1.7792470152797084, -0.3827741958966008, 0.871319355442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8521699154814953, -0.5310119017509993, 0.01940522188486421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012062960912663622, -0.01009213470815384, 0.08044021135043324, 0.0, 0.011121603867387315, -0.025711228389780374, -0.21122234439110926, 0.007131748318146876, 0.2442814862935846, 0.09699271631076936, -0.1571078672479778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36258787976455753, -0.11352482253316624, -0.1567428741534436, 0.33817225591812267, -0.20591198667496285, -0.032981753044473566, 0.0964858709840395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.198720136274969, 0.06664236333784118, 0.0038865029097937334]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001848920125801, 0.22311939837896405, 0.5834870489289138, 0.0, 0.05090078540002527, -0.308735882796434, -2.9652229966883774, -1.0411980034684942, -2.064759670416598, -0.14123323192581774, -1.0641371565315465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6991809830148032, 0.679939291147258, 1.3962051220839664, -1.087493451223696, -1.7895626538601601, -0.3844693487373193, 0.8760279613648302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8621028082079024, -0.5275522348262791, 0.01960080649115936]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012168585823553865, -0.012165282897256904, 0.08171437199547749, 0.0, 0.004017527876303342, -0.025185262376756567, -0.2022268992752162, 0.0037757034426703215, 0.23723978761649236, 0.09701618891194237, -0.16009053808733326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3660763424755128, -0.1163395982491342, -0.15422016792235796, 0.34519399665507955, -0.2063127716090326, -0.03390305681437007, 0.09417211845336478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19865785452814178, 0.06919333849440365, 0.003911692125903012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001910339768254, 0.22241740746155528, 0.5876373692829787, 0.0, 0.05072825256032961, -0.3099686862518699, -2.9748947407521658, -1.0411450762759276, -2.0532395768694993, -0.13626393879654164, -1.0723170910833948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6807032804433021, 0.6739849745819401, 1.388621114169803, -1.0698788282800074, -1.7998873562412572, -0.3861952801931571, 0.8806108106665858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8720323358314703, -0.5239535080029184, 0.019788621026410307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012283928490566007, -0.014039818348175664, 0.083006407081299, 0.0, -0.0034506567939130836, -0.024656069108718866, -0.19343488127577046, 0.0010585438513315741, 0.2304018709419729, 0.09938586258552179, -0.1635986910369645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3695540514300244, -0.1190863313063596, -0.15168015828326817, 0.3522924588737728, -0.20649404762193996, -0.03451862911675506, 0.09165698603511138, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19859055247135768, 0.07197453646721513, 0.0037562907050189094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001972276229123, 0.22160015992593438, 0.5918536565550914, 0.0, 0.05023534327615232, -0.31115485912438157, -2.98399731890119, -1.0412776896283897, -2.0420522122641835, -0.1323673535576393, -1.08069297108184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6620730424338469, 0.6678791574614724, 1.3811606617335281, -1.0518815424837384, -1.8102108812872644, -0.3879171685167433, 0.8850471905233438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8819592391097035, -0.5202568933142251, 0.019987756381997294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012387292173853077, -0.016344950712418115, 0.08432574544225284, 0.0, -0.00985818568354585, -0.023723457450233045, -0.1820515629804796, -0.0026522670492431072, 0.22374729210631697, 0.07793170477804703, -0.16751759996890506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3726047601891036, -0.12211634240935253, -0.1492090487254995, 0.35994571592537883, -0.2064705009201449, -0.034437766471724654, 0.08872759713516082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853806556466372, 0.07393229377386722, 0.0039827071117397314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20020347439010194, 0.22066886640840974, 0.5961368789821828, 0.0, 0.04942137616753238, -0.3122911282120764, -2.9924717451619225, -1.0415807058060549, -2.0311924115217646, -0.12926459359144046, -1.0893046900564256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6433087343387187, 0.6616151695062485, 1.3738233634988397, -1.0334828954614335, -1.820518215348053, -0.3896034935502784, 0.8893152917455368, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918837518366295, -0.5164777926262232, 0.020196315181244682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001249353437924127, -0.018625870350492735, 0.0856644485418279, 0.0, -0.0162793421723988, -0.0227253817538959, -0.1694885252146481, -0.0060603235533009635, 0.21719601484837767, 0.06205519932397649, -0.17223437949171228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3752861619025646, -0.12527975910447817, -0.1467459646937689, 0.36797294044609824, -0.20614668121577498, -0.03372650067070167, 0.08536202444386097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984902545385202, 0.07558201376003792, 0.004171175984947794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002097713156489, 0.21963330701260128, 0.6004876430588264, 0.0, 0.04826735161790908, -0.31337521052871675, -3.0002854311434213, -1.042017856951844, -2.020651124882025, -0.12654774583476963, -1.0982068765058308, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6244231401634923, 0.6551909860127477, 1.3666107181270413, -1.014669781954262, -1.830789814952071, -0.3912255494765068, 0.8933920015145673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9018058862955415, -0.5126188329621287, 0.020406874864572447]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001259385109389794, -0.020711187916169344, 0.08701528153287227, 0.0, -0.023080490992466042, -0.021681646332807118, -0.1562737196299728, -0.008743022915782392, 0.21082573279478972, 0.054336955133416694, -0.17804372898810442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37771188350452867, -0.12848366987001567, -0.14425290743596728, 0.3762622701434281, -0.2054319920803594, -0.032441118524568074, 0.08153419538060984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19844268917823923, 0.07717919328188974, 0.004211193666555281]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021612092282184, 0.21850629281013784, 0.6049063830180879, 0.0, 0.04674694556987107, -0.3144054031470295, -3.0074185370116227, -1.0425507553929605, -2.010411408134718, -0.12394384477934386, -1.1074574531963899, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6054236679376318, 0.6486078022609617, 1.3595250401006225, -0.9954321389298569, -1.8410018235275876, -0.3927577856739413, 0.897252692534199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9117255410177183, -0.5086754720012359, 0.020610626904816205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001269921434586169, -0.022540284049268652, 0.08837479918522834, 0.0, -0.030408120960760072, -0.02060385236625595, -0.1426621173640283, -0.01065796882233028, 0.20479433494613986, 0.052078021108515345, -0.18501153381118132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37998944451720995, -0.1316636750357197, -0.1417135605283744, 0.38475286048810226, -0.20424017151033333, -0.030644723948690555, 0.07721382039263426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19839309444353564, 0.07886721921785816, 0.004075040804875125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022253027785625, 0.2172997061063792, 0.6093940275144712, 0.0, 0.044831410138811985, -0.31538213075779564, -3.0138605032598287, -1.0431464819052012, -2.0004478758145035, -0.12130496351048073, -1.1171087473807155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5863125474238096, 0.6418689300364602, 1.3525686390384142, -0.975760852223192, -1.8511263198677277, -0.3941779859496728, 0.9008708398699348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9216425579681401, -0.5046390286167527, 0.020799215252272733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012818710068790215, -0.024131734075172735, 0.08975288992766754, 0.0, -0.03831070862118175, -0.01953455221532188, -0.12883932496411699, -0.011914530244816071, 0.19927064640429257, 0.05277762537726262, -0.1930258836865146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38222241027644466, -0.13477744449003068, -0.13912802124416684, 0.39342573413329984, -0.20248992680280403, -0.02840400551462917, 0.07236294671471433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19834033900843503, 0.08072886768966328, 0.0037717669491305742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022900860672177, 0.21602149077378158, 0.6139508566643666, 0.0, 0.04249304529260065, -0.3163082802897171, -3.019609641149978, -1.0437794882828788, -1.9907280811770776, -0.11855834742913957, -1.127203397503628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56708689339683, 0.6349787981933329, 1.3457432785905576, -0.9556459545254953, -1.8611315315344155, -0.39546708486206655, 0.9042174428273831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9315567687691604, -0.5004987690426352, 0.020966024033625068]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012956657731027664, -0.02556430665195258, 0.09113658299790565, 0.0, -0.04676729692422672, -0.01852299063842921, -0.11498275780298244, -0.012660127553552256, 0.1943958927485175, 0.054932321626823176, -0.20189300245824846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38451308053959093, -0.13780263686254624, -0.136507208957131, 0.4022979539539349, -0.20010423333375432, -0.02578197824787499, 0.06693205914896853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982842160204063, 0.08280519148234991, 0.003336175627046675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20023567613729168, 0.21468232598148812, 0.618579669380404, 0.0, 0.039716685832498946, -0.3170317589450412, -3.0246594038591277, -1.0443415770723183, -1.9812217011084206, -0.11567135386636834, -1.13777905015814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477513703633965, 0.6279428756470102, 1.3390496574407549, -0.9350758302929199, -1.8709811549442146, -0.39660843413451846, 0.9072602766909373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9414681136338643, -0.49624739219259395, 0.02109857982582755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013335061139804465, -0.02678329584586907, 0.09257625432074831, 0.0, -0.05552718920203407, -0.014469573106482808, -0.1009952541829951, -0.011241775788790789, 0.19012760137314005, 0.05773987125542451, -0.21151305309023985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3867104606686719, -0.14071845092645366, -0.13387242299605406, 0.4114024846515084, -0.1969924681959818, -0.022826985449038478, 0.06085667727108461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982268972940784, 0.08502753700082558, 0.0026511158440496816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024248448796664, 0.2132817010339462, 0.6232850539165122, 0.0, 0.03648736491123274, -0.3176151113242534, -3.029022659188296, -1.0448138848933215, -1.9718877847713319, -0.11262628356749618, -1.1488617258468545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.52829997285123, 0.6207655905849384, 1.332488202871619, -0.914035823072634, -1.8806351577949825, -0.39758655139198784, 0.909962810616463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.951376543075006, -0.49187641030852547, 0.02119267081108958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013616701349902424, -0.028012498950838564, 0.0941076907221639, 0.0, -0.06458641842532403, -0.011667047584244146, -0.08726510658336331, -0.009446156420062756, 0.1866783267417718, 0.060901405977443104, -0.2216535137742917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3890279502433304, -0.1435457012414359, -0.1312290913827172, 0.42080014440571706, -0.19308005701535966, -0.01956234514938717, 0.054050678510513796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19816858882283422, 0.08741963768137005, 0.0018818197052405962]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024942643988033, 0.21179744237757436, 0.6280614356300516, 0.0, 0.032837414321974116, -0.31812578977269435, -3.0326111904443955, -1.0452508930410527, -1.9626876112700173, -0.11087403638981642, -1.1604767590735159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5087462976732324, 0.6134391523867183, 1.3260590187239967, -0.8924938010822095, -1.8900486175493625, -0.3983666197484187, 0.9122756140155615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9612828171656946, -0.48741756737242403, 0.021263334940033223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001388390382738015, -0.029685173127436876, 0.09552763427078588, 0.0, -0.07299901178517247, -0.010213568968818868, -0.07177062512199014, -0.008740162954621399, 0.18400347002629233, 0.035044943553595116, -0.23230066453322595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.391073503559951, -0.14652876396440218, -0.1285836829524449, 0.430840439808488, -0.1882691950876016, -0.015601367128617337, 0.04625606798196829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1981254818137743, 0.0891768587220289, 0.0014132825788728686]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025648617165462, 0.2102159997234052, 0.6329105085744566, 0.0, 0.02877294974059154, -0.31860398466958934, -3.0353794732601376, -1.0456722544572943, -1.9535790164030598, -0.10975106669980453, -1.1726841966576451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48909731099497733, 0.6059579119762081, 1.3197643797852852, -0.8704192973769448, -1.8991693651637631, -0.39891412960312955, 0.9141417636527343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711873739518471, -0.4828893418700921, 0.0213193368087825]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001411946354858873, -0.03162885308338303, 0.09698145888810075, 0.0, -0.08128929162765157, -0.009563897937899444, -0.05536565631484504, -0.008427228324830742, 0.18217189733915135, 0.022459393800237974, -0.24414875168258673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39297973356510235, -0.1496248082102037, -0.12589277877422897, 0.44149007410529506, -0.1824149522880104, -0.01095019709421708, 0.03732299274345578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19809113572304787, 0.0905645100466391, 0.0011200373749855554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20026365067228066, 0.20853153423470647, 0.6378348053398177, 0.0, 0.024287414359991967, -0.31906383544072553, -3.03730358821359, -1.0460803808476857, -1.944506846300838, -0.10880336925481057, -1.1855679286607015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46935386567918885, 0.5983182674664688, 1.3136084475674703, -0.8477824018146772, -1.9079370164244762, -0.3991966785218747, 0.9154962070713135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9810904491676253, -0.47830120746567945, 0.021365983100818976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014329001252086628, -0.0336893097739748, 0.09848593530722288, 0.0, -0.08971070761199146, -0.009197015422723371, -0.03848229906904507, -0.008162527807830557, 0.18144340204443837, 0.018953948899879114, -0.2576746400611291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39486890631576926, -0.1527928901947863, -0.12311864435629659, 0.4527379112453502, -0.17535302521426147, -0.005650978374902695, 0.02708886837158525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19806150431556513, 0.09176268808825254, 0.0009329258407294982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002709181633583, 0.2067445984866543, 0.6432883074780156, 0.0, 0.019368020415770022, -0.319506030596099, -3.0383767612417256, -1.0464716606443134, -1.93539817392384, -0.10785793321986444, -1.1992183447754208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.449511737566043, 0.5905186190172917, 1.30759712755751, -0.8245528155742337, -1.9162819395303767, -0.39918565990323196, 0.9162647015301013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9909921334418351, -0.4736560022976525, 0.021405717349798476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014534982155259296, -0.035738714961043055, 0.1090700427639566, 0.0, -0.0983878788844389, -0.008843903107469055, -0.021463460562710514, -0.007825595932554615, 0.1821734475399597, 0.018908720698922653, -0.2730083222943843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39684256226291714, -0.15599296898354148, -0.1202264001992059, 0.46459172480887045, -0.1668984621180081, 0.0002203723728545822, 0.015369889175756525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19803368548419537, 0.09290410336053989, 0.000794684979589968]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20027829438051795, 0.20485868510348465, 0.6490013560727583, 0.0, 0.014002434650858962, -0.31992610835046786, -3.0386077281967667, -1.0468412358708508, -1.9261612032181843, -0.10686461645591573, -1.2137239690189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295630481332781, 0.5825587072681266, 1.3017382359732208, -0.8006983855868464, -1.9241240546061331, -0.39885668361580096, 0.9163618604901093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0008924345494923, -0.4689530184259971, 0.02143932756822293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001475243431933699, -0.037718267663393076, 0.11426097189485505, 0.0, -0.10731171529822119, -0.008401555087377478, -0.0046193391008222465, -0.007391504530747066, 0.18473941411311273, 0.01986633527897399, -0.2901124848695834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39897378865529753, -0.15919823498330188, -0.11717783168578469, 0.4770885997477463, -0.15684230151512948, 0.006579525748620504, 0.0019431792001582751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980060221531453, 0.09405967743310696, 0.0006722043684891009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028578925979554, 0.20287743274338085, 0.6547406686796089, 0.0, 0.008185018820865536, -0.32031794640898287, -3.0380197116706626, -1.0471838245626715, -1.9166848868198592, -0.10581108299932915, -1.2291713152384198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.409497880984442, 0.5744384300934184, 1.2960420336682963, -0.7761829962429637, -1.9313712603623479, -0.39818884409194577, 0.9156880981674309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0107913532621287, -0.46419123734401335, 0.021467110255929775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014989758555187285, -0.03962504720207571, 0.11478625213701081, 0.0, -0.11634831659986852, -0.007836761170300528, 0.011760330522081603, -0.0068517738364139965, 0.18952632796650123, 0.02107066913173159, -0.30894692439039756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4013033429767219, -0.16240554349416467, -0.11392404609848922, 0.49030778687765375, -0.1449441151242955, 0.013356790477103832, -0.01347524645356626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19797837425272766, 0.09523562163967537, 0.0005556537541368603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20029341668299114, 0.20080310284452807, 0.6604121090446456, 0.0, 0.001921849586408484, -0.3206748265522026, -3.036649950845352, -1.0474931959378289, -1.9068372060650318, -0.10469342341170036, -1.2456491252742798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38930633750726457, 0.5661566921582276, 1.2905223641067847, -0.750964653980663, -1.9379170515353874, -0.3971633693842987, 0.9141253637504341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0206889396240197, -0.45937220777499244, 0.021489539567299338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015254846391213545, -0.04148659797705568, 0.11342880730073404, 0.0, -0.12526338468914103, -0.007137602864394741, 0.027395216506216978, -0.006187427503146391, 0.1969536150965476, 0.022353191752575823, -0.32955620071719854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.403830869543549, -0.16563475870381658, -0.11039339123023295, 0.5043668452460132, -0.13091582346079012, 0.020509494152941406, -0.03125468833993677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979517272378216, 0.09638059138041875, 0.00044858622739128284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030119568854826, 0.19863638606599057, 0.6660139722038477, 0.0, -0.0047654859416252715, -0.32098958444084497, -3.034549899605448, -1.047761372718335, -1.8964610837443059, -0.10350850752967147, -1.2632545889497222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3689808614367368, 0.5577104480698207, 1.2851985271167368, -0.7249939125996567, -1.9436369605967867, -0.39576205076792975, 0.9115313297721367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305853548399064, -0.45450238080270544, 0.021507407707782908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015558011114232356, -0.04333433557074981, 0.1120372631840425, 0.0, -0.1337467105606751, -0.006295157772847987, 0.04200102479807478, -0.005363535610125525, 0.207522446414517, 0.023698317640577764, -0.3521092735088453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40650952141055535, -0.16892488176813872, -0.10647673980095607, 0.5194148276201257, -0.11439818122798806, 0.028026372327378497, -0.05188067956594836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792830431773525, 0.09739653944573959, 0.0003573628096714333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030914634140978, 0.19637390500117713, 0.6715828451201916, 0.0, -0.011823845857501004, -0.32125109674842384, -3.0317232352621573, -1.047993758889174, -1.8853759253989026, -0.10350850752923797, -1.282109695006647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34853531759768974, 0.5490903893140774, 1.2800996783217704, -0.6982100150772024, -1.9483808813828611, -0.3939543090524812, 0.9077272656514751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0404812611623253, -0.44961272326613566, 0.021525033954934155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001590130572305638, -0.045249621296268805, 0.11137745832687744, 0.0, -0.14116719831751465, -0.005230246151577747, 0.056533286865820584, -0.004647723416777062, 0.22170316690806577, 8.670054257864379e-12, -0.37710212113849784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4089108767809417, -0.17240117511486672, -0.10197697589932689, 0.535677950449087, -0.09487841572149006, 0.036154834308971096, -0.07608128241323243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19791812644837758, 0.09779315073139577, 0.00035252494302495706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003172693409572, 0.1940175527107981, 0.6771603689056768, 0.0, -0.019193679667741763, -0.321440476638921, -3.028179268613157, -1.0481732072969074, -1.8733471366727263, -0.10350850752836022, -1.3024202699248018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3279913270141919, 0.5402847239915176, 1.2752683565321803, -0.670544663390444, -1.9519661143688292, -0.39170631156022995, 0.9024892898828979, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0503774344917505, -0.4447394511672975, 0.021544256271463894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016245999094805286, -0.047127045807580724, 0.11155047570970374, 0.0, -0.1473966762048152, -0.0037875978099430434, 0.07087933298000587, -0.003588968154669996, 0.24057577452352463, 1.7555029717154477e-11, -0.40621149836309306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4108798116699565, -0.17611330645119624, -0.09662643579180089, 0.5533070337351663, -0.07170465971936085, 0.04495994984502532, -0.10475951537154438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792346658850413, 0.09746544197676281, 0.000384446330594774]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032562408611035, 0.19157898268789894, 0.6827789936632113, 0.0, -0.02680877064690194, -0.32154935222513786, -3.0239496911498267, -1.048269333871253, -1.8600634801830365, -0.10350850752892245, -1.3244520270897273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3073749799692585, 0.5312801892863821, 1.2707653820007925, -0.641920890359514, -1.9541671935741474, -0.38898616714406864, 0.8955337475218497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0602746926488202, -0.43992003567794874, 0.02156267750140531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016709490306319699, -0.04877140045798318, 0.11237249515069075, 0.0, -0.15230181958320357, -0.002177511724336902, 0.0845915492666035, -0.0019225314869087012, 0.2656731297937968, -1.1244587338957728e-11, -0.440635143298511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41232694089866834, -0.18009069410271097, -0.09005949062775538, 0.5724754606185991, -0.04402158410636586, 0.05440288832322622, -0.13911084722096373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979451631413971, 0.09638830978697575, 0.0003684245988282738]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003343827899983, 0.18908234189505516, 0.6884591475134899, 0.0, -0.03458886264762535, -0.32156845280526186, -3.019089507224257, -1.0482170064255085, -1.8451117116401439, -0.10350850752801133, -1.348545726744807, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.28671800434849704, 0.5220618657484017, 1.2666775150992649, -0.6122492040576393, -1.9547005956772974, -0.38576786993113416, 0.886494070350839, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0701739237493035, -0.4351940617873942, 0.02157207271245176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017517407775899616, -0.04993281585687589, 0.11360307700557186, 0.0, -0.15560184001446814, -0.0003820116024801435, 0.09720367851139555, 0.0010465489148875277, 0.29903537085785037, 1.8222420301728088e-11, -0.48187399310159584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4131395124152298, -0.18436647075960821, -0.08175733803055242, 0.5934337260374951, -0.010668042062998706, 0.06436594425868974, -0.18079354342021137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19798462200966607, 0.09451947781108981, 0.00018790422092902821]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003437113012565, 0.1865590655037719, 0.6942110743842566, 0.0, -0.042433366863801565, -0.32148710723549906, -3.013687044176947, -1.0479506258393319, -1.8279278250508226, -0.10350850752730906, -1.3751539477281702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26605257839378216, 0.5126101957533383, 1.263130067889564, -0.5814169572975708, -1.953201116026987, -0.38203307191891245, 0.8748821920655593, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0800761664844183, -0.43060595297904586, 0.021563618093416753]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018657022516393627, -0.05046552782566498, 0.11503853741533392, 0.0, -0.15689008432352433, 0.0016269113952556665, 0.10804926094620285, 0.00532761172353181, 0.34367773178642597, 1.4045463697372213e-11, -0.5321644196672647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41330851909429756, -0.1890333999012687, -0.07094894419401514, 0.6166449352013684, 0.02998959300620538, 0.07469596024443391, -0.23223756570559562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19804485470229513, 0.09176217616696702, -0.00016909238070013938]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20035384746092152, 0.18404512675042728, 0.7000380490622289, 0.0, -0.050212851054079896, -0.32129764731835564, -3.007872020375405, -1.047408573474381, -1.807714696520507, -0.1035085075265131, -1.4049158957652377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24540734864367067, 0.5028965248793075, 1.260308356335637, -0.5492699698748068, -1.949181545315102, -0.3777738292535714, 0.8600228144996451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899826588460824, -0.42620844655981927, 0.021530459334271956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020272319330068492, -0.050278775066892704, 0.11653949355944743, 0.0, -0.1555896838055666, 0.003789198342868636, 0.11630047603084057, 0.01084104729901766, 0.4042625706063127, 1.5919110619624917e-11, -0.5952389607413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41290459500222965, -0.19427341748061752, -0.0564342310785417, 0.6429397484552792, 0.08039141423770374, 0.08518485330682168, -0.2971875513182835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19812984723328245, 0.08795012838453235, -0.0006631751828959446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036843163460358, 0.18136281953048786, 0.7059390781648229, 0.0, -0.057767388905325394, -0.3210710738639323, -3.0019894450633307, -1.0466631557182662, -1.7833826261393904, -0.10350850752649103, -1.4386498684378064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22607875701511615, 0.49392618538752037, 1.2587569083891101, -0.5184133404197366, -1.941897647938553, -0.3738639731587597, 0.8417880744913834, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0998962708048692, -0.4221692529637803, 0.021686362584224045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002916834736410404, -0.053646144398788474, 0.1180205820518809, 0.0, -0.1510907570249099, 0.0045314690884670624, 0.1176515062414791, 0.014908355122296033, 0.4866414076223328, 4.4136456503999646e-13, -0.6746794534513738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3865718325710906, -0.17940678983574165, -0.03102895893053481, 0.6171325891014039, 0.1456779475309793, 0.07819712189623458, -0.36469480016523564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19827223917573664, 0.08078387192078006, 0.0031180649990417805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003942537113021, 0.17828529615059197, 0.7119086970749711, 0.0, -0.06481104577349599, -0.32095649077276867, -2.9965751754981027, -1.0458472146225162, -1.753576222358894, -0.10350850752557518, -1.476720268237994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21045717232158523, 0.4874910167006223, 1.2591597974561297, -0.492597068932329, -1.930827428581285, -0.371992393713558, 0.821011277691062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1098211641847406, -0.4187433454099081, 0.02231639502794631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000516441533970284, -0.061550467597917866, 0.11939237820296275, 0.0, -0.14087313736341175, 0.0022916618232726514, 0.10828539130455896, 0.016318821914997908, 0.5961280756099278, 1.8317036250482457e-11, -0.7614079960037541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.31243169387061864, -0.12870337373796226, 0.008057781340389522, 0.5163254297481521, 0.22140438714536217, 0.03743158890403379, -0.4155359360064289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984978675974289, 0.06851815107744402, 0.012600648874445338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004388397255267, 0.17485617009380533, 0.7179373658089209, 0.0, -0.0708799625458358, -0.32108736955233547, -2.9921991868446067, -1.0449728458633074, -1.7183656050601326, -0.103508507551078, -1.5186732699592207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20058607313259408, 0.48488016496026076, 1.261770084558291, -0.47557115538422545, -1.9164565911539984, -0.3734251779064008, 0.7994134183993886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1197616468296943, -0.41613950387568394, 0.023478168149860274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008917202844920643, -0.06858252113573299, 0.12057337467899516, 0.0, -0.12137833544679619, -0.002617575591335923, 0.08751977306991583, 0.01748737518417392, 0.70421234597523, -5.100565746783541e-10, -0.8390600344245331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19742198377982317, -0.052217034807230445, 0.052205742043229766, 0.34051827096207177, 0.2874167485457316, -0.028655683856854998, -0.43195718583346787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19880965289907265, 0.0520768306844828, 0.023235462438279234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005152505839828, 0.1713391455780551, 0.7240261343656306, 0.0, -0.0757735884958979, -0.3213355926797959, -2.9889814816028712, -1.0440263392981617, -1.6783008240333939, -0.10350850760301146, -1.5640162619985774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19755116875234574, 0.48665761041572353, 1.2661729829388388, -0.4710855997270218, -1.9005937735528882, -0.3787027586782937, 0.7798707452587533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.129720437439687, -0.4144030404743032, 0.02505428898970948]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015282171691219392, -0.07034049031500482, 0.12177537113419343, 0.0, -0.09787251900124191, -0.004964462549208628, 0.0643541048347083, 0.018930131302915862, 0.8012956205347723, -1.0386692511734449e-09, -0.9068598407871321, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06069808760496673, 0.03554890910925572, 0.08805796761095572, 0.08971111314407304, 0.31725635202220503, -0.10555161543785882, -0.3908534628127065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917581219985286, 0.034729268027614696, 0.03152241679698409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20065601839622627, 0.16807247951426837, 0.7301320595769725, 0.0, -0.07969648408535791, -0.32176962153628585, -2.986607289663825, -1.0431390960024967, -1.6342489992114075, -0.10350850760306361, -1.6122408329025861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20067328395522496, 0.492400892843251, 1.2716015314676967, -0.47859763667929617, -1.8855827822470475, -0.3876223444709693, 0.7649963838140723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1396650036073466, -0.41338405076823215, 0.026870077922475817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0028153562448687964, -0.06533332127573466, 0.12211850422683904, 0.0, -0.07845791178920039, -0.008680577129799173, 0.04748383878092355, 0.017744865913298997, 0.881036496439728, -1.042922814899149e-12, -0.9644914180801775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062442304057584455, 0.11486564855054912, 0.10857097057715762, -0.1502407390454879, 0.30021982611681386, -0.1783917158535125, -0.29748722889361945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19889132335319332, 0.02037979412142081, 0.036315778655326744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20096542306793036, 0.1654449932387038, 0.7362508424313801, 0.0, -0.08304710453424663, -0.32573663391034274, -2.9837188757965825, -1.0443762733868391, -1.5870075393538325, -0.10521373332923009, -1.662240832902595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2086725093691195, 0.5012186466235822, 1.2773543946865247, -0.496107667472857, -1.874211870670797, -0.3994081790168006, 0.7573401079606881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1494812901559333, -0.4128914605340995, 0.02866861537375455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006188093434081931, -0.0525497255112915, 0.1223756570881518, 0.0, -0.06701240897777443, -0.07934024748113738, 0.05776827734485358, -0.024743547686851254, 0.9448291971514986, -0.034104514523329695, -1.0000000000001805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998450827789035, 0.17635507560662322, 0.1150572643765603, -0.35020061587121726, 0.22741823152500568, -0.2357166909166251, -0.15312551706768568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1963257309717322, 0.009851804682653769, 0.03597074902557463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20152838728931086, 0.16369481209325562, 0.7423906816198869, 0.0, -0.08691864583703286, -0.3314701379428469, -2.9768146445403336, -1.0486542064114133, -1.5393105615783342, -0.11197817370281932, -1.712240832902578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22038123413262947, 0.5120842470988328, 1.282798670935164, -0.5219493598008356, -1.870009977014743, -0.4126385789809851, 0.7601173661938881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158737285299586, -0.41276466205298745, 0.030274916064017]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011259284427610077, -0.035003622908963465, 0.12279678377013534, 0.0, -0.07743082605572461, -0.11467008065008287, 0.13808462512497643, -0.08555866049148067, 0.9539395555099669, -0.13528880747178448, -0.999999999999657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2341744952701998, 0.21731200950501292, 0.1088855249727857, -0.5168338465595709, 0.08403787312108424, -0.2646079992836903, 0.05554516466400122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18511990287305707, 0.0025359696222403425, 0.03212601380524895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20202627967430978, 0.16284106308747984, 0.7485249734313544, 0.0, -0.09344210826657097, -0.33808688780499263, -2.962144595895054, -1.0563212869545757, -1.4949080658849068, -0.1275518286405913, -1.7622408329025676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2350154259370006, 0.5242289585463547, 1.287687448692728, -0.5546227136632432, -1.873673089113286, -0.42613294628406545, 0.7728950815705997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1674067985535097, -0.41296480272338026, 0.031647632194646884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009957847699978529, -0.017074980115515438, 0.12268583622935114, 0.0, -0.1304692485907622, -0.1323349972429145, 0.29340097290509703, -0.15334161086325052, 0.8880499138684388, -0.31147309875544, -0.9999999999997944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.29268383608742216, 0.24289422895043714, 0.09777555515128335, -0.6534670772481537, -0.0732622419708612, -0.2698873460616072, 0.25555430753423225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17339026507847224, -0.004002813407856775, 0.027454322612597743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.202398800107997, 0.16280683147053426, 0.7545672663418745, 0.0, -0.10236052291981554, -0.34514526068085766, -2.938669555357371, -1.066806922522258, -1.4566519388420978, -0.15099873731396388, -1.8122408329025614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2521359232549917, 0.5371313790297202, 1.2922238548942178, -0.5927613967532037, -1.8839800229080845, -0.4391346299700987, 0.794086424033654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1756525480679787, -0.413549951262761, 0.03278605831622804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007450408673744192, -0.0006846323389115214, 0.12084585821040356, 0.0, -0.17836829306489152, -0.141167457517301, 0.4695008107536621, -0.2097127113536453, 0.7651225408561788, -0.4689381734674513, -0.9999999999998763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3424099463598216, 0.2580484096673115, 0.090728124029795, -0.76277366179921, -0.20613867589596885, -0.26003367372066566, 0.42382684926108727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16491499028938097, -0.01170297078761519, 0.022768522431623063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2027163628310531, 0.163548418785463, 0.7604249409633889, 0.0, -0.1129019331978828, -0.34889525657054227, -2.9078895229271913, -1.0783023625548778, -1.4236392592615992, -0.1812568968502859, -1.862240832902567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27156293012603155, 0.5504404420941427, 1.2967143864739177, -0.6352723432251367, -1.8997476245278966, -0.4511342511228243, 0.8224317087991058, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.18355943573368, -0.4145957872726459, 0.03365033610337059]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006351254461121899, 0.014831746298575024, 0.11715349243028593, 0.0, -0.21082820556134538, -0.07499991779359372, 0.6156006486035991, -0.2299088006523955, 0.6602535916099723, -0.6051631907264403, -1.000000000000111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3885401374207975, 0.26618126128844893, 0.08981063159399902, -0.85021892943866, -0.31535203239624304, -0.23999242305451118, 0.5669056953090346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15813775331402652, -0.020916720197697428, 0.01728555574285116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20300062721202383, 0.16503843169782795, 0.7660373673432823, 0.0, -0.12443766154595379, -0.35264525165413685, -2.8712654969834506, -1.0900256812328397, -1.3939445447531358, -0.217290875746959, -1.9122408329024576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29321619565331164, 0.563902471783936, 1.3017963568395874, -0.6812811004027302, -1.920152501583522, -0.46209018873095564, 0.856740237231522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1912604617573923, -0.41613681364612143, 0.0342114464647145]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005685287619414848, 0.029800258247298695, 0.11224852759786824, 0.0, -0.23071456696141968, -0.07499990167189127, 0.7324805188748166, -0.23446637355923902, 0.5938942901692699, -0.7206795779334619, -0.9999999999978096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4330653105456018, 0.2692405937958666, 0.10163940731339415, -0.92017514355187, -0.4080975411125062, -0.21911875216262716, 0.6861705686483266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1540205204742444, -0.030820527469511003, 0.01122220722687825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20327350143028525, 0.16728785758489248, 0.7713944842449668, 0.0, -0.1366453821212773, -0.35264524971890543, -2.829966276228405, -1.1011813700863278, -1.3659979985495936, -0.25811805886428807, -1.9622408329024688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.317005942110701, 0.5772663034002397, 1.3082663081475974, -0.7300881061447986, -1.9449740073709518, -0.4723040399021917, 0.8960526609708361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1988628223791276, -0.4181387944267183, 0.034438861496440466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005457484365228559, 0.04498851774129044, 0.10714233803369108, 0.0, -0.24415441150647035, 3.8704628849139944e-08, 0.8259844151009157, -0.2231137770697607, 0.5589309240708441, -0.8165436623465813, -1.000000000000223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47579492914778665, 0.26727663232607307, 0.12939902616019983, -0.976140114841369, -0.49643011574859736, -0.2042770234247212, 0.786248474786281, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1520472124347034, -0.040039615611937036, 0.004548300634519246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354427407946665, 0.17029590589764237, 0.7765242390469841, 0.0, -0.14957609567993307, -0.3526452497225634, -2.784926899624365, -1.111502092915575, -1.3387330147559335, -0.30277980535815, -2.012240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3425978958829109, 0.59021135720085, 1.3168912697811177, -0.7800881312000915, -1.9743114642801527, -0.4823756353417002, 0.939502599962036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2064712450597492, -0.42048907395168095, 0.0343385347184016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005415452983628351, 0.06016096625499762, 0.10259509604034556, 0.0, -0.25861427117311553, -7.315934072253455e-11, 0.900787532080797, -0.20641445658494453, 0.5452996758732007, -0.8932349298772394, -0.9999999999999883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5118390754441977, 0.258901076012207, 0.17249923267040806, -1.0000005011058573, -0.5867491381840184, -0.20143190879016956, 0.8689987798239975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15216845361243223, -0.047005590499253035, -0.0020065355607773996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20380902679416726, 0.1740250608263596, 0.7814815414939414, 0.0, -0.16345409175240433, -0.35264524972256756, -2.7368953983411313, -1.1210488685706324, -1.3114909002989157, -0.3505092025532365, -2.062240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3694491359183932, 0.6024375144364038, 1.3280363297310942, -0.8300881562554033, -2.008190975646627, -0.49297056126018424, 0.9862625511421699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2141691199585547, -0.4230301045584226, 0.033953799488170976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005295054294012406, 0.07458309857434448, 0.09914604893914625, 0.0, -0.277559921449425, -8.306185477170416e-14, 0.960630025664667, -0.19093551310114656, 0.544842289140358, -0.954587943901729, -0.9999999999999948, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5370248007096454, 0.2445231447110752, 0.22290119899952948, -1.0000005011062378, -0.6775902273294845, -0.2118985183696804, 0.9351990236026778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15395749797610853, -0.05082061213483312, -0.007694704604612444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20405302516662302, 0.17839110823571697, 0.7863344254845989, 0.0, -0.17851430003789928, -0.35264524972255495, -2.686895373285901, -1.1300227185258729, -1.2838256251509144, -0.40050922760850854, -2.112240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3969237492142522, 0.613741097894437, 1.3415486574536832, -0.8800881813106121, -2.0459772709518442, -0.504647076992953, 1.0355802259860223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2220102602948362, -0.4255933560538981, 0.03335268787598558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004879967449115027, 0.0873209481871476, 0.09705767981314739, 0.0, -0.30120416570989883, 2.525265043987572e-13, 1.000000501104607, -0.17947699910481119, 0.5533055029600262, -1.0000005011054416, -0.9999999999999959, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5494922659171806, 0.22607166916066412, 0.2702465544517814, -1.0000005011041742, -0.7557259061043429, -0.23353031465537516, 0.9863534968770462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15682280672562757, -0.05126502990950946, -0.012022232243707826]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20427427775571064, 0.1832657630480131, 0.7911560606975594, 0.0, -0.19402046241882806, -0.3526452497225476, -2.6369255548772657, -1.1381357395602882, -1.2541818029209706, -0.4505092526637864, -2.1622408329024654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4241780894055525, 0.6240109137311005, 1.3565984597849061, -0.9300882063658712, -2.086394358193773, -0.5175612797107543, 1.085580225986022, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2299439964350036, -0.4280393053467843, 0.03261250819647751]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004425051781752245, 0.09749309624592228, 0.09643270425921166, 0.0, -0.3101232476185755, 1.46698788079243e-13, 0.9993963681727096, -0.16226042068830895, 0.5928764445988757, -1.0000005011055564, -0.9999999999999505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5450868038260062, 0.2053963167332707, 0.3009960466244557, -1.0000005011051827, -0.8083417448385756, -0.2582840543560268, 0.9999999999999947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15867472280334796, -0.04891898585772456, -0.014803593590161389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20448925460959733, 0.1884861482941713, 0.7960013837556438, 0.0, -0.20812797112921447, -0.3526452497225536, -2.590735943115225, -1.1442111287049983, -1.2195158208931738, -0.5005092777190392, -2.2122408329024843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4501567220181025, 0.6334540335899963, 1.3712930643842167, -0.9782469378031894, -2.1265963620534154, -0.531072591019149, 1.1355802259860202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2377756105301416, -0.43028076956376143, 0.03180917214483589]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004299537077733934, 0.10440770492316372, 0.09690646116168819, 0.0, -0.28215017420772837, -1.204229784694197e-13, 0.923792235240814, -0.12150778289419997, 0.6933196405559353, -1.0000005011050557, -1.000000000000377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5195726522509989, 0.1888623971779163, 0.29389209198621125, -0.9631746287463633, -0.8040400771928422, -0.2702262261678953, 0.9999999999999597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1566322819027592, -0.04482928433954309, -0.016066721032832413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2047468885177489, 0.19387014210656023, 0.8008866381240283, 0.0, -0.21961803998109392, -0.3521226426517718, -2.5514919148248616, -1.1465010588890092, -1.1798068664050003, -0.5505093027742914, -2.262240832902491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4737450900696767, 0.642079354452608, 1.3843459861892113, -1.0220309843042243, -2.1630376093293977, -0.5443202336407252, 1.1818302260191775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2452004234030019, -0.4322623985728623, 0.031009374273467866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005152678163031458, 0.10767987624777886, 0.09770508736768965, 0.0, -0.2298013770375888, 0.010452141415636393, 0.784880565807272, -0.04579860368021922, 0.794179089763471, -1.0000005011050457, -1.0000000000001337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47176736103148464, 0.17250641725223376, 0.2610584360998941, -0.8756809300207011, -0.7288249455196422, -0.2649528524315232, 0.9250000006631481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14849625745720518, -0.03963258018201765, -0.015995957427360454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2051287495455325, 0.19923065914216656, 0.8057737414679297, 0.0, -0.2281785742138778, -0.35022616837644915, -2.519391471608246, -1.1433405956760947, -1.136039702814632, -0.6005093278295216, -2.3122408329025026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4940033565817461, 0.6497248585809339, 1.3951808982628564, -1.059285479802085, -2.192812112797505, -0.5564281233814546, 1.2207959277732934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2519001603691544, -0.4339526108995303, 0.030265197010617452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007637220555672521, 0.10721034071212654, 0.09774206687802872, 0.0, -0.1712106846556775, 0.03792948550645252, 0.6420088643323169, 0.06320926425829188, 0.8753432718073637, -1.0000005011046043, -1.0000000000002376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4051653302413882, 0.15291008256651703, 0.21669824147290176, -0.7450899099572149, -0.5954900693621484, -0.24215779481458866, 0.7793140350823167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13399473932305103, -0.03380424653335981, -0.014883545257008256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20576022076715375, 0.2043888656870428, 0.8105783890627817, 0.0, -0.2337123229928388, -0.3464879381815168, -2.4940922874295155, -1.1337999009427524, -1.0890259719424475, -0.650509352884751, -2.362240832902516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510514236160238, 0.6564071831994994, 1.403620965527082, -1.0890059379932011, -2.214526068245795, -0.5667107378922177, 1.2507736607049844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2576710963515167, -0.4353477493425074, 0.029610162330812134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012629424432424752, 0.10316413089752449, 0.09609295189704037, 0.0, -0.11067497557922014, 0.07476460389864714, 0.5059836835746102, 0.19081389466684653, 0.9402746174436897, -1.0000005011045867, -1.0000000000002702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33021759156983965, 0.133646492371311, 0.16880134528450907, -0.5944091638223233, -0.43427910896580035, -0.20565229021526063, 0.5995546586338187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11541871964724648, -0.027902768859541856, -0.013100693596106397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064101730111816, 0.20918969614030278, 0.8151985088088208, 0.0, -0.23619468757488218, -0.34091006903492105, -2.475337384198103, -1.1177464421455081, -1.0394149872447274, -0.7005093779400104, -2.412240832902519, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.523403301297924, 0.6622822239167705, 1.4098182069669167, -1.1113813433797564, -2.2283755764191837, -0.5748417513451253, 1.2719013258029221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2624608795377155, -0.43646862893810046, 0.029057378771169932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880557524, 0.09601660906519982, 0.09240239492078313, 0.0, -0.04964729164086727, 0.11155738293191456, 0.375098064628254, 0.3210691759448877, 0.9922196939544017, -1.0000005011051882, -1.0000000000000613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2577813027537198, 0.11750081434542253, 0.1239448287966965, -0.44750810773110444, -0.27699016346777455, -0.16262026905815133, 0.42255330195875485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.095795663723975, -0.022417591911861316, -0.011055671192844046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2070601252552261, 0.2135221305357053, 0.8195134890305069, 0.0, -0.23592775110245523, -0.33388518964591246, -2.462551220837017, -1.0959194558390715, -0.9894149872447394, -0.7505094029952885, -2.4622408329025243, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5333287265246551, 0.667481948193073, 1.4142498397471182, -1.1277963513126714, -2.2360476984196853, -0.5810006042943882, 1.2859313215966783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.266386030912219, -0.4373574993376022, 0.028596672850609083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880889928, 0.08664868790805016, 0.08629960443372142, 0.0, 0.005338729448539366, 0.1404975877801714, 0.25572326722171174, 0.4365397261287322, 0.9999999999997586, -1.0000005011055593, -1.0000000000001035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19850850453462252, 0.10399448552605098, 0.08863265560402797, -0.32830015865830164, -0.1534424400100285, -0.12317705898525709, 0.2805999158751256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07850302749007283, -0.017777407990034997, -0.009214118411216964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20771007749924222, 0.2173234455155467, 0.823412480102414, 0.0, -0.2331721748620815, -0.3259143561449327, -2.4553099141551606, -1.0691483838741687, -0.9394149872447404, -0.8005094280505596, -2.512240832902523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5410462930877361, 0.6720870992422457, 1.4174490504828554, -1.1398783046788483, -2.23955831534367, -0.5855875325806078, 1.2949642850495815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2696122536938677, -0.43805918705077557, 0.028207867985896987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880322287, 0.07602629959682783, 0.0779798214381413, 0.0, 0.05511152480747473, 0.1594166700195956, 0.14482613363713087, 0.5354214392980579, 0.9999999999999802, -1.0000005011054218, -0.9999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15435133126162043, 0.09210302098345298, 0.0639842147147435, -0.2416390673235393, -0.07021233847969158, -0.09173856572439221, 0.18065926905806198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0645244556329731, -0.014033754263467138, -0.007776097294241945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20836002974325324, 0.220580738424814, 0.8268497555052778, 0.0, -0.22776557192265945, -0.3174532650407923, -2.453736299899618, -1.0373651970028064, -0.8894149872447474, -0.8505094531076175, -2.562240832903147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5471275253317054, 0.6760967766719892, 1.419812030834297, -1.1488903227386842, -2.2406049125982195, -0.5889740129652162, 1.3007316657284402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2722569064454363, -0.43861191622931434, 0.02786773997931919]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880220122, 0.06514585818534588, 0.06874550805727751, 0.0, 0.10813205878844129, 0.1692218220828084, 0.03147228511085087, 0.6356637374272478, 0.9999999999998577, -1.0000005011411581, -1.0000000000124751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12162464487938615, 0.08019354859486817, 0.04725960702883106, -0.18024036119671732, -0.020931945090991222, -0.067729607692168, 0.1153476135771768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0528930550313747, -0.011054583570775578, -0.006802560131555889]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20890236731276418, 0.22331947192858484, 0.8299126941352141, 0.0, -0.21963384384261464, -0.3087547466632327, -2.457943386608462, -1.0008838400568223, -0.8394149872448201, -0.9005094781628663, -2.6122408329031273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519614181536695, 0.6795011419163419, 1.4215954927811791, -1.1557017087656305, -2.2403813722918278, -0.5914575442271724, 1.3044574108583427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2744018531044412, -0.43904510173632294, 0.027557092385001702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010846751390218888, 0.05477467007541689, 0.06125877259872422, 0.0, 0.16263456160089598, 0.17397036755119216, -0.08414173417687226, 0.7296271389196829, 0.9999999999985463, -1.0000005011049757, -0.9999999999996081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0966778564392827, 0.06808730488705383, 0.035669238937643385, -0.13622772053892793, 0.004470806127835566, -0.04967062523912445, 0.07451490259804805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04289893318009702, -0.008663710140172066, -0.006212951886349732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924014300176616, 0.22558907526272806, 0.832516028451838, 0.0, -0.2088784119570595, -0.29988190631457157, -2.4679101480898793, -0.9600673236121545, -0.7894149872448852, -0.9505095032181211, -2.6622408329031124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558093246584372, 0.6822883123648255, 1.4229550903934498, -1.1609092407972317, -2.239690744526241, -0.5932717611957165, 1.3069797006688277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2761077168336417, -0.4393805271434575, 0.027263123491609406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006755513780039767, 0.04539206668286434, 0.0520666863324798, 0.0, 0.2151086377111026, 0.17745680697322283, -0.19933522962834466, 0.8163303288933546, 0.9999999999986986, -1.0000005011050965, -0.9999999999997062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07695813009535564, 0.05574340896967034, 0.027191952245415554, -0.10415064063202173, 0.01381255531173049, -0.03628433937087952, 0.050445796209702576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03411727458400836, -0.006708508142691235, -0.00587937786784593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932616161286308, 0.22744569050308344, 0.834826254295132, 0.0, -0.19579154426530776, -0.2908321419076912, -2.483469466430795, -0.9154141104565975, -0.739414987245167, -1.000509528273315, -2.712240832902818, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5588604330257323, 0.6844420565639199, 1.4239877225131137, -1.164969402369256, -2.239103536428652, -0.5946108692553929, 1.3089117387084355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2774277204317501, -0.4396341865431943, 0.02698265280572664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017203722219384116, 0.037132304807107774, 0.04620451686587979, 0.0, 0.2617373538350347, 0.18099528813760773, -0.3111863668183114, 0.8930642631111416, 0.9999999999943651, -1.0000005011038793, -0.9999999999941117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06102216734590005, 0.04307488398188946, 0.020652642393276476, -0.08120323144048687, 0.011744161951782052, -0.0267821611935287, 0.03864076079215309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026400071962168384, -0.005073187994736585, -0.005609413717655272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20933056938417735, 0.228938372466004, 0.8366688095526873, 0.0, -0.18217453223378702, -0.2814297402669101, -2.500887728282853, -0.870306111972243, -0.6931649872445551, -1.0491367343047637, -2.7584908329056668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5612536679267874, 0.6860483734709207, 1.4247430436927009, -1.168155308410831, -2.2387880875171633, -0.595590809248792, 1.3105357742296277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.278425135211993, -0.4398232632180623, 0.02672449963672147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.815542628558227e-05, 0.029853639258411103, 0.03685110515110657, 0.0, 0.2723402406304148, 0.18804803281562182, -0.3483652370411696, 0.9021599696870902, 0.9250000000122373, -0.9725441206289748, -0.9250000000569817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.047864698021103345, 0.032126338140017016, 0.01510642359174525, -0.06371812083149866, 0.006308978229771619, -0.0195987998679837, 0.032480710423844435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01994829560486069, -0.003781533497360421, -0.005163063380103397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932884115003778, 0.23011316550761649, 0.8381225057841533, 0.0, -0.1693528861440909, -0.27255979656795276, -2.518771328661458, -0.8284933281084138, -0.654414987213272, -1.0926411213852207, -2.7972408329494938, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631048045192583, 0.687252723211333, 1.4252317019514358, -1.1706501793212163, -2.2387012797308765, -0.5962762215751217, 1.3119750197448723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2791678862882272, -0.4399629161625189, 0.02649902814853944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.456468279174673e-05, 0.023495860832250186, 0.029073924629319937, 0.0, 0.2564329217939224, 0.17739887397914625, -0.35767200757209533, 0.836255677276582, 0.7750000006256631, -0.8700877416091413, -0.7750000008765425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0370227318494159, 0.024086994808245304, 0.009773165174699198, -0.04989741820770852, 0.001736155725733773, -0.013708246526593065, 0.0287849103048912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014855021524681263, -0.002793058889132289, -0.004509429763640606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932788289126003, 0.23101798821627914, 0.8391026888525631, 0.0, -0.15818501666305668, -0.26483319096932273, -2.5359587088692606, -0.7937257558710759, -0.6250680896836437, -1.1277424437604398, -2.8260974817958933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564512246192544, 0.6882110000970189, 1.4254194277410992, -1.172594032649529, -2.2387410078804804, -0.5966909778580843, 1.3133183993931452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2797159619590375, -0.4400654543891233, 0.026310697312253172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9165175554961214e-05, 0.018096454173253205, 0.0196036613681976, 0.0, 0.22335738962068408, 0.15453211197260083, -0.34374760415605077, 0.6953514447467598, 0.5869379505925651, -0.7020264475043795, -0.5771329769279895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02814883346571545, 0.01916553771371786, 0.0037545157932705603, -0.0388770665662527, -0.0007945629920774432, -0.008295125659251692, 0.02686759296545663, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010961513416206263, -0.002050764532088299, -0.003766616725725312]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209326967977962, 0.23170153162576393, 0.8397180196333647, 0.0, -0.14905358832275853, -0.25852071302748747, -2.5515493738647765, -0.7668782370757354, -0.6040801048930344, -1.1540211237438165, -2.8459557199745085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5655600193084604, 0.6890612677378614, 1.4252544891234067, -1.1741005473302502, -2.2388086006669075, -0.5968383061702716, 1.3146469020890874, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2801180324457406, -0.44014044847222306, 0.0261579683581745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.829826596068004e-05, 0.013670868189695779, 0.01230661561603071, 0.0, 0.1826285668059628, 0.12624955883670494, -0.31181329991032136, 0.5369503759068073, 0.4197596958121855, -0.5255735996675329, -0.397164763572303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02095546231832748, 0.01700535281684921, -0.003298772353851691, -0.030130293614425267, -0.001351855728544265, -0.002946566243744073, 0.02657005391884625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008041409734061587, -0.001499881661994671, -0.003054579081573399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093259380204269, 0.23220977394247713, 0.8400854275917896, 0.0, -0.14197612515217423, -0.2536482214865198, -2.564986775067951, -0.7473180611300209, -0.5895743811466219, -1.1724845390217244, -2.858801959448876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663198497966578, 0.6899025586887599, 1.424707731640309, -1.1752628476276366, -2.2388339068055143, -0.5967248652769541, 1.3160195454508985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2804118817113503, -0.440195155718598, 0.02603609857431136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0599150701613132e-05, 0.010164846334263896, 0.007348159168498353, 0.0, 0.14154926341168605, 0.09744983081935366, -0.2687480240634872, 0.39120351891429056, 0.29011447492825215, -0.36926830555815804, -0.2569247894873526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015196609763948796, 0.016825819017970946, -0.010935149661955473, -0.023246005947725922, -0.0005061227721400406, 0.0022688178663480153, 0.027452867236222957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005876985312195564, -0.0010941449274996567, -0.002437395677262807]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932478082939882, 0.23258303632233118, 0.8403182736213654, 0.0, -0.13673976621698192, -0.25009048605629397, -2.5760634691920976, -0.7338035035911181, -0.5797348308047431, -1.1846861181123198, -2.8666674562661716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5668496073376568, 0.690808718640863, 1.423754695329556, -1.176157114405769, -2.2387707525162717, -0.5963535131611295, 1.3174903452101003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2806261112024597, -0.4402349952513054, 0.02593967049718884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.314382056186457e-05, 0.007465247597081032, 0.004656920591515499, 0.0, 0.10472717870384635, 0.07115470860451609, -0.22153388248293018, 0.2702911507780543, 0.19679100683757533, -0.24403158181190557, -0.1573099363459114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010595150819977833, 0.018123199042062353, -0.019060726215059675, -0.017885335562650054, 0.001263085784849995, 0.007427042316493482, 0.02941599518403489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004284589822188753, -0.0007967906541475968, -0.00192856154245041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932339724114024, 0.2328547249447787, 0.8404844977878413, 0.0, -0.13302175330080057, -0.2476419798401231, -2.5848497946527678, -0.7249578381638652, -0.5731054595349542, -1.1922294288601571, -2.8712263686173403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5671915980120815, 0.6918542953571599, 1.4223367074189475, -1.1768459124727995, -2.2385826009709686, -0.5957045777303653, 1.3191371386595554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2807820429389665, -0.440263974177527, 0.025863793622816735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.76717651716686e-05, 0.0054337724489508295, 0.003324483329518648, 0.0, 0.0743602583236267, 0.048970124323417547, -0.17572650921339994, 0.17691330854505882, 0.13258742539577828, -0.1508662149567478, -0.09117824702337414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006839813488494819, 0.020911534325937276, -0.028359758212169114, -0.013775961340610206, 0.0037630309060581193, 0.012978708615283687, 0.03293586898910326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003118634730133735, -0.000579578524432414, -0.001517537487442093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932160909258068, 0.2330513790842077, 0.840695975766972, 0.0, -0.1304781107382692, -0.24608019902554626, -2.5915906810501066, -0.7195101586413297, -0.5686273915797048, -1.1965227031409893, -2.873712065986655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5673716881041702, 0.6931383151733975, 1.420324885976035, -1.1773812592468422, -2.2382285951112917, -0.5947182660780783, 1.321087474954143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2808954222641762, -0.44028503700835714, 0.025804395699238862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.576297119099514e-05, 0.003933082788579588, 0.004229559582612759, 0.0, 0.05087285125062718, 0.031235616291536917, -0.1348177279467748, 0.1089535904507085, 0.08956135910498746, -0.08586548561664105, -0.04971394738629807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003601801841772482, 0.02568039632475126, -0.0402364288582501, -0.01070693548085521, 0.007080117193534543, 0.019726233045739956, 0.03900672589175434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022675865041934746, -0.000421256616602761, -0.0011879584715574895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931920301568352, 0.2331934293386948, 0.8408585872212334, 0.0, -0.12879737342821995, -0.245203650165338, -2.5966091754426435, -0.7164018528654865, -0.5655782245461377, -1.198687194199383, -2.8749662449540203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56739952898861, 0.6947976467255678, 1.417501623225868, -1.1778071478137369, -2.2376551247952263, -0.5932859412217962, 1.3235316849239758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.280977805635369, -0.4403003384623748, 0.025758135598587646]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.812153794340694e-05, 0.0028410050897417867, 0.0032522290852278627, 0.0, 0.03361474620098516, 0.017530977204165292, -0.10036988785073828, 0.0621661155168642, 0.06098334067134223, -0.04328982116787521, -0.02508357934730481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005568176887978771, 0.033186631043404066, -0.056465255003339654, -0.008517771337891071, 0.011469406321307846, 0.02864649712564206, 0.04888419939665492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016476674238530644, -0.0003060290803538771, -0.0009252020130243051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931618104453162, 0.23329626311703922, 0.8409724071782145, 0.0, -0.12772312341066705, -0.24481395712687198, -2.6002446659971485, -0.7148146095129365, -0.5634795661829842, -1.199550618643628, -2.875531087473784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5672778537988058, 0.6969542188524047, 1.4136642286778873, -1.1781593437099984, -2.2368185258139257, -0.5913055409781842, 1.3266454613493943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810376429208725, -0.44031145120516274, 0.02572219668437234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0439423038208124e-05, 0.002056675566888427, 0.002276399139622121, 0.0, 0.021485000351057923, 0.007793860769319941, -0.07270981109009911, 0.03174486705099942, 0.041973167263069225, -0.01726848888489693, -0.011296850395268064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024335037960834314, 0.04313144253673796, -0.07674789095961343, -0.007043917925231801, 0.016731979626013978, 0.03960800487223917, 0.06227552850837193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011967457100707489, -0.00022225485575790908, -0.0007187782843061262]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093132596300379, 0.2333713576137685, 0.8411024824889938, 0.0, -0.12705684411839407, -0.2447149090405895, -2.602818979415272, -0.7141544056546724, -0.5620128669998177, -1.199683608494942, -2.8757399307150244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5670300950976542, 0.6995436439667067, 1.4089507589655348, -1.1784599753817526, -2.2357609555553686, -0.5888537791612296, 1.3303470237452841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810810937432404, -0.4403195204187482, 0.0256940742681744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.842828987430867e-05, 0.0015018899345859969, 0.0026015062155844244, 0.0, 0.013325585845459686, 0.00198096172564936, -0.0514862683624715, 0.013204077165283132, 0.029333983663330492, -0.002659797026282086, -0.004176864824815902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004955174023030489, 0.05178850228603931, -0.09426939424704964, -0.0060126334350839375, 0.021151405171141162, 0.04903523633909185, 0.07403124791779794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008690164473574144, -0.00016138427170990318, -0.0005624483239587907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931107145574457, 0.23342725960843494, 0.8412299048084414, 0.0, -0.1266536488275151, -0.24475560750623362, -2.6046089182401073, -0.71401434648281, -0.56096890190329, -1.1994554876513186, -2.875785908046203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5667027024736216, 0.7023252529122656, 1.4038254173463194, -1.1787187226710483, -2.234602608355407, -0.5861785294179096, 1.334307758548752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811126383451363, -0.44032537855362475, 0.02567146062408601]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3763485867001316e-05, 0.001118039893328548, 0.002548446388953234, 0.0, 0.008063905817579597, -0.0008139693128823918, -0.035798776496701455, 0.002801183437245544, 0.020879301930553273, 0.004562416872467299, -0.0009195466235717882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006547852480650781, 0.05563217891117837, -0.10250683238430679, -0.005174945785914244, 0.023166943999231908, 0.053504994866400785, 0.07921469606935587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006308920379176483, -0.00011716269753029164, -0.0004522728817677998]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093095357777038, 0.23347030733254687, 0.8413333933949931, 0.0, -0.12641317592168402, -0.2448425633689893, -2.6058359713905936, -0.7141318406218842, -0.5602121250904676, -1.1990895838369133, -2.8757726831399966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663405076834858, 0.7050641520890193, 1.398739313522182, -1.1789408532348258, -2.23345759570976, -0.5835200154982266, 1.3382051322199189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281135535361113, -0.44032963089928073, 0.02565226245036766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0713560815450024e-05, 0.0008609544822384934, 0.002069771731034684, 0.0, 0.00480945811662164, -0.001739117255113497, -0.024541063009727, -0.0023498827814825117, 0.015135536256447077, 0.007318076288105374, 0.0002644981241333316, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007243895802718277, 0.0547779835350745, -0.10172207648274745, -0.004442611275548488, 0.022900252912939713, 0.05317027839365999, 0.07794747342334042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00045794031953013753, -8.504691312025128e-05, -0.0003839634743670364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093083863401872, 0.23350509051701604, 0.8413646252815028, 0.0, -0.12626914210007656, -0.2449286003817336, -2.606668321483937, -0.7143485456589677, -0.5596551025701284, -1.1987097357395833, -2.875750105900365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.565974677304888, 0.7076153731996925, 1.393973547800686, -1.1791313171364814, -2.2323958449919328, -0.5810281181019368, 1.3418399661678189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811521534988537, -0.4403327173759992, 0.025634732928234014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2988750332211854e-05, 0.0006956636893833827, 0.0006246377301939144, 0.0, 0.0028806764321491277, -0.001720740254886341, -0.016647001866865102, -0.004334100741669422, 0.011140450406784304, 0.007596961946602426, 0.0004515447926331461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007316607571954944, 0.051024422213464565, -0.09531531442991814, -0.0038092780331124413, 0.021235014356552527, 0.049837947925796156, 0.07269667895799907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000332362754814236, -6.172953436950594e-05, -0.0003505904426728646]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093074345213319, 0.23353476076684745, 0.8413867836530399, 0.0, -0.12617978319897336, -0.2449968772106131, -2.6072287718098015, -0.714577054554873, -0.559240923775451, -1.1983759739779265, -2.8757378530791198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5656226078371608, 0.7099212289243557, 1.3896443520739996, -1.1792953816447265, -2.2314451351174696, -0.5787651709376522, 1.345133091682759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811642136478232, -0.4403349575490008, 0.02561761009628726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9036377105635495e-05, 0.0005934049966281783, 0.000443167430740441, 0.0, 0.0017871780220643492, -0.0013655365775899187, -0.011209006517291896, -0.0045701779181072716, 0.008283575893547793, 0.006675235233133516, 0.00024505642489917266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007041389354544094, 0.0461171144932648, -0.08658391453372918, -0.003281290164901044, 0.01901419748926482, 0.045258943285691154, 0.06586251029880365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002412029793911311, -4.480346003190916e-05, -0.0003424566389351333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930656804015205, 0.23356129882315158, 0.8413701620718517, 0.0, -0.12612001251429453, -0.24504422559840863, -2.607604653229138, -0.7147753717799153, -0.5589313399745239, -1.1981100556589004, -2.8757403173484275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5652913274534491, 0.7119836069201142, 1.385754835100013, -1.1794382729338133, -2.2306047665306026, -0.5767333927952603, 1.3480873651022844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281172965508997, -0.440336583464336, 0.025600174956988263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7329623597052658e-05, 0.0005307611260826335, -0.00033243162376509416, 0.0, 0.0011954136935767837, -0.0009469677559102456, -0.007517628386735238, -0.003966344500848236, 0.006191676018541968, 0.005318366380524382, -4.928538615713067e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006625607674232605, 0.04124755991517044, -0.077790339479733, -0.0028578257817353727, 0.01680737173734279, 0.040635562847839264, 0.059085468390505325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017503722347327722, -3.2518306703991607e-05, -0.00034870278597991196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930571697289413, 0.23358578927657528, 0.8413301762265463, 0.0, -0.1260756570374459, -0.24507464315984007, -2.6078564227091303, -0.7149285725174833, -0.5586999459037346, -1.1979128602868756, -2.8757551078398103, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5649807970422012, 0.7138384212270887, 1.3822426312907556, -1.1795648525660125, -2.229858153091005, -0.5749001873910619, 1.3507527457911412, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811793163762348, -0.4403377635721811, 0.02558220222703967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.702134515844646e-05, 0.0004898090684743421, -0.000799716906108358, 0.0, 0.0008871095369727812, -0.0006083512286286783, -0.0050353895998431234, -0.0030640147513591332, 0.004627881415787143, 0.003943907440495759, -0.0002958098276514625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006210608224958936, 0.03709628613948982, -0.07024407618514973, -0.0025315926439827795, 0.014932268791951654, 0.036664108083967424, 0.05330761377713449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001270173447574517, -2.360215690101155e-05, -0.00035945459897185014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093048289687132, 0.23360869936906162, 0.8412687929570802, 0.0, -0.12603921694238535, -0.24509250940629626, -2.6080254533918, -0.7150364279503766, -0.5585275030750284, -1.197775332567186, -2.8757778356522703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5646863279103231, 0.7155384116720686, 1.3790120388227531, -1.1796795240936315, -2.229181352658341, -0.5732152525497688, 1.3532028827256402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811839248259298, -0.44033862013547376, 0.02556383189244487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7760083618687023e-05, 0.0004582018497266741, -0.0012276653893209275, 0.0, 0.0007288019012108107, -0.00035732492912375895, -0.0033806136533930773, -0.0021571086578656457, 0.00344885657412393, 0.002750554393789047, -0.00045455624919883757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005889382637561511, 0.03399980889959524, -0.06461184936005213, -0.002293430552380959, 0.013536008653279674, 0.033698696825861935, 0.04900273868997617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.216899389749787e-05, -1.713126585362548e-05, -0.0003674066918959724]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093038618960449, 0.23363013314251516, 0.8412021612596656, 0.0, -0.12600711441060672, -0.24510213748602921, -2.6081395104400515, -0.7151055316030717, -0.5583997009662818, -1.1976850765639133, -2.8758042432433197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5644002197876236, 0.7171431776920782, 1.3759527757440497, -1.1797862949051272, -2.228548011012204, -0.571620595983273, 1.3555215766006095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811872688471595, -0.44033924188535506, 0.02554541065054421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9341453365596536e-05, 0.00042867546907065216, -0.0013326339482925987, 0.0, 0.0006420506355724892, -0.00019256159465898116, -0.0022811409650317937, -0.00138207305390175, 0.0025560421749317797, 0.0018051200654563017, -0.0005281518209890811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005722162453991348, 0.03209532040019296, -0.06118526157406873, -0.002135416229915026, 0.01266683292273626, 0.03189313132991613, 0.04637387749938665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.688042459223199e-05, -1.243499762654782e-05, -0.0003684248380132118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930277955712914, 0.23365003479002197, 0.841142355991144, 0.0, -0.12597786919762735, -0.2451067040304369, -2.608217050437533, -0.7151446630045013, -0.5583056253473476, -1.1976298647099906, -2.875831082964572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564112916098539, 0.718713631945134, 1.3729505868607748, -1.1798888818872901, -2.227932048589906, -0.5700562098209019, 1.3577952065121577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811896953317157, -0.44033969321508903, 0.025527345973332755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1646778315541915e-05, 0.0003980329501363525, -0.0011961053704323751, 0.0, 0.0005849042595874469, -9.133088815418519e-05, -0.0015507999496303946, -0.0007826280285938342, 0.001881512378682125, 0.0011042370784556759, -0.0005367944250410268, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005746073781690693, 0.03140908506111582, -0.06004377766550069, -0.002051739643259896, 0.012319248445959628, 0.03128772324742158, 0.04547259823096527, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.852969112507101e-05, -9.026594679226684e-06, -0.0003612935442291047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930155521577734, 0.23366833009605906, 0.841094961488964, 0.0, -0.12595099681958702, -0.24510830575426978, -2.608270244854492, -0.7151623127094201, -0.5582368711318413, -1.1975992576938694, -2.8758562656040474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5638140257817605, 0.7203079847006745, 1.369895085563649, -1.1799907533268417, -2.227309439495549, -0.5684642412888999, 1.360107104727664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281191456016363, -0.440340020855898, 0.02550999675993775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4486827036107972e-05, 0.0003659061207415492, -0.0009478900435981089, 0.0, 0.0005374475608064811, -3.203447665762285e-05, -0.0010638883391749958, -0.0003529940983749414, 0.0013750843101261174, 0.0006121403224216934, -0.0005036527895113157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0059778063355689585, 0.03188705511080903, -0.061110025942516716, -0.0020374287910290695, 0.012452181887139795, 0.03183937064003895, 0.046237964310127326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.521369294633575e-05, -6.552816180006944e-06, -0.0003469842679000255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930018081720683, 0.23368500968621683, 0.8410609628302775, 0.0, -0.125926388040214, -0.24510836130916702, -2.6083070567133824, -0.7151655660674753, -0.5581869933210988, -1.1975851125906631, -2.875878686583119, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.563493591706401, 0.7219767244682881, 1.3666896025534783, -1.18009501357608, -2.226660223367573, -0.5667941725697253, 1.3625303249008929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811927335841258, -0.44034025872312105, 0.025493606580810426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7487971409974618e-05, 0.00033359180315545664, -0.0006799731737292077, 0.0, 0.0004921755874602552, -1.1110979447739581e-06, -0.0007362371778133676, -6.506716110269497e-05, 0.0009975562148499739, 0.0002829020641273661, -0.0004484195814282261, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006408681507189875, 0.033374795352271634, -0.06410966020341216, -0.002085204984763627, 0.012984322559509329, 0.033401374383493235, 0.04846440346457676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5551355253924737e-05, -4.757344460149128e-06, -0.00032780358254653704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929867884331144, 0.2337001652461733, 0.8410398000736337, 0.0, -0.1259039816055719, -0.24510771241587442, -2.608332691702937, -0.7151597804444204, -0.5581510785125475, -1.1975814871566215, -2.875897971265622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631438560880656, 0.7237552448328658, 1.3632656213457324, -1.180204082582403, -2.225971326545408, -0.5650103653121799, 1.365116883684307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281193660600752, -0.4403404314317798, 0.025478275340491713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0039477908181726e-05, 0.00030311119912921383, -0.00042325513287815654, 0.0, 0.0004481286928418511, 1.2977865851722881e-05, -0.0005126997910942445, 0.00011571246109806768, 0.0007182961710260918, 7.250868083288599e-05, -0.0003856936500588376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006994712366707671, 0.03557040729155468, -0.0684796241549184, -0.002181380126459792, 0.013777936443305007, 0.03567614515090822, 0.051731175668285306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8540332523773255e-05, -3.4541731755088937e-06, -0.00030662480637424854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092971066962968, 0.23371399345663038, 0.8410315183894932, 0.0, -0.12588360240755486, -0.24510639356105499, -2.6083506489147124, -0.7151486795474746, -0.5581253344249605, -1.1975842653907938, -2.875914255468676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5627612462555937, 0.7256557504430601, 1.3595986979929144, -1.180319265356326, -2.225239514424052, -0.5631003451914094, 1.3678858125913502, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811943332514166, -0.44034055684806567, 0.025463959270514265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.144294029240099e-05, 0.000276564209141811, -0.0001656336828101733, 0.0, 0.00040758396034068956, 2.6377096388984554e-05, -0.00035914423550959505, 0.00022201793891585123, 0.0005148817517415824, -5.55646834436625e-05, -0.0003256840610755665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007652196649439385, 0.03801011220388612, -0.07333846705635926, -0.0023036554784603078, 0.014636242427122956, 0.03820040241540994, 0.055378578140861626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3453013296197203e-05, -2.508325717375635e-06, -0.000286321399548956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929554240381656, 0.23372677844954556, 0.8410309175430131, 0.0, -0.12586495439624742, -0.24510451324511714, -2.608363229770946, -0.715134626654381, -0.5581069586289285, -1.1975907620666153, -2.875927934791054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5623475532949853, 0.7276636348005215, 1.355715874881219, -1.1804404942998248, -2.2244724050053057, -0.5610786053208363, 1.3708175312484436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811948213291113, -0.4403406479415184, 0.025450491256586823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.128584960460454e-05, 0.0002556998583034697, -1.2016929603494417e-05, 0.0, 0.00037296022614867746, 3.7606318756892435e-05, -0.0002516171246731703, 0.00028105786187182383, 0.00036751592064140806, -0.00012993351642981148, -0.00027358644755902454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008273859212166279, 0.040157687149229564, -0.07765646223390661, -0.002424578869977944, 0.015342188374920577, 0.040434797411462116, 0.05863437314186746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.7615538926286e-06, -1.8218690544552197e-06, -0.00026936027854881727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209294053398125, 0.23373885868698788, 0.8410335748135789, 0.0, -0.12584763873052435, -0.24510210272088584, -2.6083719747967073, -0.7151189612611795, -0.558093895091273, -1.197599327374643, -2.8759395243000445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.561909294418856, 0.7297428023174414, 1.3516858663276905, -1.1805665121830295, -2.2236858833252864, -0.5589813906049087, 1.3738611251068245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195175474863, -0.4403407141278588, 0.025437617055845567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9780113831033408e-05, 0.00024160474884648138, 5.314541131553214e-05, 0.0, 0.00034631331446133593, 4.821048462616556e-05, -0.00017490051522889565, 0.00031330786403151347, 0.0002612707531080156, -0.00017130616055594606, -0.00023179017981265172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008765177522586246, 0.041583350338396, -0.080600171070569, -0.0025203576640966487, 0.01573043360038643, 0.04194429431855181, 0.060871877167615614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.082915030469657e-06, -1.3237268083657956e-06, -0.0002574840148251435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929267402278356, 0.23375058401338336, 0.8410368464974026, 0.0, -0.1258312071972287, -0.24509912738008263, -2.608377934289759, -0.7151023257509268, -0.5580846474444042, -1.1976090235471704, -2.8759495580003933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5614554637779701, 0.7318480731070073, 1.3475954379145076, -1.180695442257408, -2.222898841005886, -0.5568542851154894, 1.3769520004783893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195432432936, -0.4403407622430411, 0.0254250422090177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7587506829197594e-05, 0.00023450652790980332, 6.543367647447401e-05, 0.0, 0.0003286306659130794, 5.9506816063916064e-05, -0.00011918986102826232, 0.0003327102050529317, 0.00018495293737567448, -0.00019392345054728718, -0.00020067400697726577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009076612817717112, 0.04210541579131824, -0.08180856826365653, -0.0025786014875700805, 0.015740846388008323, 0.04254210978838492, 0.06181750743129771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.139161459139613e-06, -9.623036454801814e-07, -0.0002514969365572958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929140492578405, 0.23376226979364867, 0.8410366838434314, 0.0, -0.1258152304891205, -0.24509561131307556, -2.6083818247290775, -0.7150849474311873, -0.5580781479145169, -1.1976193739597198, -2.875958516984219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5609949280913906, 0.7339380409830827, 1.3435246690204103, -1.180825424830752, -2.22212797938815, -0.5547392558008276, 1.380030415191857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811956188667661, -0.44034079724974484, 0.025412482780436875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.538193999048871e-05, 0.00023371560530605358, -3.2530794247178512e-06, 0.0, 0.0003195341621644069, 7.032134014142217e-05, -7.78087863706458e-05, 0.0003475663947893592, 0.00012999059774529547, -0.00020700825098755003, -0.0001791796765088974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009210713731589496, 0.04179935752150859, -0.08141537788194497, -0.002599651466876533, 0.015417232354719007, 0.042300586293236575, 0.06156829426935478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7286766039075745e-06, -7.001340752734186e-07, -0.0002511885716165004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929022605121414, 0.23377415724123438, 0.8410354043712006, 0.0, -0.12579936807991787, -0.245091880159618, -2.6083840897483874, -0.7150668577609607, -0.55807369540577, -1.197630180755887, -2.8759667720472466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5605345511860355, 0.7359832897091294, 1.3395309574510912, -1.1809550542929945, -2.2213846728043958, -0.552666304106167, 1.3830534858866987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811957541294259, -0.44034082274968717, 0.025399710587983983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3577491398254557e-05, 0.000237748951714319, -2.5589444615739494e-05, 0.0, 0.0003172481840523629, 7.462306915097544e-05, -4.5300386200787526e-05, 0.00036179340453244813, 8.905017493845235e-05, -0.00021613592333979306, -0.0001651012605533446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009207538107104077, 0.040904974520935396, -0.07987423138638482, -0.002592589244853728, 0.01486613167508669, 0.04145903389321194, 0.06046141389683468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7052531964609267e-06, -5.099988465446153e-07, -0.00025544384905784367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092891087142332, 0.2337863889700238, 0.8410360082603573, 0.0, -0.12578335826999573, -0.24508741702397602, -2.6083851827022246, -0.715048050955997, -0.5580706532528865, -1.1976413418152407, -2.8759746453116835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5600783519138955, 0.7379690563802977, 1.3356436247608887, -1.1810835571516842, -2.2206741594981336, -0.5506506833394155, 1.3859992698826669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811958522663727, -0.4403408413557531, 0.025386583483815072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2346739618580776e-05, 0.0002446345757885683, 1.207778313352136e-05, 0.0, 0.0003201961984425355, 8.926271283950733e-05, -2.18590767437206e-05, 0.0003761360992743255, 6.084305766997865e-05, -0.00022322118707697718, -0.00015746528873960834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009123985442799153, 0.03971533342336723, -0.07774665380405146, -0.002570057173793344, 0.014210266125241882, 0.04031241533503041, 0.058915679919361294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9627389349568807e-06, -3.721213176678822e-07, -0.0002625420833782228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928802517115022, 0.23379900514934923, 0.8410349328638245, 0.0, -0.125767081482586, -0.24508231676848866, -2.6083853909718746, -0.7150285610661412, -0.5580686155401812, -1.1976528125791381, -2.8759823294466824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5596274722157201, 0.7398939844199924, 1.3318660572606382, -1.1812107802490412, -2.219996308616668, -0.5486940638167193, 1.3888652079976598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959234561143, -0.4403408549627982, 0.025373054806792944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1670861659835338e-05, 0.00025232358650895104, -2.1507930657501184e-05, 0.0, 0.00032553574819482414, 0.00010200510974724494, -4.1653930017752455e-06, 0.0003897977971152688, 4.075425410771976e-05, -0.0002294152779486388, -0.0001536826999770408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00901759396351018, 0.038498560793894, -0.07555135000501167, -0.002544461947141193, 0.013557017629314352, 0.03913239045392443, 0.05731876229985881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4237948324154929e-06, -2.721409020453415e-07, -0.00027057354044257597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928695084797927, 0.2338119584573455, 0.8410321159752371, 0.0, -0.12575052771739645, -0.2450766126830368, -2.6083849522399776, -0.7150084945107471, -0.558067272264523, -1.1976645422434569, -2.875989934475641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5591806119876536, 0.7417669828489495, 1.3281815578917626, -1.181337083108363, -2.219347098584525, -0.5467876350123405, 1.3916637907816496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959750864783, -0.4403408649438677, 0.025359163293032172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.148646341928201e-05, 0.00025906615992544573, -5.6337771747108655e-05, 0.0, 0.00033107530379099525, 0.00011408170903712871, 8.774637939968811e-06, 0.0004013311078828809, 2.6865513162621074e-05, -0.00023459328637668916, -0.0001521005791680687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00893720456133019, 0.03745996857914207, -0.07368998737751273, -0.002526057186434127, 0.012984200642861312, 0.038128576087575396, 0.05597165567979601, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.032607281879432e-06, -1.9962139030758776e-07, -0.000277830275215461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928586632714155, 0.23382514213019298, 0.8410281279171928, 0.0, -0.1257337701212526, -0.245070380155813, -2.608384056205543, -0.7149880199197897, -0.5580663940860073, -1.1976764629807153, -2.875997503976249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5587346767482065, 0.7436035660074914, 1.3245602911608023, -1.1814631941859728, -2.218720221675862, -0.5449157679568635, 1.3944173987513842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196012518856, -0.4403408722934107, 0.02534500869895688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.169041675451192e-05, 0.0002636734569495852, -7.976116088462764e-05, 0.0, 0.000335151922876737, 0.00012465054447576959, 1.7920688690471714e-05, 0.0004094918191487047, 1.756357031465416e-05, -0.000238414745170206, -0.0001513900121642371, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008918704788940066, 0.036731663170838695, -0.07242533461920501, -0.0025222215521966854, 0.012537538173262038, 0.03743734110954007, 0.05507215939469092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.486475535157642e-07, -1.4699085936223667e-07, -0.0002830918815058249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928475816571282, 0.23383842289331924, 0.8410237772334282, 0.0, -0.12571693075540719, -0.24506380536438543, -2.6083828393500443, -0.7149673371095181, -0.5580658266392596, -1.1976884972615673, -2.876005033477747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5582855023094606, 0.7454223285409701, 1.320966063736913, -1.1815900579661462, -2.2181085407857957, -0.5430595762208513, 1.397153250655472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960396432749, -0.4403408777315123, 0.025330721100861507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2163228574663497e-05, 0.00026561526252498984, -8.701367529104261e-05, 0.0, 0.00033678731690860153, 0.00013149582855127422, 2.4337109971788726e-05, 0.0004136562054321969, 1.134893495327528e-05, -0.00024068561703942797, -0.00015059002995320076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008983488774919038, 0.03637525066957294, -0.07188454847778691, -0.002537275603468942, 0.012233617801327062, 0.03712383472024385, 0.05471703808175564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.424883800536471e-07, -1.0876203281328585e-07, -0.00028575196190749576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928361962021858, 0.233851671975343, 0.8410200329115725, 0.0, -0.12570014481308564, -0.24505718307812926, -2.608381384654628, -0.714946639975147, -0.5580654824178932, -1.19770057133443, -2.87601249037681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5578285987012843, 0.7472417640137283, 1.317362530804653, -1.1817186799421848, -2.217505315958886, -0.5412001596216567, 1.3998987606241629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960592890377, -0.4403408817798127, 0.025316430660225216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2770909884935263e-05, 0.00026498164047559765, -7.488643711521706e-05, 0.0, 0.0003357188464307567, 0.00013244572512316, 2.909390832013645e-05, 0.0004139426874227912, 6.884427328987225e-06, -0.0002414814572513849, -0.00014913798126398273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00913807216352482, 0.036388709455163676, -0.07207065864519666, -0.0025724395207737606, 0.012064496538201786, 0.037188331983892126, 0.054910199373815416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9291525549217034e-07, -8.096600676193637e-08, -0.0002858088127258603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928245108894183, 0.23386478804542368, 0.8410174650185066, 0.0, -0.125683527186835, -0.24505075403237622, -2.6083797446478076, -0.7149260860247941, -0.55806531127179, -1.1977126232930966, -2.876019838179076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.557359873636548, 0.7490775025074466, 1.31371866460612, -1.181849972036363, -2.216905181731572, -0.5393214456994128, 1.402677423283606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960735113084, -0.4403408848165188, 0.025302244240532755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3370625534722936e-05, 0.0002623214016136919, -5.135786131682776e-05, 0.0, 0.000332352525012723, 0.00012858091506071477, 3.280013641051642e-05, 0.0004110790070570588, 3.4229220628398828e-06, -0.000241039173333795, -0.0001469560453180969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00937450129472489, 0.03671476987436629, -0.07287732397065966, -0.0026258418835635637, 0.01200268454627503, 0.03757427844487955, 0.05557325318886109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.844454131390296e-07, -6.07341217716913e-08, -0.0002837283938491854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928125975254663, 0.2338777108130339, 0.8410158630732162, 0.0, -0.1256671439747314, -0.24504447219903447, -2.608377986471098, -0.7149057769458779, -0.5580652503388998, -1.1977246030067663, -2.876027063526532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5568762726491504, 0.7509401348519842, 1.3100131355736913, -1.181984612037136, -2.2163048343526506, -0.5374124503813171, 1.4055054932543025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196083799387, -0.44034088711628594, 0.02528823051558007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3826727904008558e-05, 0.0002584553522042788, -3.203890580907234e-05, 0.0, 0.000327664242072245, 0.00012563666683489575, 3.516353418872416e-05, 0.0004061815783248623, 1.2186578059567068e-06, -0.0002395942733952444, -0.00014450694912265818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009672019747952372, 0.03725264689075036, -0.07411058064857856, -0.002692800015456993, 0.012006947578431529, 0.0381799063619132, 0.056561399413934295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0576157060140677e-07, -4.5995343059355314e-08, -0.0002802744990537038]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928005822107565, 0.23389042542853103, 0.8410148861598132, 0.0, -0.1256510139598323, -0.24503832647630847, -2.608376152939475, -0.7148857485231586, -0.5580652620672273, -1.1977364858353845, -2.8760341665429783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5563762310020239, 0.7528339407988729, 1.3062369547787211, -1.182122942229882, -2.2157033441213, -0.535468624793998, 1.4083899574042051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960912332747, -0.4403408888790849, 0.02527441387595175]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4030629419687853e-05, 0.0002542923099423783, -1.953826805875379e-05, 0.0, 0.00032260029798148945, 0.00012291445452000235, 3.667063245698228e-05, 0.00040056845438629304, -2.3456654998743283e-07, -0.0002376565723656537, -0.00014206032892117383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010000832942529793, 0.037876118937773505, -0.07552361589940103, -0.002766603854918861, 0.012029804627013495, 0.038876511746381424, 0.057689282998053766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.486777525501345e-07, -3.525597893159262e-08, -0.00027633279256637983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927886130024168, 0.2339029581009885, 0.8410143843772253, 0.0, -0.12563511083264114, -0.2450323182141585, -2.6083742664359377, -0.7148659747237618, -0.5580653290243688, -1.1977482722593595, -2.876041161779588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558598237937736, 0.7547568426705952, 1.3023937086428552, -1.182264935247827, -2.21510201780957, -0.5334919482142477, 1.4113283165359392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960965966573, -0.4403408902509209, 0.025260777130170713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.393841667927272e-05, 0.0002506534491489933, -1.0035651758644546e-05, 0.0, 0.0003180625438231048, 0.00012016524299924724, 3.773007074423181e-05, 0.0003954759879352741, -1.339142829504216e-06, -0.0002357284794985124, -0.00013990473219042374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010328144165007061, 0.038458037434445515, -0.07686492271731701, -0.0028398603588998673, 0.012026526234592393, 0.039533531595005764, 0.05876718263468003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0726765329846376e-07, -2.7436719599043683e-08, -0.00027273491562077913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092776824624636, 0.23391536552185, 0.8410144391534922, 0.0, -0.12561937333641351, -0.24502644928800751, -2.608372332749249, -0.714846381459219, -0.5580654492593156, -1.197759983980225, -2.8760480752640456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5553285643804892, 0.7567016476649344, 1.2984972245575668, -1.182410240711934, -2.2145038309831597, -0.5314896916689004, 1.4143103114192785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961004586885, -0.440340891338681, 0.025247270725072626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3576755561743843e-05, 0.0002481484172302796, 1.0955253381353154e-06, 0.0, 0.00031474992455246607, 0.00011737852301981131, 3.8673733772419264e-05, 0.0003918652908572367, -2.4046989356143726e-06, -0.00023423441731272078, -0.00013826968915586324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010625188265690203, 0.03889609988678383, -0.07792968170576704, -0.002906109282138934, 0.011963736528207015, 0.040045130906946655, 0.05963989766678648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.724062164925631e-08, -2.175520169768459e-08, -0.00027012810196172857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927653107197078, 0.23392772070120912, 0.84101540580586, 0.0, -0.12560372148059526, -0.2450207360536313, -2.608370340249683, -0.7148268663770398, -0.5580656368309801, -1.1977716584644167, -2.8760549373458373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5547849118132201, 0.7586582290391126, 1.2945673283683066, -1.1825582987058603, -2.2139125863543287, -0.5294722015989911, 1.417321104001079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961032334704, -0.44034089222072975, 0.02523382607193861]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3027809855934757e-05, 0.0002471035871828815, 1.9333047355637315e-05, 0.0, 0.0003130371163650664, 0.00011426468752416804, 3.984999132486252e-05, 0.00039030164358217097, -3.751433291583298e-06, -0.00023348968383076396, -0.00013724163583012978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010873051345381439, 0.03913162748356494, -0.07859792378520314, -0.0029611598785264674, 0.011824892576616503, 0.04034980139818535, 0.06021585163600526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.5495637686507746e-08, -1.764097494381458e-08, -0.00026889306268031713]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927541131276883, 0.23394009802358995, 0.8410185932189661, 0.0, -0.12558808170539637, -0.24501536003159705, -2.6083682275172504, -0.7148073196989726, -0.5580659552445796, -1.1977833488101328, -2.8760617628774376, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5542316414209236, 0.7606159964722238, 1.2906249655285476, -1.182708483457291, -2.21333203892798, -0.5274503660158455, 1.4203449570214883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196105224699, -0.4403408929544426, 0.025220370236506463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2395184038915284e-05, 0.00024754644761651673, 6.374826212170298e-05, 0.0, 0.0003127955039780514, 0.00010752044068553737, 4.225464864792489e-05, 0.0003909335613460387, -6.368271990569878e-06, -0.00023380691432252473, -0.00013651063200414507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011065407845928948, 0.039155348662223484, -0.07884725679517919, -0.0030036950286129248, 0.011610948526976715, 0.04043671166291232, 0.06047706040818713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.982457199812676e-08, -1.4674257741168563e-08, -0.0002691167086428905]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092743215783537, 0.23395255998394907, 0.8410230051473843, 0.0, -0.1255723470215273, -0.24500948683706794, -2.6083661263330646, -0.7147876519622324, -0.5580662673833868, -1.1977950636282821, -2.8760686341751702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5536712534113452, 0.7625660031818171, 1.2866879830377118, -1.182860236787746, -2.2127652088517054, -0.5254334347642385, 1.4233684315272994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066363056, -0.4403408935819532, 0.025206839486613532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1794688302532136e-05, 0.0002492392071820842, 8.823856836351996e-05, 0.0, 0.00031469367738097055, 0.00011746389058215508, 4.202368371624377e-05, 0.0003933547348035006, -6.242776145484021e-06, -0.00023429636298597504, -0.000137425954647393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011207760191569353, 0.03900013419186768, -0.0787396498167154, -0.0030350666091020382, 0.011336601525492554, 0.04033862503213897, 0.06046949011622329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.823213433133761e-08, -1.2550211904220164e-08, -0.0002706149978586365]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927325796914456, 0.23396514844578484, 0.8410271275585507, 0.0, -0.1255564580338701, -0.24500311691316207, -2.6083640599432076, -0.7147677981657665, -0.5580665472338727, -1.1978068265208242, -2.876075583750252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.553105546653773, 0.7645022849839103, 1.2827683981542415, -1.1830131612272698, -2.2122139963352003, -0.5234276176635633, 1.426382469184317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119610762088, -0.44034089413375943, 0.025193188723775455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1272184183163444e-05, 0.00025176923671551226, 8.244822332876133e-05, 0.0, 0.0003177797531437408, 0.00012739847811768642, 4.132779714126504e-05, 0.0003970759293174542, -5.597009716998422e-06, -0.00023525785083845817, -0.00013899150163114093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011314135151442745, 0.03872563604186414, -0.07839169766940694, -0.0030584887904729547, 0.011024250330098417, 0.04011634201350546, 0.06028075314034978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9691486868662377e-08, -1.1036124096475251e-08, -0.00027301525676155737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927221430519952, 0.23397788059636185, 0.8410270716064849, 0.0, -0.12554039099261471, -0.24499642276078032, -2.608362020589197, -0.7147477276260098, -0.5580668007004707, -1.197818655240422, -2.8760826201722662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5525354056982379, 0.7664223422694074, 1.278871353095892, -1.1831670647227828, -2.2116791073875484, -0.5214355596259588, 1.4293832066465353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961082891086, -0.4403408946317607, 0.025179396447075814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0873278901138924e-05, 0.00025464301154047255, -1.119041316239696e-06, 0.0, 0.0003213408251079206, 0.00013388304763496832, 4.0787080209078265e-05, 0.0004014107951335775, -5.069331957641143e-06, -0.00023657439195773594, -0.00014072844028634236, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011402819110700887, 0.03840114570994267, -0.07794090116698955, -0.003078069910258842, 0.010697778953041907, 0.03984116075209075, 0.06001474924436734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3364573338846698e-08, -9.96002479206681e-09, -0.00027584553399285095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927118397610842, 0.23399075006007178, 0.8410239311303209, 0.0, -0.1255241513808587, -0.24498956199327032, -2.608359996228923, -0.7147274444229025, -0.5580670386222834, -1.1978305548826256, -2.8760897378995463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519607905134508, 0.7683268961315398, 1.2749955209541877, -1.1833219600052314, -2.2111602189092636, -0.5194565663562908, 1.4323716913338567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087239965, -0.44034089509134106, 0.025165464592248835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0606581822150228e-05, 0.00025738927419882105, -6.280952327926157e-05, 0.0, 0.00032479223511994534, 0.00013721535019996331, 4.048720548120468e-05, 0.0004056640621466314, -4.758436254420416e-06, -0.0002379928440712219, -0.00014235454560254028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492303695741828, 0.0380910772426483, -0.07751664283408612, -0.0030979056489716097, 0.010377769565691192, 0.03957986539335971, 0.05976969374642933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.697758470711222e-09, -9.191606961494153e-09, -0.0002786370965395946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927016114082483, 0.23400373210759065, 0.8410194512123002, 0.0, -0.12550776676360897, -0.24498264241683182, -2.6083579783408393, -0.7147069809039911, -0.558067269018674, -1.1978425179494117, -2.8760969224402344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5513808833672721, 0.770219150729859, 1.2711345184463556, -1.1834780299146201, -2.210656286818563, -0.5174873471763168, 1.4353528300773581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961089872947, -0.4403408955231401, 0.025151414134471806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0456705671853165e-05, 0.0002596409503772192, -8.959836041594101e-05, 0.0, 0.00032769234499486994, 0.00013839152876997973, 4.035776167439639e-05, 0.0004092703782273909, -4.607927813112079e-06, -0.00023926133572264456, -0.0001436908137622857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011598142923575108, 0.037845091966384706, -0.0772200501566399, -0.0031213981877756675, 0.010078641814011902, 0.03938438359947973, 0.05962277487002981, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.265964787306103e-09, -8.635980485045285e-09, -0.0002810091555406154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092691414881666, 0.23401679135898465, 0.8410150085045758, 0.0, -0.12549127854671643, -0.24497574505774763, -2.608355960179742, -0.7146863868814608, -0.5580674989080651, -1.1978545284643507, -2.8761041534961382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5507943371419204, 0.7721037991406221, 1.2672788624344777, -1.1836355715101474, -2.2101659072623985, -0.5155230332547469, 1.4383339177750694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091267843, -0.4403408959343855, 0.02513727793862914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0393053164340324e-05, 0.00026118502787984593, -8.885415448636424e-05, 0.0, 0.00032976433785099205, 0.00013794718168371885, 4.036322194714469e-05, 0.0004118804506054077, -4.597787821579858e-06, -0.00024021029877926975, -0.0001446211180774292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011730924507034505, 0.037692968215261316, -0.07711312023755544, -0.003150831910545682, 0.009807591123291796, 0.0392862784313995, 0.059621753954225365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7897920090490064e-09, -8.224908377818695e-09, -0.00028272391685331427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926812261786906, 0.23402988986582984, 0.8410113546364125, 0.0, -0.1254747319744555, -0.24496891110737837, -2.6083539390949957, -0.7146657179611566, -0.5580677317620203, -1.1978665659441785, -2.8761114100393854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5501995705682504, 0.7739859735345267, 1.2634180710725733, -1.1837949304919402, -2.209687661112676, -0.5135582639844605, 1.441323046386029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091769961, -0.44034089633000717, 0.025123092917831803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.037740595119924e-05, 0.00026197013690362075, -7.307736326522295e-05, 0.0, 0.0003309314452189297, 0.00013667900738548018, 4.042169492600479e-05, 0.000413378406083312, -4.657079103848079e-06, -0.00024074959655829772, -0.00014513086494717239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011895331473398937, 0.037643487878091735, -0.07721582723808787, -0.0031871796358551034, 0.009564922994449472, 0.039295385405728384, 0.05978257221919284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0042353279090035e-09, -7.91243332768826e-09, -0.00028370041594671626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209267104140628, 0.2340429943556656, 0.8410087467675743, 0.0, -0.12545816787715466, -0.24496215978482463, -2.6083519141469704, -0.7146450246015063, -0.5580679696948085, -1.1978786103348296, -2.8761186733775808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5495950616600683, 0.7758702989590087, 1.2595425870350851, -1.1839564366614876, -2.2092203933095136, -0.5115881754110759, 1.4443276391989144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091630049, -0.44034089671341636, 0.025108892724971923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0369544821449065e-05, 0.00026208979671518603, -5.215737676477587e-05, 0.0, 0.0003312819460165331, 0.0001350264510744388, 4.049896050569199e-05, 0.00041386719300691855, -4.75865576519643e-06, -0.00024088781302224356, -0.00014526676390855757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012090178163641576, 0.0376865084896394, -0.07750968074976214, -0.0032301233909471402, 0.009345356063242948, 0.039401771467691124, 0.060091856257709055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7982296091932287e-10, -7.668184058429974e-09, -0.00028400385719756733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926608744319491, 0.2340560813647748, 0.84100714592006, 0.0, -0.12544161653442082, -0.244955497567562, -2.6083498843726542, -0.7146243440160265, -0.558068214967887, -1.1978906458593799, -2.8761259294668036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5489795953441095, 0.7777601731303376, 1.2556452680292212, -1.1841203496511143, -2.2087633966761158, -0.50960916074856, 1.447353305741198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091030892, -0.4403408970870755, 0.025094702314994995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0333948661378775e-05, 0.00026174018218340985, -3.20169502866619e-05, 0.0, 0.0003310268546768269, 0.00013324434525306686, 4.059548631981508e-05, 0.0004136117095959833, -4.905461569446624e-06, -0.000240710491007444, -0.0001451217844593823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012309326319177109, 0.03779748342657835, -0.07794638011728017, -0.003278259792533467, 0.009139932667958336, 0.03958029325031823, 0.06051333084567211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1983133136278932e-09, -7.473183279607074e-09, -0.00028380819953853617]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926507518548892, 0.23406913975715812, 0.8410063972109484, 0.0, -0.1254250943916626, -0.24494892316027456, -2.608347847602481, -0.7146036957909659, -0.5580684709624298, -1.197902663376985, -2.8761331701051116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5483524295994947, 0.7796573562743375, 1.2517222633995697, -1.1842868227479875, -2.208316486536265, -0.5076193119658289, 1.450403158759081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961090106299, -0.4403408974528865, 0.025080534974728976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.024515411962932e-05, 0.00026116784766674965, -1.4974182231708038e-05, 0.0, 0.0003304428551644765, 0.00013148814574851165, 4.073540347224048e-05, 0.0004129645012103608, -5.11989085565838e-06, -0.00024035035209954281, -0.00014481276615678032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012543314892294048, 0.03794366287999797, -0.07846009259303048, -0.0033294619374617247, 0.008938202797012384, 0.039796975654622084, 0.06099706035765974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8491878388867557e-09, -7.316219767631447e-09, -0.00028334680532038955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092640706247312, 0.23408217066001355, 0.8410063526322429, 0.0, -0.12540860373294258, -0.2449424304491214, -2.60834579975472, -0.7145830813160546, -0.5580687427240117, -1.1979146611692344, -2.876140392932268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477133581084443, 0.7815619052704538, 1.2477731946150523, -1.184455889736394, -2.207879969820352, -0.5056185028546967, 1.4534776604086994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961088954982, -0.44034089781242836, 0.025066391894913224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.009121515419239e-05, 0.000260618057108365, -8.915741105720763e-07, 0.0, 0.00032981317440052325, 0.00012985422306327325, 4.095695521190876e-05, 0.0004122894982256085, -5.435231639094996e-06, -0.00023995584498924465, -0.00014445654312312013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012781429821006966, 0.03809097992232506, -0.07898137569034647, -0.0033813397681313325, 0.008730334318258284, 0.0400161822226447, 0.06149003299236816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3026331635870013e-09, -7.190836763878865e-09, -0.00028286159631504327]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926307691308385, 0.23409518526677917, 0.8410069402647227, 0.0, -0.1253921349031404, -0.24493601079447763, -2.6083437344912714, -0.7145624864817306, -0.5580690372130511, -1.1979266443344707, -2.8761476003795403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5470626671276048, 0.7834724248618756, 1.2438006829971782, -1.184627475277609, -2.207454529886821, -0.5036081384235395, 1.4565749690388725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087651023, -0.44034089816707767, 0.025052263927612763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.987423294722793e-05, 0.0002602921353122936, 1.1752649594739351e-05, 0.0, 0.00032937659604336363, 0.00012839309287525946, 4.1305268976469446e-05, 0.0004118966864805311, -5.889780787719116e-06, -0.00023966330472836243, -0.00014414894544540635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013013819616792176, 0.03821039182843783, -0.07945023235748334, -0.0034317108242994452, 0.008508798670629213, 0.04020728862314311, 0.061946172603460165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.6079186586223684e-09, -7.0929858090402915e-09, -0.0002825593460092203]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926209653450153, 0.23410820123521298, 0.8410082143246913, 0.0, -0.1253756709732818, -0.24492966907772523, -2.6083416402413238, -0.7145418865534288, -0.5580693663526989, -1.1979386237684981, -2.8761547968083865, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5464010059180497, 0.7853865487005857, 1.2398093933607142, -1.1848014244146543, -2.207041062165461, -0.5015906591196544, 1.4596916611728852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961086252894, -0.44034089851804437, 0.025038134870181875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9607571646466996e-05, 0.0002603193686763777, 2.5481199373799305e-05, 0.0, 0.00032927859717196993, 0.0001268343350481614, 4.188499894923267e-05, 0.00041199856603673615, -6.582792954605186e-06, -0.00023958868055025964, -0.0001439285769249745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013233224191099789, 0.038282476774199756, -0.0798257927292779, -0.003478982740907496, 0.008269354427197501, 0.04034958607770108, 0.06233384268025381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7962567570105424e-09, -7.0193344667182365e-09, -0.00028258114861774437]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926113099265617, 0.234121238526162, 0.8410105984550883, 0.0, -0.1253591947926548, -0.24492346106987012, -2.6083394906020354, -0.7145212518834684, -0.5580697569854639, -1.1979506160215903, -2.8761619827878184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5457292068060542, 0.7873015241020881, 1.2358048465440552, -1.184977542987103, -2.206640501330332, -0.49956893056404467, 1.4628236370430239, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961084815775, -0.4403408988663479, 0.025023985465707808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931083690758048e-05, 0.0002607458189806041, 4.768260794038333e-05, 0.0, 0.00032952361254006915, 0.00012416015710208913, 4.2992785767106124e-05, 0.0004126933992083718, -7.812655299679258e-06, -0.0002398450618418897, -0.0001437195886432252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01343598223991072, 0.03829950803004944, -0.08009093633318079, -0.0035223714489752, 0.008011216702579899, 0.0404345711121948, 0.06263951740277536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8742398780104438e-09, -6.966071248459883e-09, -0.0002829880894813476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926018097379936, 0.23413431550550415, 0.8410167207029203, 0.0, -0.12534271040293332, -0.2449177927150775, -2.608337171986235, -0.7145005514573702, -0.5580703255885383, -1.1979626566472965, -2.876169126106767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5450480973304483, 0.7892147697485378, 1.2317922688863037, -1.1851556392368676, -2.206253675763402, -0.4975456560147912, 1.4659670042325852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961083432173, -0.4403408992127139, 0.025009797299432257]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9000377136226644e-05, 0.0002615395868425685, 0.00012244495664020678, 0.0, 0.00032968779442995655, 0.00011336709585256783, 4.637231600443822e-05, 0.00041400852196258844, -1.1372061487813333e-05, -0.00024081251412407916, -0.00014286637897059832, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013622189512117975, 0.03826491292899262, -0.08025155315503234, -0.003561924995294374, 0.007736511338602989, 0.040465490985068735, 0.06286734379122626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7672025351042834e-09, -6.927319278877532e-09, -0.0002837633255110353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925924473431196, 0.23414744577279814, 0.8410295052634726, 0.0, -0.12532615413129616, -0.24491146594222257, -2.6083348858091493, -0.7144797706276045, -0.5580708638242928, -1.1979747109666614, -2.876176309298787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5443583420276428, 0.7911243028203149, 1.2277756938930156, -1.1853355594288222, -2.205881215621574, -0.49552292125638464, 1.4691187756999138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961081996834, -0.4403408995579558, 0.024995556101940583]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.872478974795834e-05, 0.0002626053458798795, 0.0002556912110465393, 0.0, 0.0003311254327433029, 0.00012653545709845852, 4.5723541721021796e-05, 0.0004156165953142211, -1.0764715090429236e-05, -0.00024108638729753126, -0.00014366384040922283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013795106056110737, 0.038190661435542575, -0.08033149986576091, -0.0035984038390933335, 0.007449202836556653, 0.04045469516813203, 0.06303542934656964, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.870679197150595e-09, -6.904837927637466e-09, -0.00028482394983349996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209258321812838, 0.23416063671814646, 0.8410437398870134, 0.0, -0.12530950693366413, -0.2449045021895959, -2.6083326703868854, -0.7144588979179173, -0.5580713315230594, -1.1979867766771146, -2.876183551344064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5436603401302411, 0.7930289777705635, 1.2237574461151752, -1.1855172087541164, -2.205523515013933, -0.4935019358093305, 1.4722772729752847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196108047214, -0.4403408999025876, 0.02498125341052859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8458429479456307e-05, 0.00026381890696620686, 0.00028469247081648613, 0.0, 0.00033294395264052857, 0.0001392750525336554, 4.430844527807723e-05, 0.0004174541937448723, -9.353975332314504e-06, -0.00024131420906434384, -0.00014484090553941895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013960037948034177, 0.03809349900497107, -0.08036495555680431, -0.003632986505881571, 0.007154012152821098, 0.04041970894108255, 0.06316994550741814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0493887787539148e-09, -6.892636135295253e-09, -0.00028605382823986507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925741079071422, 0.23417388915558981, 0.8410558513561877, 0.0, -0.1252927688848866, -0.24489716620190444, -2.608330514922322, -0.7144379299689384, -0.5580717393380537, -1.1979988583162735, -2.876190849474161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5429541857656108, 0.7949285340699397, 1.219738015378438, -1.1857005597806267, -2.20518074960298, -0.49148297443279904, 1.4754422337730737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961078852034, -0.44034090024685824, 0.02496688719657855]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.822044247553129e-05, 0.00026504874886679614, 0.00024222938348463573, 0.0, 0.00033476097555076287, 0.00014671975382885406, 4.3109291263184026e-05, 0.00041935897957802475, -8.15629988416167e-06, -0.00024163278317604285, -0.00014596260194143167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014123087292605495, 0.0379911259875245, -0.08038861473474176, -0.003667020530205452, 0.006855308219058671, 0.04037922753062938, 0.06329921595578203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.240211931340805e-09, -6.8854117509447195e-09, -0.0002873242790007967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925651016993824, 0.2341871982181353, 0.841064560189934, 0.0, -0.12527594904818817, -0.244889683732324, -2.6083283999322955, -0.7144168718483338, -0.5580721071402739, -1.1980109586672534, -2.8761981945080244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5422396885604397, 0.796823478601238, 1.2157162776406405, -1.1858856473286126, -2.204852931173053, -0.48946549449193955, 1.4786146509471971, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961077143157, -0.440340900590808, 0.024952461212057558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8012415519644415e-05, 0.0002661812509097066, 0.00017417667492830742, 0.0, 0.0003363967339687805, 0.00014964939160868815, 4.22998005336657e-05, 0.0004211624120919971, -7.356044404709993e-06, -0.00024200701959800386, -0.00014690067726872157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014289944103422625, 0.03789889062596692, -0.08043475475595119, -0.003701750959717785, 0.006556368598541364, 0.04034959881719022, 0.06344834348246732, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.417755392511266e-09, -6.878994897202412e-09, -0.0002885196904198138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925561871488957, 0.2342005551099568, 0.8410618129676085, 0.0, -0.12525905888066197, -0.24488214897121363, -2.6083263175041984, -0.7143957352424114, -0.5580724431370468, -1.1980230752117988, -2.876205579243565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5415164409760148, 0.7987148547729442, 1.2116899592973498, -1.1860725531242928, -2.204539981107109, -0.4874483756147806, 1.4817964206867469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196107529577, -0.4403409009345591, 0.024937983419938786]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7829100973510103e-05, 0.00026713783642982983, -5.494444651112204e-05, 0.0, 0.00033780335052389384, 0.00015069522220727264, 4.1648561942064236e-05, 0.00042273211844828475, -6.719935459193817e-06, -0.00024233089091155212, -0.0001476947108070534, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0144649516884974, 0.03782752343412516, -0.08052636686581613, -0.0037381159136050312, 0.006259001318883878, 0.04034237754317851, 0.063635394790993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.6947749940585474e-09, -6.875021760779324e-09, -0.00028955584237541106]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925473569686348, 0.23421394931927147, 0.8410514001986437, 0.0, -0.1252421128803267, -0.24487463982329583, -2.6083242575075474, -0.714374534897885, -0.5580727580383967, -1.1980352043068812, -2.876212994467474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5407839134953499, 0.8006039588567667, 1.207656221940558, -1.186261384604039, -2.2042418051162214, -0.48543021847138557, 1.484989893729473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961073308133, -0.4403409012779771, 0.024923463887919817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.766036052164086e-05, 0.0002678841862932682, -0.0002082553792966759, 0.0, 0.0003389200067054922, 0.00015018295835598537, 4.119993302519067e-05, 0.00042400689052663815, -6.298026998768619e-06, -0.00024258190164787988, -0.00014830447818341125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014650549613298546, 0.037782081676448954, -0.08067474713583679, -0.0037766295949263422, 0.005963519817753503, 0.04036314286790055, 0.06386946085452182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.975271951200736e-09, -6.868360176661031e-09, -0.00029039064037935573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092538608537945, 0.23422737072300479, 0.8410381966315522, 0.0, -0.12522512498451718, -0.24486719520491726, -2.6083222122520726, -0.7143532856264078, -0.558073060175217, -1.1980473414524133, -2.8762204318291222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5400415571601024, 0.802492060683494, 1.203612248263087, -1.1864522523033614, -2.203958355577257, -0.48340964194609903, 1.4881974215808351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961071196258, -0.4403409016208386, 0.024908912697799563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7496861379995055e-05, 0.0002684280746661161, -0.00026407134182844635, 0.0, 0.0003397579161902799, 0.00014889236757115187, 4.0905109493422496e-05, 0.0004249854295460771, -6.042736403583455e-06, -0.00024274291064534188, -0.00014874723296733107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014847126704950253, 0.03776203653454571, -0.08087947354941886, -0.0038173539864452552, 0.005668990779289269, 0.04041153050573016, 0.06415055702724443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.223748727891442e-09, -6.857230398915573e-09, -0.0002910238024050965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092529944076841, 0.23424081134161082, 0.8410256342076418, 0.0, -0.1252081083032503, -0.24485987423481367, -2.6083201681803243, -0.7143319993473054, -0.5580733639668903, -1.19805948425245, -2.876227881748336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5392888952123503, 0.8043801749776589, 1.199555730702428, -1.1866452498983047, -2.203689672700999, -0.4813855291015325, 1.4914209744135996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961069010158, -0.44034090196284364, 0.024894338130268572]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.73289222079557e-05, 0.0002688123721204562, -0.00025124847820875187, 0.0, 0.0003403336253374409, 0.0001464194020714956, 4.088143496894334e-05, 0.00042572558204703276, -6.075833466954572e-06, -0.00024285600073301045, -0.00014899838427806628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015053238955041206, 0.037762285883297685, -0.08113035121317991, -0.00385995189886731, 0.005373657525156167, 0.0404822568913309, 0.06447105665528777, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.372200407588851e-09, -6.840101178064515e-09, -0.00029149135061983824]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925213689002095, 0.2342542662563984, 0.8410156966170897, 0.0, -0.12519107192954645, -0.24485269584579836, -2.6083181143208978, -0.7143106838121357, -0.5580736811329241, -1.1980716312967383, -2.8762353371275893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5385255891694956, 0.8062689141714454, 1.1954851943908478, -1.1868404398340329, -2.2034359013919644, -0.47935718789178705, 1.4946618848676878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066785933, -0.44034090230379175, 0.024879745639150908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.715035326296363e-05, 0.00026909829575125156, -0.00019875181104035377, 0.0, 0.0003407274740771001, 0.00014356778030618733, 4.1077188530469014e-05, 0.0004263107033934446, -6.343320675583013e-06, -0.000242940885769391, -0.00014910758505718826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015266120857095179, 0.03777478387572981, -0.08141072623160639, -0.0039037987145622843, 0.00507542618069157, 0.04056682419490884, 0.06481820908176425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.448451342577258e-09, -6.818962556157126e-09, -0.0002918498223532651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925128903715878, 0.23426773395518843, 0.8410091822802671, 0.0, -0.1251740209093694, -0.24484566153708204, -2.608316039956505, -0.7142893418370708, -0.5580740230314425, -1.1980837830640352, -2.8762427927565875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5377514715302819, 0.8081584355938903, 1.191400123617303, -1.1870378465048221, -2.203197285560948, -0.47732441194759734, 1.4979207434700035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961064552824, -0.44034090264356734, 0.024865137375008096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6957057243526444e-05, 0.00026935397580074723, -0.0001302867364530094, 0.0, 0.00034102040354084764, 0.00014068617432632294, 4.1487287853933165e-05, 0.00042683950129745, -6.8379703677965584e-06, -0.00024303534593528628, -0.0001491125799654512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015482352784273262, 0.037790428448899266, -0.08170141547089317, -0.003948133415784107, 0.004772316620325626, 0.04065551888379408, 0.06517717204631435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4662181708756e-09, -6.795512158578875e-09, -0.00029216528285619614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925045163771558, 0.23428121600255097, 0.841006182580274, 0.0, -0.1251569578582527, -0.2448387886481049, -2.6083139287135433, -0.7142679714400227, -0.5580744067173158, -1.198095943175205, -2.8762502430157117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5369665434085289, 0.8100484778689586, 1.1873008984865836, -1.1872374571208901, -2.202974145462632, -0.47528744564920095, 1.5011974420998633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961062340045, -0.44034090298211515, 0.02485051238883319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.674798886404033e-05, 0.00026964094725063224, -5.999399986235081e-05, 0.0, 0.0003412610223343902, 0.0001374577795425186, 4.2224859239858586e-05, 0.0004274079409619088, -7.673717465437287e-06, -0.00024320222339622167, -0.00014900518248552445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015698562435060924, 0.03780084550136615, -0.08198450261439016, -0.003992212321361882, 0.00446280196632445, 0.04073932596792761, 0.06553397259719447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.425557552529118e-09, -6.770956109758903e-09, -0.000292499723498149]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092496254561651, 0.23429471621174008, 0.8410070818992268, 0.0, -0.12513988917033175, -0.24483220114101195, -2.6083117354932526, -0.7142465662167454, -0.5580748787203342, -1.1981081230145345, -2.876257672920959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5361709421772896, 0.8119384662083703, 1.1831885815751473, -1.1874392290545575, -2.2027668457589105, -0.47324687428874174, 1.5044913358973206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961060191408, -0.4403409033193899, 0.024835867359076832]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6523631009647197e-05, 0.00027000418378232623, 1.7986379055652413e-05, 0.0, 0.00034137375841914824, 0.0001317501418588057, 4.38644058126588e-05, 0.000428104465546681, -9.440060369282882e-06, -0.00024359678659280064, -0.00014859810494164313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01591202462478672, 0.03779976678823284, -0.082246338228728, -0.004035438673345594, 0.004145994074430361, 0.04081142720918442, 0.06587787594914715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.2972752186325556e-09, -6.745495156767535e-09, -0.0002929005951271798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924881037954635, 0.23430823941628123, 0.8410104805760512, 0.0, -0.12512278443502178, -0.24482522520652472, -2.6083095683298225, -0.7142251228420964, -0.5580753276019556, -1.1981203016818394, -2.876265125001612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5353648890732149, 0.8138276562638193, 1.1790646163154206, -1.1876431018294107, -2.2025757636634418, -0.47120347108002103, 1.507801477500176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961058005932, -0.4403409036557102, 0.02482119775785553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6301532375350888e-05, 0.00027046409082271354, 6.797353648898557e-05, 0.0, 0.00034209470619956105, 0.00013951868974477018, 4.334326859974839e-05, 0.0004288674929802702, -8.977632425557614e-06, -0.00024357334609904135, -0.00014904161305743515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016121062081492537, 0.037783801108978735, -0.08247930519453568, -0.004077455497066453, 0.0038216419093723523, 0.04086806417441358, 0.0662028320571086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.370951473633228e-09, -6.7264061167353235e-09, -0.00029339202442599564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924800703709684, 0.23432179057086786, 0.8410220134799768, 0.0, -0.1251056348788504, -0.24481791065265449, -2.608307439769383, -0.7142036343470946, -0.5580757402627518, -1.1981324793969663, -2.876272606590669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5345486301753641, 0.815715283537283, 1.174930509137666, -1.187849009680018, -2.202401260338183, -0.46915803691662905, 1.511126864406344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961055784995, -0.44034090399110765, 0.024806498730338414]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6066848990084677e-05, 0.000271023091732647, 0.0002306580785137615, 0.0, 0.0003429911234276098, 0.00014629107740476386, 4.2571208786319135e-05, 0.00042976990003583957, -8.253215924271817e-06, -0.00024355430253760203, -0.00014963178114351563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01632517795701424, 0.037752545469273785, -0.08268214355509021, -0.00411815701214592, 0.003490066505177751, 0.040908683267839405, 0.06650773812336223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.441875061750068e-09, -6.707948679834676e-09, -0.0002939805503423458]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924721542543817, 0.23433537370842256, 0.8410361863605892, 0.0, -0.12508843718601376, -0.24481039522159975, -2.608305342609468, -0.7141820942853051, -0.5580761239398435, -1.1981446603147465, -2.8762801172878922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5337223806981956, 0.8176006922550547, 1.1707875488863044, -1.1880568938312568, -2.202243664018041, -0.46711126031023903, 1.5144666613670423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961053527348, -0.4403409043256543, 0.024791766155124875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5832233173576852e-05, 0.0002716627510938502, 0.00028345761224643766, 0.0, 0.0003439538567329903, 0.0001503086210947443, 4.194319830212943e-05, 0.000430801235789004, -7.673541835312326e-06, -0.00024361835560364367, -0.00015021394446600118, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01652498954337114, 0.037708174355435345, -0.08285920502723475, -0.004157683024774714, 0.0031519264028380908, 0.040935532127800434, 0.06679593921396432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.515292675017828e-09, -6.690933603425866e-09, -0.00029465150427082805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924643533830425, 0.2343489912932732, 0.8410488218063917, 0.0, -0.12507119063353525, -0.2448027929086804, -2.6083032659665797, -0.7141604982942021, -0.558076489693346, -1.1981568485621175, -2.8762876545351124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5328862835321865, 0.8194834221540722, 1.1666366132028636, -1.1882667114267673, -2.2021032639672424, -0.4650636217414324, 1.5178203558558363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961051233105, -0.4403409046594021, 0.024776997345098726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5601742678380886e-05, 0.0002723516970125972, 0.0002527089160520015, 0.0, 0.00034493104957015075, 0.00015204625838715168, 4.153285776985821e-05, 0.000431919822058675, -7.315070048949514e-06, -0.0002437649474163956, -0.00015074494440707218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0167219433201824, 0.03765459798034946, -0.08301871366881823, -0.004196351910210223, 0.002808001015978366, 0.04095277137613264, 0.06707388977588098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.588484374229094e-09, -6.674955954323654e-09, -0.0002953762005229549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924566647408677, 0.2343626439628206, 0.8410582188776666, 0.0, -0.12505389614320422, -0.2447951709450306, -2.6083012010642563, -0.7141388447389879, -0.5580768464749206, -1.198169046739875, -2.876295215589466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5320403872014193, 0.8213632450124095, 1.1624780814579907, -1.1884784401226691, -2.2019803143826557, -0.46301535181210113, 1.5211878305426285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196104890307, -0.4403409049923652, 0.02476219137471044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5377284349828743e-05, 0.0002730533909486646, 0.00018794142549695913, 0.0, 0.0003458898066202609, 0.00015243927299610655, 4.129804646886761e-05, 0.0004330711042844184, -7.135631492355292e-06, -0.0002439635551490929, -0.00015122108707033406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016917926615343505, 0.03759645716674715, -0.08317063489745692, -0.004234573918034956, 0.002458991691729575, 0.04096539858662546, 0.0673494937358462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.660066937348196e-09, -6.659262154159706e-09, -0.00029611940776575553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924490848327904, 0.23437633061949292, 0.8410560835309228, 0.0, -0.12503655431277882, -0.24478752010214577, -2.6082991495782464, -0.7141171348764142, -0.5580771925424345, -1.1981812541074885, -2.8763028006481965, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5311846441002754, 0.8232401533797046, 1.1583118511849793, -1.1886920782222765, -2.201875045276336, -0.4609664411809146, 1.524569354157154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961046486924, -0.44034090532473663, 0.024747349055800713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.515981615443592e-05, 0.0002737331334461661, -4.2706934877010327e-05, 0.0, 0.0003468366085082563, 0.0001530168576964341, 4.102972019804011e-05, 0.0004341972514756301, -6.921350278078256e-06, -0.0002441473522719288, -0.0001517011746054956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017114862022878714, 0.037538167345899924, -0.08332460546022809, -0.004272761992147246, 0.0021053821263965393, 0.04097821262373043, 0.0676304722905131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.8322945298618424e-09, -6.647428706090912e-09, -0.00029684637819448666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924416111709013, 0.23439004885222628, 0.8410461448202162, 0.0, -0.12501916851060207, -0.24477986099661353, -2.608297108373726, -0.7140953718715477, -0.5580775311962143, -1.1981934700527117, -2.8763104073626153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5303189263193195, 0.8251143119355534, 1.1541374375979159, -1.1889076410571624, -2.2017876764519566, -0.458916691640201, 1.527965505878348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961043974682, -0.44034090565650524, 0.024732472576478384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.494732377830591e-05, 0.00027436465466719494, -0.0001987742141298727, 0.0, 0.00034771604353479976, 0.00015318211064475697, 4.082409040750608e-05, 0.0004352600973289408, -6.773075596842037e-06, -0.0002443189044638289, -0.0001521342883787291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017314355619117806, 0.03748317111697732, -0.0834882717412666, -0.004311256697716052, 0.0017473764875824422, 0.0409949908142728, 0.06792303442387358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.024482560456021e-09, -6.6353721321817925e-09, -0.0002975295864465577]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092434241898101, 0.23440379548519505, 0.8410332845986868, 0.0, -0.12500174317378177, -0.24477220846572847, -2.608295074172032, -0.7140735601679984, -0.5580778659557126, -1.1982056933796754, -2.876318032849949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5294430534430056, 0.8269859865684598, 1.1499541243889762, -1.189125154817421, -2.2017184311773126, -0.45686579217268836, 1.5313770578414172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961041372786, -0.4403409059875701, 0.024717564985329347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4738545600715052e-05, 0.0002749326593754455, -0.0002572044305889292, 0.0, 0.00034850673640610146, 0.0001530506177013048, 4.068403387558512e-05, 0.0004362340709858327, -6.695189967279231e-06, -0.00024446653927346663, -0.00015250974666713418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01751745752627855, 0.037433492658127586, -0.08366626417879379, -0.004350275205172314, 0.0013849054928832506, 0.04101798935025297, 0.0682310392613842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.20379147070437e-09, -6.6212970787305426e-09, -0.0002981518229807454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924269768571976, 0.23441756723256021, 0.8410211936055637, 0.0, -0.12498428656625127, -0.24476466142210812, -2.6082930282445553, -0.7140517040554214, -0.5580782163099339, -1.1982179260165966, -2.876325668360499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5285568258487621, 0.8288554673713606, 1.1457611312938534, -1.1893446493034172, -2.2016675466270863, -0.4548134026388708, 1.5348048426790608, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196103873076, -0.44034090631767464, 0.024702629546660564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4530081806884725e-05, 0.0002754349473032083, -0.00024181986246085216, 0.0, 0.0003491321506098486, 0.00015094087240714833, 4.091854953169874e-05, 0.00043712225154075634, -7.007084426564443e-06, -0.0002446527384237837, -0.00015271021099671814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017724551884869048, 0.03738961605801727, -0.08385986190245388, -0.004389889719921877, 0.0010176910045214236, 0.041047790676350795, 0.06855569675287329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.284054276865303e-09, -6.602091496072119e-09, -0.00029870877337561573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924198163869062, 0.2344313611202062, 0.8410122464977837, 0.0, -0.12496680663473403, -0.2447572764006, -2.608290952109812, -0.7140298075149323, -0.5580786015168077, -1.1982301698893667, -2.8763333053410314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5276600565197247, 0.8307230000548407, 1.141557766052324, -1.1895661509740727, -2.2016352798132326, -0.45275922901337, 1.5382496319416816, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961036089454, -0.44034090664660797, 0.024687669311053716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4320940582745845e-05, 0.00027587775291998173, -0.0001789421555994827, 0.0, 0.000349598630344771, 0.00014770043016274956, 4.152269486684434e-05, 0.0004379308097814693, -7.704137474671007e-06, -0.0002448774554009283, -0.00015273961065152483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017935386580748176, 0.03735065366960045, -0.08406730483058789, -0.004430033413108865, 0.0006453362770783385, 0.04108347251001572, 0.0688957852524162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.282608769722518e-09, -6.578666193878617e-09, -0.00029920471213696226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924127625602892, 0.2344451748886894, 0.8410079530709207, 0.0, -0.12494931498664277, -0.244750168298184, -2.6082888080760194, -0.7140078729634463, -0.5580790606308612, -1.1982424314263758, -2.8763409284529082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5267525963935548, 0.8325887363924743, 1.1373435371498235, -1.1897896775209689, -2.2016219084821045, -0.4507030786006588, 1.5417120444288943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961033496475, -0.4403409069741575, 0.02467268668987216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4107653234047511e-05, 0.00027627536966383934, -8.58685372608118e-05, 0.0, 0.00034983296182516905, 0.00014216204832000084, 4.288067585132707e-05, 0.0004386910297200211, -9.182281072144481e-06, -0.0002452307401810137, -0.0001524622375366768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018149202523398262, 0.0373147267526732, -0.08428457805000901, -0.004470530937921876, 0.00026742662256651394, 0.04112300825422484, 0.06924824974425506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.1859567260439755e-09, -6.5509905493119906e-09, -0.00029965242363114023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092405814221847, 0.23445900711925993, 0.8410076193949413, 0.0, -0.12493180308159409, -0.24474297271213807, -2.6082866415957042, -0.7139859042924999, -0.5580795469753796, -1.1982546995110912, -2.876348553631648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5258343494031532, 0.8344527092342277, 1.1331182132852262, -1.1900152349403026, -2.2016277287256725, -0.44864488862339164, 1.5451924969752042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961030939942, -0.440340907300321, 0.024657683298567584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3896676884206326e-05, 0.0002766446114107791, -6.67351958730456e-06, 0.0, 0.0003502381009738575, 0.0001439117209183849, 4.3329606299553536e-05, 0.00043937341892728914, -9.726890369524963e-06, -0.000245361694308613, -0.0001525035747982607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01836493980803164, 0.037279456835067414, -0.08450647729194553, -0.004511148386673094, -0.00011640487135941536, 0.04116379954534321, 0.06960905092619887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.113067642888294e-09, -6.523269362194304e-09, -0.0003000678260915194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923989737066429, 0.23447285729849482, 0.8410173949544465, 0.0, -0.12491426032710078, -0.2447354537589122, -2.608284502251769, -0.71396390406394, -0.5580800095622412, -1.198266962763555, -2.8763561988785353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5249052765248465, 0.8363148320871545, 1.1288818293044027, -1.1902428166137695, -2.201653048920596, -0.4465847280576006, 1.5486911968215638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961028376508, -0.44034090762510103, 0.024642659859163866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3681030408542761e-05, 0.00027700358469752445, 0.00019551119010394067, 0.0, 0.0003508550898663204, 0.00015037906451729831, 4.27868787103912e-05, 0.00044000457119782273, -9.251737232382818e-06, -0.00024526504927672977, -0.00015290493773938857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018581457566134493, 0.03724245705853732, -0.08472767961646975, -0.004551633469339973, -0.0005064038984640953, 0.041203211315821324, 0.06997399692719035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.126869319532842e-09, -6.495600528856092e-09, -0.0003004687880743624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092392244501384, 0.234486725664656, 0.8410311200160856, 0.0, -0.12489668545552522, -0.24472768583321533, -2.6082823951474987, -0.7139418722212836, -0.5580804432043482, -1.1982792199698034, -2.8763638661337536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5239653889266263, 0.8381749203751567, 1.1246346429876275, -1.1904724048381408, -2.201698183225296, -0.4445227753775335, 1.5522081740767828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961025786713, -0.4403409079485101, 0.024627616319695567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3458410517791e-05, 0.0002773673232235325, 0.00027450123278138414, 0.0, 0.0003514974315111833, 0.00015535851393738803, 4.214208540367673e-05, 0.00044063685312759504, -8.672842140828888e-06, -0.0002451441249686973, -0.00015334510436367145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018797751964405293, 0.037201765760044934, -0.08494372633550343, -0.004591764487425716, -0.0009026860940070896, 0.041239053601341294, 0.07033954510438059, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.179590171708666e-09, -6.4681820872776385e-09, -0.00030087078936595537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092385628245801, 0.23450061290819943, 0.841043974989202, 0.0, -0.12487907955192709, -0.24471978613250056, -2.6082803126668055, -0.7139198076214038, -0.5580808557941545, -1.1982914729840688, -2.87637155287179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5230147331040501, 0.840032726778139, 1.1203770586254933, -1.1907039742031829, -2.201763446439512, -0.44245928030608556, 1.555743342117177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961023164102, -0.4403409082705559, 0.024612552136522255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3232511166461702e-05, 0.0002777448708686309, 0.0002570994623296304, 0.0, 0.0003521180719626334, 0.00015799401429511677, 4.164961386793083e-05, 0.0004412919975958298, -8.251796124645198e-06, -0.0002450602853071114, -0.00015373476072257683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01901311645152213, 0.0371561280596449, -0.08515168724268607, -0.004631387300841511, -0.0013052642843153798, 0.04126990142895847, 0.07070336080788225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.245223065171383e-09, -6.440916079248447e-09, -0.000301283663466211]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923791258923294, 0.23451451984754135, 0.841053839335408, 0.0, -0.124861443738691, -0.24471183909284877, -2.6082782461560727, -0.7138977088744598, -0.5580812562752453, -1.198303724005304, -2.876379256266048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5220533722188224, 0.8418879814421235, 1.1161095379235029, -1.1909374956665297, -2.201849150615711, -0.4403945196928669, 1.5592965689997291, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196102050767, -0.44034090859124075, 0.024597466590461522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3004706942721193e-05, 0.0002781387868381211, 0.00019728692411996905, 0.0, 0.00035271626472192926, 0.00015894079303583724, 4.1330214656937515e-05, 0.00044197493888114875, -8.009621817293962e-06, -0.0002450204247059355, -0.00015406788515755283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019227217704553823, 0.03710509327968975, -0.0853504140398068, -0.004670429266939552, -0.0017140835239768332, 0.041295212264373216, 0.0710645376510457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.312866158655143e-09, -6.413697667347336e-09, -0.0003017109212146423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923727385304727, 0.2345284471820798, 0.8410522138073605, 0.0, -0.12484378254230989, -0.24470398536804427, -2.6082761725991963, -0.7138755742604499, -0.5580816683877518, -1.1983159783207948, -2.876386968121842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5210813675425818, 0.8437404292008875, 1.111832515911148, -1.191172940537945, -2.2019556038910966, -0.4383287562399933, 1.56286774570927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961017818023, -0.44034090891060784, 0.024582359033059612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2774723713286888e-05, 0.00027854669076925285, -3.251056095003856e-05, 0.0, 0.00035322392762227256, 0.00015707449608995283, 4.147113752742501e-05, 0.0004426922801981734, -8.242250128389216e-06, -0.0002450863098167964, -0.00015423711587763197, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01944009352481135, 0.03704895517528012, -0.08554044024709782, -0.004708897428303273, -0.002129065507710266, 0.04131526905747279, 0.07142353419081342, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.379290814927804e-09, -6.3873414308310886e-09, -0.000302151148038187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092366466504449, 0.2345423951962035, 0.8410434472930469, 0.0, -0.12482610237027067, -0.2446963384501182, -2.6082740628509478, -0.7138534024818921, -0.5580821222057958, -1.1983282422944421, -2.8763946777497114, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5200987630336469, 0.8455898577733169, 1.107546335549563, -1.1914102836995266, -2.2020831116149004, -0.4362622067468347, 1.566456840158064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961015123277, -0.44034090922857455, 0.024567229195095627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2544052047728873e-05, 0.0002789602824744588, -0.00017533028627138354, 0.0, 0.00035360344078455975, 0.000152938358521538, 4.2194964967829366e-05, 0.0004434355711551118, -9.0763608804408e-06, -0.000245279472945569, -0.00015419255739288778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019652090178698466, 0.03698857144858722, -0.08572360723169974, -0.004746863231634872, -0.002550154476074551, 0.04133098986317244, 0.07178188897588188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.389492783145938e-09, -6.359334203315072e-09, -0.0003025967592796801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923603119785542, 0.23455636366143515, 0.8410353019987932, 0.0, -0.1248084242584862, -0.24468923095470801, -2.6082718269296277, -0.713831191059617, -0.5580827105398091, -1.1983405351414187, -2.876402351621198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.519105575620468, 0.8474361134617115, 1.1032512099441503, -1.1916495054977405, -2.202231978612754, -0.4341950240570607, 1.5700639289912093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961012491604, -0.4403409095449165, 0.024552077293800822]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2309051789507755e-05, 0.00027936930463274916, -0.00016290588507396475, 0.0, 0.00035356223568931217, 0.00014214990820386725, 4.471842639831812e-05, 0.00044422844550102134, -1.1766680265442813e-05, -0.00024585693952967403, -0.00015347742973165416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019863748263576935, 0.03692511376789492, -0.08590251210825339, -0.004784435964277944, -0.0029773399570713964, 0.04134365379548046, 0.07214177666290271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.26334369806623e-09, -6.326839330366228e-09, -0.00030303802589605624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092354267738185, 0.2345703517593418, 0.841037086357163, 0.0, -0.12479072675782128, -0.24468196978950849, -2.608269562166431, -0.71380894456449, -0.5580833331616019, -1.1983528350359811, -2.87641002529331, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5181017919564832, 0.8492791034645827, 1.0989472139222365, -1.1918905930169712, -2.2024025140696923, -0.4321272937656738, 1.5736892075793183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961010055812, -0.4403409098589737, 0.02453690412215113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2088480738122096e-05, 0.0002797619581327564, 3.568716739713108e-05, 0.0, 0.0003539500132983976, 0.00014522330399074646, 4.529526392674975e-05, 0.0004449299025413268, -1.2452435856533942e-05, -0.00024599789125044413, -0.0001534734422348367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020075673279695384, 0.03685980005742207, -0.08607992043827516, -0.004821750384614016, -0.003410709138764685, 0.04135460582773689, 0.07250557176218154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.871585243622658e-09, -6.281143838603349e-09, -0.0003034634329938299]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923483351000108, 0.23458435821041387, 0.8410433690732536, 0.0, -0.1247729928187537, -0.24467419120495768, -2.6082673488459154, -0.7137866672064415, -0.5580839074054937, -1.198365123797158, -2.87641772791869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5170873720815716, 0.85111878546559, 1.0946343060215737, -1.192133538432852, -2.202595032702884, -0.43005904517215826, 1.5773329717200524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961007619495, -0.4403409101713919, 0.024521710933646846]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1865276348927471e-05, 0.0002801290214417316, 0.00012565432181280977, 0.0, 0.00035467878135150756, 0.0001555716910162052, 4.4266410315425116e-05, 0.0004455471609690459, -1.1484877837322644e-05, -0.00024577522353742175, -0.0001540525076079574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020288397498231026, 0.0367936400201483, -0.0862581580132528, -0.00485890831761699, -0.003850372663837832, 0.04136497187031095, 0.07287528281468234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.872635981013225e-09, -6.248363731130677e-09, -0.00030386377008570877]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923425164787207, 0.2345983814792764, 0.841050347506695, 0.0, -0.12475522292646406, -0.24466603816082416, -2.6082651926888545, -0.713764361211254, -0.5580844274851053, -1.1983773992061868, -2.876425460844925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5160622570306792, 0.8529551512103469, 1.09031236495632, -1.1923783374825825, -2.2028098565664673, -0.4279902694218642, 1.5809955887759293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961005111467, -0.4403409104823721, 0.02450649925825024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.163724258027144e-05, 0.0002804653772501444, 0.0001395686688296028, 0.0, 0.0003553978457929012, 0.0001630608826704875, 4.312314121554707e-05, 0.0004461199037493099, -1.0401592232705189e-05, -0.0002455081805767086, -0.00015465852470114935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02050230101784817, 0.03672731489513667, -0.08643882130507669, -0.004895980994609451, -0.004296477271664276, 0.041375515005881276, 0.073252341117538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.0160564280701034e-09, -6.219605362174422e-09, -0.0003042335079320552]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092336812073117, 0.23461241991371726, 0.8410561678621937, 0.0, -0.12473742219781848, -0.24465770728454195, -2.6082630802066746, -0.7137420285191424, -0.5580849074418099, -1.198389663027904, -2.8764332181693337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5150263785751835, 0.8547882069357311, 1.0859812336661037, -1.1926249875088784, -2.2030473162083246, -0.4259209411969448, 1.5846774624480346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961002514438, -0.44034091079192145, 0.024491270776937437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1408811207364125e-05, 0.0002807686888172977, 0.00011640710997282274, 0.0, 0.00035601457291151454, 0.00016661752564447262, 4.224964359557917e-05, 0.0004466538422316748, -9.599134091982837e-06, -0.0002452764343438294, -0.0001551464881691109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020717569109913524, 0.03666111450768433, -0.08662262580432678, -0.004933000525917938, -0.0047491928371491505, 0.041386564498387415, 0.07363747344210625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.194058572993528e-09, -6.190986860384029e-09, -0.00030456962625612414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092331222669531, 0.23462647193549757, 0.841052066079572, 0.0, -0.12471959924255467, -0.24464941954873765, -2.608260982624077, -0.713719670597397, -0.55808537708744, -1.1984019203027907, -2.8764409883123934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5139796698170055, 0.8566179539149585, 1.0816407643975692, -1.1928734852410094, -2.203307750057057, -0.4238510406151482, 1.5883789956931182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960999830891, -0.44034091110001405, 0.02447602713313368]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1178807172321633e-05, 0.00028104043560611415, -8.203565243488869e-05, 0.0, 0.00035645910527626145, 0.00016575471608629082, 4.195165195554541e-05, 0.00044715843490582383, -9.392912601900415e-06, -0.00024514549773298693, -0.00015540286119064626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02093417516356161, 0.03659493958454977, -0.08680938537068913, -0.004969954642621503, -0.005208676974652198, 0.04139801163593095, 0.07403066490167189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.367093402234195e-09, -6.1618522748371104e-09, -0.0003048728760751354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923257491223984, 0.23464053609047267, 0.8410419055366319, 0.0, -0.12470176364589647, -0.24464133781230815, -2.6082588665282125, -0.7136972887095854, -0.5580858710249742, -1.1984141770704049, -2.8764487579958957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5129220742543645, 0.8584443728070699, 1.077290855772315, -1.1931238248543903, -2.2035915028096063, -0.42178057102604194, 1.5921005596733184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960997096226, -0.440340911406489, 0.024460769881989263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0947094264936601e-05, 0.00028128309950176415, -0.0002032108588002307, 0.0, 0.00035671193316402056, 0.00016163472858988137, 4.232191728334855e-05, 0.0004476377562333042, -9.878750685222405e-06, -0.0002451353522834519, -0.00015539367005093068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021151911252818414, 0.03652837784222549, -0.08699817250508257, -0.005006792267617171, -0.005675055050982058, 0.04140939178212616, 0.07443127960400155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.469333852017078e-09, -6.129498761064716e-09, -0.00030514502288832664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923203945074248, 0.234654611139149, 0.8410329760044956, 0.0, -0.12468393783006151, -0.24463381737345521, -2.608256641870117, -0.7136748820675878, -0.5580864822372624, -1.1984264517189394, -2.876456493033111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5118535520675944, 0.86026741417937, 1.0729314763532303, -1.193375996563004, -2.2038989229339174, -0.4197095700785597, 1.59584247316251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960994386653, -0.4403409117110504, 0.024445500384940443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0709229947061336e-05, 0.0002815009735270556, -0.00017859064272867818, 0.0, 0.0003565163166989832, 0.00015040877705849477, 4.449316191303092e-05, 0.000448132839952295, -1.2224245764281534e-05, -0.00024549297069120405, -0.0001547007443032467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0213704437354033, 0.036460827446003485, -0.08718758838169695, -0.005043434172273638, -0.0061484024862227945, 0.041420018949645344, 0.07483826978383265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.41914580147142e-09, -6.091227530342086e-09, -0.00030538994097642047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923151539108384, 0.23466869601465398, 0.8410369603092293, 0.0, -0.12466610730241652, -0.24462629384666287, -2.6082543779253315, -0.7136524549442156, -0.5580871394853086, -1.1984387281294149, -2.876464218332244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5107740827551385, 0.8620869957374822, 1.0685626721506054, -1.1936299866938658, -2.2042303620937327, -0.41763811324967404, 1.5996049968703707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960991865436, -0.44034091201287073, 0.024430219834777226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0481193173066671e-05, 0.0002816975100991661, 7.968609467351684e-05, 0.0, 0.00035661055289996446, 0.00015047053584673302, 4.5278895708661466e-05, 0.0004485424674445845, -1.3144960923647588e-05, -0.0002455282095096486, -0.00015450598266201668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02158938624911852, 0.03639163116224268, -0.08737608405249829, -0.005079802617235855, -0.006628783196301097, 0.04142913657771301, 0.07525047415721449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.042432717502845e-09, -6.0364069223755525e-09, -0.0003056110032643384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923100283255752, 0.23468278982685334, 0.8410444950602779, 0.0, -0.12464825226265315, -0.24461829692062967, -2.6082521656327224, -0.713630011550289, -0.5580877491526708, -1.198450985861604, -2.8764719670998957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5096836649634202, 0.8639030045311199, 1.0641845631582998, -1.1938857771391707, -2.2045861721409685, -0.4155663116254859, 1.603388334133879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960989332096, -0.44034091231267136, 0.024414929235849793]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0251170526505469e-05, 0.00028187624398724346, 0.0001506950209727834, 0.0, 0.00035710079526729164, 0.00015993852066417723, 4.4245852182918864e-05, 0.0004488678785303976, -1.219334724283644e-05, -0.00024515464378050837, -0.0001549753530299669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021808355834365044, 0.03632017587275478, -0.08756217984611223, -0.005115808906095752, -0.007116200944715079, 0.041436032483762424, 0.07566674527016634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.066679126741525e-09, -5.996012086212419e-09, -0.00030581197854868307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923050216204658, 0.23469689186915452, 0.8410516616188889, 0.0, -0.12463037171473912, -0.24460994079275783, -2.6082500133720026, -0.7136075531239947, -0.5580883027034881, -1.1984632225123395, -2.8764797420544017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5085823128939614, 0.8657153051896176, 1.0597973256827151, -1.194143346163699, -2.2049667038536658, -0.4134943030747915, 1.6071926446615838, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196098671681, -0.44034091261067837, 0.024399629399881436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0013410218914426e-05, 0.00028204084602383465, 0.00014333117222068478, 0.0, 0.00035761095828053827, 0.00016712255743682876, 4.304521440058582e-05, 0.0004491685258869663, -1.1071016345658088e-05, -0.0002447330147117217, -0.00015549909012203795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022027041389176896, 0.03624601316995274, -0.08774474951169516, -0.0051513804905646155, -0.007610634253944473, 0.041440171013887465, 0.07608621055409705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.230571128178997e-09, -5.960140387646349e-09, -0.0003059967193671177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923001346662412, 0.23471100150640223, 0.8410570992865238, 0.0, -0.124612469576945, -0.24460141530682628, -2.6082479078840874, -0.7135850801968361, -0.5580888139089831, -1.1984754403653106, -2.876487537895516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5074700501760492, 0.867523751218759, 1.0554011660280609, -1.1944026698833945, -2.2053723078435907, -0.4114222395388834, 1.6110180667421843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960984004842, -0.440340912906907, 0.024384321059351226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.77390844932557e-06, 0.0002821927449540467, 0.000108753352697927, 0.0, 0.00035804275588250685, 0.00017050971863127144, 4.210975830491218e-05, 0.0004494585431732285, -1.0224109900509904e-05, -0.0002443570594232101, -0.0001559168222916129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022245254358245144, 0.036168920582829035, -0.08792319309308277, -0.005186474393909225, -0.008112079798501207, 0.04144127071816173, 0.07650844161200956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.423937811173064e-09, -5.924572664479066e-09, -0.0003061668106041999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092295368781185, 0.23472511812237018, 0.8410525567244167, 0.0, -0.12459455539927589, -0.24459298694859025, -2.608245811408167, -0.7135625925579099, -0.5580893217995248, -1.1984876469894246, -2.876495340225951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5063469036469429, 0.8693281958882545, 1.0509962948414044, -1.1946637235971365, -2.205803335645199, -0.40935027469185803, 1.6148647387961867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960981211883, -0.440340913201293, 0.024369004918805077]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.531770112582698e-06, 0.0002823323193592111, -9.085124214319048e-05, 0.0, 0.0003582835533821116, 0.00016856716472041987, 4.192951841072784e-05, 0.00044975277852422565, -1.0157810831525628e-05, -0.0002441324822768575, -0.00015604660869718368, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02246293058212572, 0.03608889338990902, -0.08809742373312995, -0.005221074274839436, -0.008620556032167825, 0.04143929694050713, 0.07693344108004997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.585919470088617e-09, -5.8877196347280575e-09, -0.00030632281092298554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922907254402637, 0.23473924097755533, 0.8410430468096177, 0.0, -0.12457664465750391, -0.24458494204825634, -2.6082436611804063, -0.7135400894695607, -0.558089891193906, -1.1984998552367652, -2.8765031252828543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5052128977614048, 0.871128501107967, 1.0465829055964682, -1.194926482883499, -2.2062601412752496, -0.4072785536904651, 1.6187328177432267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960978396832, -0.44034091349359755, 0.024353681801970777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.286681842308948e-06, 0.00028245710370275603, -0.00019019829597943813, 0.0, 0.00035821483543939294, 0.00016089800667815171, 4.3004555210236635e-05, 0.0004500617669834312, -1.1387887624443933e-05, -0.00024416494681227545, -0.00015570113806031218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022680117710762223, 0.03600610439425101, -0.08826778489872511, -0.005255185727246861, -0.009136112601008644, 0.04143442002785773, 0.07736157894079969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.630101619651346e-09, -5.8460912789013415e-09, -0.00030646233668602126]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092286203029788, 0.2347533691199173, 0.8410366097666756, 0.0, -0.12455873906782257, -0.24457712016806227, -2.608241455221437, -0.7135175725101464, -0.5580905242752763, -1.1985120646248903, -2.876510891702536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5040680507202013, 0.872924542990264, 1.042161160418863, -1.1951909245602055, -2.2067430834685604, -0.40520720662076, 1.6226224919949306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960975589218, -0.4403409137837116, 0.02433835273812638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.044820950828083e-06, 0.00028256284723898446, -0.00012874085884307046, 0.0, 0.00035811179362700286, 0.00015643760388143953, 4.411917938666845e-05, 0.0004503391882867604, -1.2661627407282987e-05, -0.00024418776250376096, -0.00015532839362946262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022896940824068145, 0.03592083764594023, -0.08843490355210347, -0.00528883353413279, -0.009658843866211879, 0.0414269413941024, 0.0777934850340786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6152266013673606e-09, -5.802281156345202e-09, -0.0003065812768879271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922817994548892, 0.23476750143913333, 0.8410317368181572, 0.0, -0.12454082133663524, -0.24456902851836237, -2.6082392747393492, -0.713495046101068, -0.5580911374821886, -1.1985242565890923, -2.87651866889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5029123732057359, 0.8747162132660619, 1.0377311860746754, -1.1954570270293148, -2.207252526997856, -0.40313634677010934, 1.6265339855381478, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960972813505, -0.4403409140713817, 0.024323018905498428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.807149797687654e-06, 0.0002826463843210159, -9.74589703665631e-05, 0.0, 0.0003583546237463803, 0.00016183299399782965, 4.360964175396415e-05, 0.00045052818156762596, -1.2264138246990007e-05, -0.0002438392840411457, -0.00015554380207734861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02311355028930857, 0.035833405515955936, -0.0885994868837508, -0.005322049382186002, -0.010188870585910479, 0.04141719701301333, 0.07822987086434155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5514245871595604e-09, -5.753402196005454e-09, -0.000306676652559026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922775208871658, 0.23478163673089025, 0.8410269189424823, 0.0, -0.12452290749927553, -0.2445610802733366, -2.60823705671734, -0.7134725099597611, -0.5580917959042532, -1.1985364438454809, -2.876526432828552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5017458688935809, 0.876503417771528, 1.0332930775127567, -1.1957247695296482, -2.2077888417223948, -0.4010660722071327, 1.6304675538598268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196097005762, -0.44034091435659856, 0.02430768157447591]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.557135447079631e-06, 0.00028270583513837535, -9.63575134987599e-05, 0.0, 0.00035827674719448194, 0.00015896490051578013, 4.4360440186066256e-05, 0.00045072282613815867, -1.3168441291317371e-05, -0.00024374512776992012, -0.00015527871823862847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023330086243100588, 0.03574409010932276, -0.08876217123837545, -0.005354850006668302, -0.010726294490778453, 0.041405491259532884, 0.07867136643357993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5117697080917796e-09, -5.704337183720439e-09, -0.00030674662045039944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092273364795529, 0.23479577360256368, 0.8410267217978544, 0.0, -0.12450499913756155, -0.2445531912725162, -2.6082348019596893, -0.7134499663025892, -0.5580924988772874, -1.1985486250627273, -2.876534182971404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5005685356159986, 0.8782860735546842, 1.0288469036469596, -1.1959941324338006, -2.2083524046662615, -0.3989964689225732, 1.6344234810585367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960967315432, -0.44034091463937164, 0.024292342210012866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.31218327346479e-06, 0.00028273743346835396, -3.942892555852602e-06, 0.0, 0.000358167234279383, 0.00015778001640777447, 4.50951530158411e-05, 0.0004508731434375434, -1.4059460683804483e-05, -0.00024362434492997581, -0.00015500285704769982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02354666555164614, 0.03565311566312634, -0.08892347731593916, -0.005387258083048048, -0.011271258877333048, 0.04139206569119055, 0.07911854397420086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4843783973253375e-09, -5.655461688257759e-09, -0.00030678728926084454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092269328669074, 0.2348099105758585, 0.8410328085718266, 0.0, -0.12448707681038215, -0.2445448705057502, -2.608232602889105, -0.7134274203571955, -0.5580931513025706, -1.1985607790395163, -2.876541952707773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4993803688712595, 0.880064103097541, 1.0243927211786348, -1.1962650965612587, -2.208943599389502, -0.3969276174649741, 1.6384020683100775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960964513507, -0.440340914919795, 0.02427700236992856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.072252910155402e-06, 0.00028273946589653745, 0.00012173547944455026, 0.0, 0.00035844654358794566, 0.0001664153353203612, 4.398141168845759e-05, 0.00045091890787210125, -1.3048505665113734e-05, -0.00024307953578067693, -0.00015539472737960248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023763334894781794, 0.03556059085713516, -0.08908364936649825, -0.005419282549162722, -0.011823894464809255, 0.04137702915198115, 0.07957174503081545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6038510622082095e-09, -5.608466697218602e-09, -0.00030679680168615704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922654166067067, 0.23482404617815011, 0.8410412273442239, 0.0, -0.12446914038951988, -0.24453622390550075, -2.608230468085501, -0.7134048745361499, -0.5580937444931828, -1.1985729027930856, -2.876549744394196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49818136574451966, 0.8818374283976583, 1.019930589651557, -1.1965376419472014, -2.2095628134221337, -0.3948595998606208, 1.6424036197278522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960961632773, -0.44034091519783325, 0.024261663614724982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.824124734902576e-06, 0.0002827120458322431, 0.0001683754479456738, 0.0, 0.0003587284172453867, 0.00017293200498848488, 4.2696072079051175e-05, 0.00045091642091311116, -1.1863812242775575e-05, -0.00024247507138728597, -0.00015583372845762609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023980062534796138, 0.035466506002346784, -0.08924263054155514, -0.00545090771885237, -0.012384280652634735, 0.04136035208706627, 0.08003102835549275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.761465067164659e-09, -5.5607647810329235e-09, -0.00030677510407153255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922616295505392, 0.23483817896123738, 0.8410490852513846, 0.0, -0.12445119489880907, -0.24452743829899679, -2.6082283837711637, -0.7133823305847966, -0.5580942928161348, -1.198584998145203, -2.8765575520800817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4969715275917248, 0.8836059669803608, 1.0154605812500674, -1.196811747499963, -2.2102104377362424, -0.39279250428916135, 1.6464284343560336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095867687, -0.44034091547339604, 0.024246327492719974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.574112335228865e-06, 0.0002826556617451584, 0.00015715814321276875, 0.0, 0.00035890981421632693, 0.00017571213007928167, 4.1686286744317405e-05, 0.0004508790270657108, -1.0966459037819545e-05, -0.00024190704235009058, -0.00015615371771426863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024196763055897286, 0.035370771654048096, -0.08940016802979006, -0.0054821110552363845, -0.012952486282172465, 0.04134191142918913, 0.0804962925636271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.911807805937267e-09, -5.5112561318106675e-09, -0.0003067224401001848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922579680585263, 0.23485230751964287, 0.8410551260082697, 0.0, -0.12443324572456714, -0.24451864694277212, -2.6082263344864067, -0.7133597902155533, -0.5580948123792668, -1.1985970672594228, -2.8765653691833957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49575086226104903, 0.8853696289438552, 1.0109827884664662, -1.1970873906083481, -2.2108868656457132, -0.39072642862796775, 1.65047679939993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960955656938, -0.4403409157463759, 0.024230995521878285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.322984026012576e-06, 0.0002825711681099264, 0.00012081513770211566, 0.0, 0.00035898348483850577, 0.00017582712449362893, 4.098569513964275e-05, 0.0004508073848668016, -1.0391262641673134e-05, -0.00024138228439390562, -0.0001563420662759655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02441330661351502, 0.035273239269888054, -0.0895558556720272, -0.005512862167700783, -0.013528558189413202, 0.04132151322387183, 0.08096730087792933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.039863141520829e-09, -5.459597199002481e-09, -0.00030663941683379875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922544348864547, 0.23486643055305054, 0.8410516600789181, 0.0, -0.12441531025423512, -0.24451022400760422, -2.608224252247095, -0.7133372533672377, -0.558095373430019, -1.198609123703882, -2.876573169694533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4945193854577599, 0.8871283156303824, 1.006497328144911, -1.1973645468070087, -2.2115924913823406, -0.388661482186963, 1.6545489860475655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095262447, -0.44034091601655695, 0.024215669123602613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.066344143356634e-06, 0.0002824606681536391, -6.931858703256564e-05, 0.0, 0.0003587094066402643, 0.00016845870335784188, 4.1644786232455846e-05, 0.00045073696631083623, -1.1221015042756142e-05, -0.00024112888918500513, -0.00015601022275316007, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02462953606578174, 0.035173733730543714, -0.08970920643110362, -0.00554312397321154, -0.014112514732550215, 0.041298928820095435, 0.0814437329527083, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0649334679944005e-09, -5.403621012739874e-09, -0.00030652796551343983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922510287796178, 0.23488054673289557, 0.8410453123797789, 0.0, -0.12439739345231203, -0.24450208979585292, -2.608222123215735, -0.7133147218632591, -0.5580959904178329, -1.198621169241677, -2.876580947616735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4932771206221174, 0.8888819200328602, 1.002004340587019, -1.1976431899810067, -2.2123277102860492, -0.38659778527636235, 1.658645250560513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196094961182, -0.44034091628382155, 0.02420034975651545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.812213673893282e-06, 0.00028232359690059553, -0.00012695398278336715, 0.0, 0.00035833603846176075, 0.00016268423502602524, 4.2580627199534485e-05, 0.00045063007957435767, -1.2339756277197146e-05, -0.00024091075590005698, -0.00015555844404097243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02484529671285001, 0.035072088049553814, -0.08985975115784277, -0.005572863479960354, -0.014704378074173489, 0.04127393821201264, 0.08192529025895022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0252987988901175e-09, -5.345292444117205e-09, -0.0003063873417432767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922477524753944, 0.23489465477246935, 0.8410452074994145, 0.0, -0.12437950954869476, -0.24449439493203598, -2.6082198931027345, -0.7132921961287746, -0.5580967194820536, -1.1986332144417962, -2.87658868200518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4920240985108147, 0.8906303281832448, 0.997503986963954, -1.1979232922787466, -2.2130929177335372, -0.38453546777582476, 1.6627658355278006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960946663445, -0.44034091654796714, 0.02418503883586631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.55260844684948e-06, 0.00028216079147531595, -2.0976072879545196e-06, 0.0, 0.0003576780723454631, 0.00015389727633898903, 4.460226001287e-05, 0.00045051468968865444, -1.4581284414749146e-05, -0.00024090400238012088, -0.00015468776889814983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025060442226055177, 0.03496816300769299, -0.0900070724612974, -0.005602045954796174, -0.015304148949760347, 0.0412463500107513, 0.08241169934575161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.896747979429786e-09, -5.282911832871913e-09, -0.0003062184129828008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922445995118852, 0.23490875335282946, 0.8410484974848362, 0.0, -0.12436162721644259, -0.2444862530313363, -2.6082177053556697, -0.7132696829483258, -0.5580974129435289, -1.1986452270616588, -2.876596425174763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49076035572194887, 0.8923734214703991, 0.9929964432129866, -1.198204825000671, -2.213888511169073, -0.38247466647819256, 1.6669109766511037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960943694733, -0.4403409168091144, 0.024169737799255797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.305927018371171e-06, 0.00028197160720243975, 6.57997084341371e-05, 0.0, 0.00035764664504322043, 0.00016283801399335354, 4.3754941293355606e-05, 0.00045026360897635297, -1.3869229504038548e-05, -0.0002402523972538747, -0.00015486339166848937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025274855777316755, 0.03486186574308656, -0.09015087501934801, -0.005630654438487442, -0.015911868710717047, 0.04121602595264391, 0.0829028224660603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.937423846599186e-09, -5.22294577457969e-09, -0.00030602073221025353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922415758091562, 0.2349228411724104, 0.8410526983818923, 0.0, -0.12434374248924537, -0.24447768873916056, -2.60821558440803, -0.7132471849890912, -0.5580980457685073, -1.19865720078781, -2.8766041854502538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4894859337370256, 0.8941110786251171, 0.9884818963113168, -1.1984877579817428, -2.214714887686934, -0.38041552288820757, 1.6710809034491936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960940678644, -0.4403409170672489, 0.02415444805994494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.047405458144199e-06, 0.0002817563916189022, 8.401794112132126e-05, 0.0, 0.0003576945439442653, 0.00017128584351477422, 4.241895279880636e-05, 0.0004499591846913434, -1.2656499568355628e-05, -0.00023947452302428265, -0.00015520550981206458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025488439698465194, 0.034753143094359555, -0.09029093803339643, -0.005658659621436673, -0.016527530357216394, 0.04118287179970025, 0.08339853596179836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.03217883464038e-09, -5.1626905210071585e-09, -0.00030579478621716805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922386825645328, 0.23493691690624557, 0.8410564512649941, 0.0, -0.1243258594111105, -0.24446889925952728, -2.6082135201018084, -0.7132247038994421, -0.5580986285853954, -1.1986691367474456, -2.8766119583016656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48820087632289133, 0.8958431793631576, 0.983960534776307, -1.1987720604255176, -2.2155724461756536, -0.3783581789414705, 1.6752758485502535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960937612354, -0.4403409173222983, 0.024139171052652106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786489246427161e-06, 0.0002815146767031294, 7.505766203420739e-05, 0.0, 0.00035766156269743726, 0.00017578959266584843, 4.1286124428578224e-05, 0.0004496217929827031, -1.1656337761063967e-05, -0.00023871919271227572, -0.00015545702823389334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025701148282685583, 0.03464201476081067, -0.09042723070019727, -0.005686048875495764, -0.017151169774387676, 0.04114687893474189, 0.08389890202119733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.132577920404379e-09, -5.1009871084421215e-09, -0.00030554014585668624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092235922605165, 0.23495097923899583, 0.8410519427358509, 0.0, -0.12430799797295512, -0.24446039171558423, -2.6082114331239783, -0.7132022392024135, -0.5580992433130904, -1.1986810509852375, -2.8766197135440503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4869052277139634, 0.8975696069788188, 0.9794325421284801, -1.1990577012557722, -2.2164615881936442, -0.37630277396989964, 1.679496053466264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960934548712, -0.4403409175740272, 0.024123908203004432]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.519918735469442e-06, 0.0002812466550050523, -9.017058286262138e-05, 0.0, 0.0003572287631076722, 0.00017015087886112826, 4.173955660569902e-05, 0.00044929394057188977, -1.2294553899290337e-05, -0.00023828475583984556, -0.00015510484769303776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025912972178559337, 0.034528552313223757, -0.09055985295653808, -0.005712816605088591, -0.017782840359812042, 0.04110809943141729, 0.08440409832021027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.127284994485085e-09, -5.034578465706776e-09, -0.0003052569929535026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922332950507752, 0.23496502672304753, 0.841047783413629, 0.0, -0.12429016966556214, -0.24445225590891467, -2.60820928186934, -0.7131797919809006, -0.5580999330293639, -1.1986929512033815, -2.8766274348355845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48559903131642573, 0.8992902496173529, 0.9748980930181969, -1.199344649530385, -2.2173827195828784, -0.3742494430608768, 1.6837417729196484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196093153261, -0.44034091782227236, 0.02410866107571083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.2551087796667704e-06, 0.0002809496810341711, -8.318644443892944e-05, 0.0, 0.00035656614785969763, 0.0001627161333910628, 4.3025092769582105e-05, 0.0004489444302589652, -1.3794325470608606e-05, -0.0002380043628809906, -0.000154425830679982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02612392795075296, 0.03441285277068236, -0.09068898220566399, -0.005738965492258566, -0.018422627784678763, 0.04106661818045598, 0.08491438906769068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0322003801230195e-09, -4.964903312858732e-09, -0.0003049425458720436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922307991070202, 0.23497905786820408, 0.8410556573019119, 0.0, -0.12427237387831729, -0.2444442940500671, -2.608207077567316, -0.7131573652116887, -0.5581006863642975, -1.1987048335720254, -2.8766351253435607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4842823300878567, 0.9010049998697255, 0.9703573543408388, -1.1996328745291291, -2.2183362506259474, -0.3721983176407974, 1.6880132741548193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960928754658, -0.44034091806592374, 0.024093431277851397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.991887509777812e-06, 0.0002806229031311392, 0.00015747776565822725, 0.0, 0.0003559157448970038, 0.00015923717695157525, 4.408604048309066e-05, 0.00044853538423953636, -1.5066698673928943e-05, -0.00023764737287945692, -0.00015381015952641166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026334024571381103, 0.0342950050474507, -0.09081477354716017, -0.005764499974883995, -0.01907062086137703, 0.041022508401587915, 0.08543002470341639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.555908666280711e-09, -4.8730279323739366e-09, -0.00030459595718869284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922284323115387, 0.23499307108162593, 0.8410620224473074, 0.0, -0.12425458744531685, -0.24443588510526554, -2.608204929517324, -0.7131349647765528, -0.5581013908433606, -1.1987166731633414, -2.8766428246415074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48295516731288507, 0.9027137532260882, 0.9658104886496258, -1.1999223453926828, -2.219322595734824, -0.37014952706588417, 1.6923108338763249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960925990926, -0.4403409183058999, 0.024078220512936645]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.7335909628940805e-06, 0.00028026426843671655, 0.00012730290790996507, 0.0, 0.00035572866000864066, 0.00016817889603117935, 4.296099983475214e-05, 0.00044800870271772164, -1.408958126273807e-05, -0.0002367918263207148, -0.00015398595893936561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02654325549943236, 0.034175067127253114, -0.09093731382426007, -0.005789417271074297, -0.019726902177531216, 0.040975811498265485, 0.08595119443011036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527463615746055e-09, -4.799523095846143e-09, -0.0003042152982949902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922261997224498, 0.2350070647912494, 0.8410577045336366, 0.0, -0.12423681243828566, -0.24442719122016499, -2.6082028373758583, -0.7131125929317202, -0.5581020469926288, -1.1987284688445206, -2.876650531726507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48161758806816896, 0.904416406601707, 0.9612576589459293, -1.2002130305739471, -2.2203421712282, -0.36810320061496893, 1.696634732660511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196092317279, -0.44034091854252083, 0.024063030469186026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.465178177833702e-06, 0.00027987419246927657, -8.635827341689408e-05, 0.0, 0.00035550014062387086, 0.00017387770201113094, 4.184282931522522e-05, 0.000447436896650261, -1.3122985361760713e-05, -0.0002359136235845094, -0.0001541416999878178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026751584894322514, 0.034053067512376585, -0.09105659407393087, -0.005813703625287087, -0.020391509867517234, 0.04092652901830437, 0.08647797568372015, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.636273932491716e-09, -4.732419414340443e-09, -0.00030380087501240055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922241016812146, 0.23502103740905048, 0.8410463694385787, 0.0, -0.12421905333043677, -0.24441836995158422, -2.608200790619741, -0.7130902517633231, -0.5581026658436722, -1.198740221602538, -2.8766582417647193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48026963952599694, 0.9061128577303539, 0.9566990298493572, -1.20050489804106, -2.221395396086243, -0.36605946817557733, 1.700985254766309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960920279746, -0.44034091877582304, 0.024047862863995576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.1960824706491225e-06, 0.0002794523560217615, -0.0002267019011576197, 0.0, 0.00035518215697770964, 0.00017642537161540508, 4.0935122353427696e-05, 0.0004468233679431487, -1.2377020867531316e-05, -0.00023505516034913785, -0.00015420076425019393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026958970843440316, 0.03392902257293763, -0.09117258193144308, -0.005837349342256303, -0.02106449716086064, 0.04087464878783213, 0.08701044211595904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786086760284027e-09, -4.666044771786301e-09, -0.00030335210380902497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922221440887018, 0.23503498739762702, 0.841036886455467, 0.0, -0.1242013481825966, -0.24441026653189415, -2.608198632835657, -0.7130679387372286, -0.5581034088108263, -1.1987519639596742, -2.876665895865233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4789113717793767, 0.9078030043511358, 0.9521347702517232, -1.200797914844916, -2.222482690370258, -0.3640184612869564, 1.7053626847014656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196091741422, -0.4403409190052954, 0.024032719370823248]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.915185025717901e-06, 0.0002789997715310093, -0.0001896596622333224, 0.0, 0.00035410295680355535, 0.0001620683938012719, 4.315568167552039e-05, 0.0004462605218899997, -1.4859343083454556e-05, -0.0002348471427225327, -0.00015308201027994006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027165354932404285, 0.03380293241563895, -0.09128519195267903, -0.005860336077119565, -0.021745885680302154, 0.04082013777241842, 0.08754859870313353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.731050726891179e-09, -4.58944610775106e-09, -0.0003028698634465459]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922203164538525, 0.23504891307276912, 0.841032541842507, 0.0, -0.12418366740896726, -0.24440192084839657, -2.6081965020990285, -0.7130456612191032, -0.5581041338020172, -1.1987636644722774, -2.876673544051086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4775428382354116, 0.9094867432162603, 0.9475650547121593, -1.2010920480404839, -2.223604478160592, -0.3619803142765615, 1.7097673090060426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960914598313, -0.4403409192310516, 0.02401760180827296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.655269698775106e-06, 0.00027851350284206105, -8.689225920218913e-05, 0.0, 0.00035361547258678437, 0.00016691366995180907, 4.2614732565614394e-05, 0.00044555036250906017, -1.4499823817667592e-05, -0.00023401025206547227, -0.0001529637170595984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027370670879302096, 0.033674777302491084, -0.09139431079127737, -0.005882663911359049, -0.022435755806672526, 0.04076294020789779, 0.08809248609153901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.631816940030336e-09, -4.515125428379149e-09, -0.0003023512510057976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218624636338, 0.23506281281421168, 0.8410356756575126, 0.0, -0.12416600432264169, -0.24439321694763538, -2.608194436426376, -0.7130234228233399, -0.5581048018148895, -1.1987753136380845, -2.876681199480581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47616409798292436, 0.9111639678647261, 0.9429900709564467, -1.2013872631601683, -2.224761182138141, -0.3599451670496676, 1.7141994056720824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960911738547, -0.44034091945324066, 0.024002511926413173]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383635029025387e-06, 0.00027799482885125325, 6.26763001119526e-05, 0.0, 0.00035326172651137423, 0.0001740780152235415, 4.131345304538199e-05, 0.00044476791526665467, -1.3360257447749238e-05, -0.00023298331614080524, -0.0001531085898994188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027574805049744477, 0.03354449296931504, -0.09149967511425215, -0.005904302393688978, -0.023134079550981332, 0.04070294453787818, 0.08864193332079673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.719530654727784e-09, -4.443781211465503e-09, -0.0003017976371957132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922170704203732, 0.23507668502075083, 0.8410423074849374, 0.0, -0.1241483623155468, -0.244384310557527, -2.6081924300125126, -0.7130012257667365, -0.5581054190160493, -1.1987869114340584, -2.876688859076571, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47477521540227136, 0.9128345692861699, 0.9384100182269607, -1.20168352459866, -2.225953224315494, -0.35791316440846443, 1.7186592461985255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960908809377, -0.44034091967180033, 0.02398745145288188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1084319293768643e-06, 0.00027744413078277237, 0.0001326365484943806, 0.0, 0.00035284014189772793, 0.00017812780216790056, 4.01282772728635e-05, 0.00044394113206605953, -1.2344023195454017e-05, -0.00023195591947688265, -0.00015319191979646822, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02777765161305974, 0.033412028428875376, -0.09160105458971957, -0.0059252287698322425, -0.02384084354705729, 0.04064005282406402, 0.08919681052886042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.858339466261557e-09, -4.371193406864528e-09, -0.00030120947062583256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922156543450052, 0.23509052810004516, 0.8410492694389827, 0.0, -0.12413074689682618, -0.24437535618911002, -2.6081904678915984, -0.712979072046481, -0.5581060010212636, -1.1987984597786585, -2.8766965163409224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47337625952659734, 0.9144984368578705, 0.9338251048857156, -1.2019807958468574, -2.2271810265116145, -0.3558844549669417, 1.7231470978947316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960905813695, -0.44034091988659374, 0.023972422108249798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8321507362843026e-06, 0.00027686158588654494, 0.00013923908090758875, 0.0, 0.00035230837441229307, 0.00017908736833938907, 3.9242418287363135e-05, 0.0004430744051094812, -1.1640104287746735e-05, -0.00023096689200289316, -0.00015314528703072957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02797911751348016, 0.03327735143401081, -0.09169826682490159, -0.00594542496394866, -0.024556043922417028, 0.0405741888304541, 0.08975703392412263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.99136182881903e-09, -4.295868409399808e-09, -0.00030058689264164613]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092214376950768, 0.2351043404631002, 0.841055000947925, 0.0, -0.12411316316685755, -0.24436644803037927, -2.6081885369185116, -0.7129569637734708, -0.5581065615745155, -1.1988099601669355, -2.8767041654304397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4719673035386995, 0.916155459116594, 0.9292355465253229, -1.2022790396236822, -2.228445010501852, -0.3538591902620027, 1.7276632254874882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196090276409, -0.44034092009746506, 0.023957425614455224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.554788474152601e-06, 0.00027624726110047753, 0.00011463017884518368, 0.0, 0.0003516745993725979, 0.000178163174614961, 3.861946173756925e-05, 0.0004421654602037304, -1.1211065038467111e-05, -0.00023000776553994804, -0.0001529817903483625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02817911975795758, 0.033140445174471, -0.09179116720785228, -0.005964875536498757, -0.025279679804751456, 0.04050529409878031, 0.0903225518551289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.099211472283008e-09, -4.217426245952425e-09, -0.00029992987589149664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132402106286, 0.23511812054038544, 0.8410520894025295, 0.0, -0.12409562383109912, -0.2443578314158735, -2.608186590890484, -0.712934902017406, -0.5581071484951111, -1.1988214212369817, -2.8767117882556934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47054842423382764, 0.9178055245993192, 0.9246415639932796, -1.202578217928743, -2.229745597925077, -0.3518375237867856, 1.7322078925422681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196089970556, -0.4403409203040926, 0.023942463678312494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2734802787669106e-06, 0.00027560154570521126, -5.8230907909955594e-05, 0.0, 0.000350786715168619, 0.0001723322901152663, 3.892056055380001e-05, 0.00044123512129748107, -1.1738411910820731e-05, -0.0002292214009220766, -0.0001524565050773675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028377586097436923, 0.033001309654503014, -0.09187965064086771, -0.0059835661012142315, -0.02601174846449523, 0.0404333295043409, 0.09089334109560107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.1170619527525975e-09, -4.1325504136064795e-09, -0.00029923872285463716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922122434115142, 0.23513186671753447, 0.8410480627601596, 0.0, -0.12407813314545002, -0.24434945545829273, -2.608184620574443, -0.7129128891496048, -0.5581077715045112, -1.198832843569758, -2.8767193803773026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4691197012732411, 0.9194485226447213, 0.9200433810360168, -1.2028782923185342, -2.2310832111884804, -0.34981960999287814, 1.7367813640484877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960896649155, -0.44034092050638907, 0.02392753805860094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.993598228687448e-06, 0.0002749235429804493, -8.053284739664491e-05, 0.0, 0.00034981371298213994, 0.00016751915161527365, 3.9406320815882495e-05, 0.0004402573560225493, -1.2460188001387484e-05, -0.00022844665552575148, -0.00015184243218659447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028574459211730487, 0.032859960908041684, -0.09196365914525552, -0.006001487795825586, -0.026752265268074542, 0.04035827587814968, 0.09146943012439056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.112808490593471e-09, -4.045929541332256e-09, -0.00029851239423111863]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211389827854, 0.23514557736365363, 0.8410578585477725, 0.0, -0.12406070988152301, -0.24434158934098602, -2.608182553769859, -0.7128909254979008, -0.5581085052234442, -1.1988442413850604, -2.8767269140492373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4676812169158026, 0.9210843438719359, 0.9154412233761499, -1.2031792237209296, -2.2324582726969604, -0.3478056037279826, 1.741383906369289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960893591872, -0.44034092070432945, 0.023912650529372945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7071673205114855e-06, 0.00027421292238309636, 0.00019591575225744434, 0.0, 0.00034846527854018143, 0.000157322346134472, 4.133609168080293e-05, 0.0004392730340808338, -1.4674378662152341e-05, -0.00022795630604805403, -0.00015067343869631415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02876968714876997, 0.032716424544291745, -0.09204315319733973, -0.006018628047907992, -0.027501230169602837, 0.0402801252979109, 0.09205084641602652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.114568185997018e-09, -3.958807443717854e-09, -0.0002977505845598786]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210672469882, 0.23515925083401482, 0.8410652320488057, 0.0, -0.12404332566823896, -0.24433336627992613, -2.608180522997439, -0.7128690180598636, -0.5581092132659031, -1.1988555845615416, -2.876734437299029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46623305579286745, 0.9227128804080058, 0.9108353175470177, -1.2034809732727259, -2.2338712072731286, -0.3457956600814619, 1.7460157904635891, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960890519567, -0.44034092089783095, 0.02389780286694324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4347159446389079e-06, 0.00027346940722347367, 0.00014747002066334785, 0.0, 0.0003476842656809194, 0.00016446122119761613, 4.0615448397339356e-05, 0.0004381487607450033, -1.4160849177094524e-05, -0.00022686352962361731, -0.00015046499583523993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896322245870369, 0.03257073072139712, -0.09211811658264313, -0.00603499103592687, -0.028258691523363376, 0.04019887293041388, 0.09263768188600079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.144607672069865e-09, -3.870029836860596e-09, -0.0002969532485941604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210100400509, 0.23517288551398433, 0.8410664138041404, 0.0, -0.1240259996089749, -0.24432528532443024, -2.608178454395147, -0.7128471669546982, -0.5581099719448497, -1.198866887773201, -2.8767419218274246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4647753056448859, 0.9243340253193703, 0.9062258936717704, -1.2037835010299036, -2.235322437674143, -0.3437899350125588, 1.750677285561212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960887517417, -0.44034092108648143, 0.023882996819733292]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1441387459766836e-06, 0.0002726935993901465, 2.3635106694689962e-05, 0.0, 0.00034652118528124735, 0.0001616191099181937, 4.1372045842379415e-05, 0.0004370221033072508, -1.5173578930017302e-05, -0.0002260642331865976, -0.00014969056791598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029155002959631346, 0.03242289822728867, -0.09218847750494656, -0.006050555143554061, -0.029024608020289562, 0.04011450137806245, 0.09322990195245989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.004299680337448e-09, -3.7730098884789655e-09, -0.0002961209441989173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092209669726632, 0.23518647970489048, 0.8410609226416369, 0.0, -0.12400872906868333, -0.24431719191532206, -2.608176369004111, -0.7128253755692321, -0.5581107597717642, -1.1988781450453656, -2.876749374387809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4633080561386832, 0.9259476735196431, 0.9016131818317626, -1.2040867669585253, -2.236812388228808, -0.34178858417897373, 1.7553686651971052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960884538656, -0.44034092127040986, 0.023868234227515342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.613477534914119e-07, 0.00027188381812338203, -0.00010982325006922625, 0.0, 0.000345410805831185, 0.00016186818216330927, 4.170782071484811e-05, 0.0004358277093212305, -1.575653829063398e-05, -0.00022514544329536624, -0.0001490512076832327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029344990124054126, 0.03227296400545834, -0.09225423680015506, -0.006065318572435898, -0.02979901109329317, 0.0400270166717004, 0.09382759271786134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.957524940023932e-09, -3.6785690750768175e-09, -0.0002952518443589767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093822929072, 0.2352000317341201, 0.8410524181684602, 0.0, -0.12399151746904731, -0.24430910863530028, -2.608174261444083, -0.7128036463850764, -0.5581115824848359, -1.1988893561534155, -2.876756791973215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46183139963036696, 0.9275537212519152, 0.8969974141792522, -1.2043907305783736, -2.238341482998964, -0.3397917636906221, 1.7600902039997306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960881578726, -0.4403409214495698, 0.0238535169087839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.748674497860114e-07, 0.0002710405845922016, -0.00017008946353326963, 0.0, 0.0003442319927206149, 0.0001616656004355191, 4.215120056168994e-05, 0.00043458368311318613, -1.645426143494226e-05, -0.0002242221609999945, -0.00014835170811919904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029533130166324435, 0.03212095464544021, -0.09231535305020915, -0.006079272396967082, -0.030581895403125385, 0.039936409767033054, 0.09443077605250862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.91986084688446e-09, -3.5831994274456708e-09, -0.0002943463746288033]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373323128, 0.23521353992827793, 0.8410438725266971, 0.0, -0.12397436044111262, -0.244300887496518, -2.6081721601693726, -0.7127819829808627, -0.558112410947662, -1.1989005135506143, -2.876764184099484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4603454313905481, 0.9291520657795702, 0.8923788256592536, -1.204695351075815, -2.239910145922031, -0.33779963049762673, 1.7648421773105925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960878624786, -0.4403409216239188, 0.023838846682848473]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8992118888876934e-07, 0.0002701638831565353, -0.00017091283526128758, 0.0, 0.0003431405586938345, 0.00016442277564585636, 4.202549420018781e-05, 0.00043326808427352663, -1.6569256520598532e-05, -0.00022314794397777974, -0.0001478425253884784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029719364796376244, 0.03196689055310157, -0.09237177039997145, -0.006092409948825406, -0.031373258461334215, 0.03984266385990679, 0.09503946621723514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907879199330411e-09, -3.486980077253522e-09, -0.00029340451870856404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373722798, 0.23522700262504698, 0.8410374403757168, 0.0, -0.12395726578111037, -0.24429269050492022, -2.6081700407288655, -0.7127603871926259, -0.5581132705496118, -1.1989116211622244, -2.8767715407119447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.458850249996433, 0.9307426050694383, 0.8877576552539141, -1.2050005870186693, -2.2415187994729133, -0.3358123427934258, 1.7696248590278236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196087569427, -0.4403409217933179, 0.023824225354744655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.993361838705048e-11, 0.0002692539353811438, -0.00012864301960679008, 0.0, 0.0003418932000452387, 0.00016393983195510124, 4.2388810139131095e-05, 0.0004319157647347982, -1.719203899706572e-05, -0.00022215223220196987, -0.00014713224921229104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029903627882302698, 0.03181078579736128, -0.09242340810678894, -0.006104718857087361, -0.03217307101764898, 0.039745754084018536, 0.09565363434462144, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.861033564134219e-09, -3.387982440439172e-09, -0.0002924265620763873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093803793915, 0.23524041814845156, 0.8410374906842297, 0.0, -0.12394022730095001, -0.2442843307062041, -2.6081679394647272, -0.712738862857545, -0.558114124022187, -1.198922669739127, -2.8767788742441045, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4573459573374052, 0.9323252377254454, 0.8831341459157536, -1.2053063966618953, -2.2431678654292573, -0.33383006012496247, 1.7744385224039096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960872769383, -0.4403409219577329, 0.02380965473961995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.860142235474362e-07, 0.0002683104680918212, 1.0061702575075656e-06, 0.0, 0.0003407696032069348, 0.00016719597432282023, 4.202528276281991e-05, 0.00043048670161862127, -1.706945150298024e-05, -0.0002209715380559683, -0.0001466706431985636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03008585318055555, 0.031652653120141615, -0.09247018676321055, -0.00611619286451865, -0.032981319126879634, 0.039645653369266835, 0.09627326752172037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.849774123333481e-09, -3.2882997372638714e-09, -0.0002914123024940956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922096657396688, 0.2352537848481625, 0.8410424879608319, 0.0, -0.12392323099804707, -0.24427550322994218, -2.608165926451545, -0.7127174147928246, -0.5581148993177725, -1.1989336427949417, -2.876786209655038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4558326592403161, 0.9338998624960788, 0.8785085463058647, -1.2056127377883856, -2.2448577636846556, -0.3318529440691488, 1.7792834377311177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960869837198, -0.44034092211708964, 0.023795136622358486]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.707205544453632e-07, 0.00026733399421898104, 9.99455320436035e-05, 0.0, 0.00033992605805876916, 0.00017654952523818242, 4.026026364787405e-05, 0.00042896129440782137, -1.550591171088359e-05, -0.0002194611162937864, -0.000146708218664564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030265961941782726, 0.03149249541266861, -0.09251199219777764, -0.0061268225298059045, -0.03379796510796265, 0.039542321116274225, 0.09689830654416252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.86437310864071e-09, -3.187134913313221e-09, -0.00029036234522933065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922100965552448, 0.23526710107514773, 0.8410490640684287, 0.0, -0.12390627994451152, -0.2442664026430487, -2.60816399756591, -0.7126960453592284, -0.5581156008578939, -1.198944539937928, -2.8767935444610173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4543104655338203, 0.9354663782831726, 0.8738811111354717, -1.2059195673919778, -2.246588910859805, -0.3298811581868147, 1.7841598707715598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960866898349, -0.4403409222713018, 0.023780672785392188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.616311522513805e-07, 0.0002663245397044324, 0.0001315221519361624, 0.0, 0.000339021070711086, 0.0001820117378696219, 3.857771269517252e-05, 0.0004273886719234314, -1.4030802428831007e-05, -0.00021794285972423394, -0.0001466961195899939, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030443874129915626, 0.031330315741874865, -0.09254870340785973, -0.006136592071843622, -0.03462294350299033, 0.039435717646682064, 0.09752866080883925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.877696582075045e-09, -3.0842428966251893e-09, -0.00028927673932593894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210673237465, 0.235280365187046, 0.8410550975979828, 0.0, -0.12388938100491373, -0.24425724891563522, -2.608162132255566, -0.7126747564615128, -0.5581162500032212, -1.1989553642943187, -2.8768008700700447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4527794894455337, 0.9370246848142204, 0.8692520991614596, -1.2062268420164741, -2.2483617212788136, -0.3279148672301889, 1.7890680851332526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960863958802, -0.4403409224202819, 0.023766265007226756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1533644406949973e-06, 0.00026528223796546833, 0.00012067059108091881, 0.0, 0.00033797879195573256, 0.00018307454826957186, 3.73062068809094e-05, 0.00042577795431106595, -1.2982906544877191e-05, -0.0002164871278149365, -0.00014651218054448473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030619521765731874, 0.031166130620956245, -0.09258023948024134, -0.006145492489924126, -0.03545620838017727, 0.03932581913251551, 0.09816428723385391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.879091789393594e-09, -2.979601671892309e-09, -0.0002881555633086335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211398984335, 0.2352935755878579, 0.8410555050831465, 0.0, -0.12387255996124569, -0.24424862974986714, -2.6081602276898908, -0.7126535474193972, -0.5581169529252559, -1.198966136758033, -2.8768081474179703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4512398472649066, 0.9385746831577152, 0.8646217720329866, -1.20653451772497, -2.2501766065511055, -0.32595423653796046, 1.7940083427031794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960861098235, -0.4403409225636437, 0.023751915023692883]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.451493739797756e-06, 0.0002642080162376779, 8.149703274743813e-06, 0.0, 0.0003364208733607873, 0.00017238331536136223, 3.809131350543452e-05, 0.00042418084231146783, -1.4058440694780964e-05, -0.00021544927428580668, -0.00014554695851592048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03079284361254177, 0.030999966869896325, -0.0926065425694596, -0.00615351416991691, -0.036297705445837984, 0.03921261384456869, 0.09880515139853736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.721133778020836e-09, -2.8672360332484574e-09, -0.00028699967067747945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221227393265, 0.23530673061450377, 0.8410565945129704, 0.0, -0.12385584263010913, -0.24424086611527335, -2.608158181332645, -0.7126324177743517, -0.5581178155082985, -1.1989768780505843, -2.8768153374764402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4496916576505383, 0.9401162761748174, 0.8599903925518251, -1.2068425503342475, -2.252033976608772, -0.3239994313693354, 1.798980905793647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960858334568, -0.4403409227013466, 0.02373762464347082]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.749896630280465e-06, 0.0002631005329173592, 2.1788596477419196e-05, 0.0, 0.00033434662273115046, 0.00015527269187593876, 4.092714491516038e-05, 0.0004225929009102559, -1.7251660853081745e-05, -0.0002148258510234415, -0.00014380116939687583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030963792287366225, 0.03083186034204511, -0.09262758962322996, -0.006160652185548577, -0.037147401153326536, 0.0390961033725009, 0.09945126180934931, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527332100915927e-09, -2.7540586281405656e-09, -0.0002858076044412479]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132919391548, 0.23531982864719386, 0.841063223931719, 0.0, -0.1238392122362804, -0.24423321920061875, -2.6081560758377376, -0.7126113735463446, -0.5581187527877131, -1.1989875685837716, -2.8768224695965015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44813504236501883, 0.941649368224787, 0.8553582259425409, -1.2071508962014381, -2.2539342407502954, -0.3220506177501416, 1.8039860375006576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196085635504, -0.44034092283093423, 0.023723395630806134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.03601300906797e-06, 0.0002619606538019357, 0.0001325883749712573, 0.0, 0.0003326078765743858, 0.000152938293091898, 4.210989814999217e-05, 0.0004208845601416009, -1.8745588290554045e-05, -0.00021381066374907771, -0.00014264240122127474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031132305710390124, 0.030661840999390497, -0.09264333218568391, -0.006166917343814103, -0.03800528283046801, 0.038976272383875785, 0.10010263414021117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.959053397238659e-09, -2.5917525910362977e-09, -0.00028458025329374653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922144519139135, 0.2353328680869434, 0.8410676669346647, 0.0, -0.12382263726512502, -0.24422491913739267, -2.6081540567514145, -0.7125904214700881, -0.5581196148820815, -1.1989981758353803, -2.8768295968508615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4465701270552781, 0.9431738636921824, 0.8507255432224222, -1.207459510790999, -2.2558778039573784, -0.3201079635102819, 1.8090239953968683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960854533182, -0.4403409229545072, 0.023709229726479042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199495176391782e-06, 0.00026078879499084965, 8.886005891627416e-05, 0.0, 0.0003314994231077098, 0.00016600126452181964, 4.038172646392046e-05, 0.00041904152513015484, -1.7241887368174105e-05, -0.0002121450321726098, -0.00014254508720348415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03129830619481516, 0.030489909347908482, -0.09265365440237223, -0.006172291791215753, -0.03887126414166291, 0.038853084797193384, 0.1007591579242136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.643715639193411e-09, -2.4714595723696988e-09, -0.00028331808654188023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922157604694372, 0.23534584736592495, 0.8410668504909772, 0.0, -0.12380612670554354, -0.24421636926187285, -2.6081520936769205, -0.7125695627130906, -0.5581204332535905, -1.1990087053101475, -2.8768367071660017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4449970414885467, 0.94468966757663, 0.8460926213960657, -1.2077683487512805, -2.2578650650041974, -0.3181716381099931, 1.8140950299117282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960852664008, -0.44034092307275113, 0.023695128639661108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6171110473867365e-06, 0.0002595855796310719, -1.6328873750977248e-05, 0.0, 0.0003302111916294966, 0.00017099751039630092, 3.9261489880747366e-05, 0.0004171751399507709, -1.636743018040559e-05, -0.0002105894953461487, -0.00014220630280115963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146171133462829, 0.030316077688951552, -0.09265843652713089, -0.006176759205631756, -0.0397452209363828, 0.038726508005776, 0.1014206902972002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.738346712078653e-09, -2.3648780842152937e-09, -0.00028202173635868386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922172187093444, 0.235358764914175, 0.8410654898822433, 0.0, -0.12378970357889556, -0.24420812020919186, -2.608150095496031, -0.7125487967681349, -0.5581213019711135, -1.1990191755044783, -2.8768437658949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4434159178476597, 0.9461966869587102, 0.8414597384723083, -1.2080773645313565, -2.2598964193485593, -0.31624181071038876, 1.8191993904816701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960850686543, -0.4403409231858745, 0.023681094082104545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.916479814417497e-06, 0.00025835096500088103, -2.721217467799101e-05, 0.0, 0.0003284625329597579, 0.00016498105361986836, 3.996361778996376e-05, 0.00041531889911317413, -1.7374350460272283e-05, -0.00020940388661766464, -0.00014117457796544163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03162247281773904, 0.03014038764160504, -0.09265765847514915, -0.006180315601519984, -0.040627086887241, 0.038596547992087005, 0.10208721139883624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.954931207271424e-09, -2.2624669460461017e-09, -0.00028069115113125986]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218820509567, 0.2353716191701673, 0.8410633476626547, 0.0, -0.1237733545919424, -0.24419974024874178, -2.6081481290056185, -0.7125281285220432, -0.5581221523588407, -1.1990295706059233, -2.8768507967261296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44182689050891993, 0.9476948312002192, 0.8368271724979245, -1.2083865130951508, -2.2619722611590123, -0.31431865007858156, 1.824337328212959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960848777775, -0.44034092329331354, 0.02366712775352238]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2036004456094876e-06, 0.0002570851198458028, -4.28443917725028e-05, 0.0, 0.00032697973906325436, 0.00016759920900176153, 3.932980824228668e-05, 0.000413364921835116, -1.7007754542764683e-05, -0.00020790202889795674, -0.0001406166245909901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03178054677479595, 0.02996288483018038, -0.09265131948767472, -0.006182971275886583, -0.04151683620905522, 0.038463212636144044, 0.10275875462577573, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.817535953222311e-09, -2.1487807233846523e-09, -0.00027932657164330354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221916360722, 0.23538440877937317, 0.84113623431204, 0.0, -0.12375716825404547, -0.24419305877140782, -2.608145824566453, -0.7125075583188882, -0.5581233419857754, -1.1990400234739393, -2.87685766726029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44024420765108996, 0.9491709563510456, 0.832235792593017, -1.208693270166394, -2.2640751584080365, -0.31229657903902314, 1.829464531952495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960847210564, -0.4403409233974491, 0.023653231142714507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.861953054122794e-07, 0.000255792184117114, 0.0014577329877055664, 0.0, 0.00032372675793870207, 0.00013362954667919574, 4.6088783318532606e-05, 0.0004114040630983184, -2.3792538695589267e-05, -0.0002090573603190461, -0.0001374106832015365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03165365715659935, 0.02952250301652904, -0.0918275980981496, -0.006135141424863823, -0.04205794498048291, 0.04044142079116874, 0.10254407479071907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1344232765148914e-09, -2.0827119200966643e-09, -0.00027793221615745386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922201868250198, 0.23539634306990492, 0.8412314006554471, 0.0, -0.12374207508064684, -0.24418789206263306, -2.6081432812967753, -0.7124882530489969, -0.5581248514787112, -1.1990499100341336, -2.8768639699113385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43850370439191116, 0.9507742115167876, 0.8272174784440234, -1.209027128457125, -2.266421303994671, -0.30998379134964577, 1.8351043704068524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846727415, -0.44034092351037646, 0.02364019598329647]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0464356000538463e-06, 0.00023868581063525855, 0.0019033268681426727, 0.0, 0.00030186346797247786, 0.00010333417549517549, 5.0865393554811415e-05, 0.0003861053978273925, -3.0189858715893594e-05, -0.00019773120388399588, -0.00012605302097634758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.034810065183576266, 0.03206510331484076, -0.10036628297987271, -0.006677165814621422, -0.0469229117326932, 0.04625575378754693, 0.11279676908714747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.66298946820811e-10, -2.2585461717950393e-09, -0.0002607031883607115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922216437310262, 0.2354080849464401, 0.8413213449530466, 0.0, -0.12372725721475548, -0.24418254640448694, -2.6081406111655814, -0.7124692442472988, -0.5581265156307138, -1.1990596621045952, -2.8768701100452763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43673363940883975, 0.9523871568461224, 0.8221391334650482, -1.2093648423795467, -2.26884706203803, -0.30766750998431247, 1.840851733829424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846677342, -0.44034092362250954, 0.023627366179124365]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.913812013021153e-06, 0.00023483753070400228, 0.00179888595198974, 0.0, 0.0002963573178272846, 0.00010691316292219053, 5.340262387741816e-05, 0.0003801760339596849, -3.328304005376323e-05, -0.00019504140923134718, -0.00012280267875417538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03540129966142834, 0.03225890658669601, -0.10156689957950295, -0.006754278448434319, -0.0485151608671812, 0.046325627306666436, 0.11494726845142962, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0014635555554529e-10, -2.242661711052622e-09, -0.00025659608344215124]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922230828349167, 0.23542179120280785, 0.8413961196175765, 0.0, -0.1237101320622456, -0.2441748125719034, -2.608137768907168, -0.7124473589817228, -0.5581281884138987, -1.1990708510518875, -2.8768772695111755, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4350979902425157, 0.9538648375688505, 0.8174609802263084, -1.2096783122332178, -2.271137094484585, -0.305621782567045, 1.846191036079717, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960845977244, -0.4403409237343511, 0.02361258903531463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8782077809993562e-06, 0.0002741251273545041, 0.0014954932906001, 0.0, 0.00034250305019766023, 0.0001546766516706125, 5.684516826768007e-05, 0.0004377053115208709, -3.3455663696616285e-05, -0.00022377894584475218, -0.0001431893179887565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03271298332648065, 0.029553614454562817, -0.09356306477479633, -0.006269397073421333, -0.04580064893110514, 0.04091454834535009, 0.10678604500586072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4001961193872394e-09, -2.236830667351529e-09, -0.0002955428761946808]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922243783393282, 0.23543903852997633, 0.8414513434500096, 0.0, -0.12368880508011355, -0.24416378984995993, -2.60813464483527, -0.7124202454252593, -0.5581298364460988, -1.1990846663697565, -2.876886296613515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4336623984435202, 0.9551532708001835, 0.8133606711026311, -1.209957272600563, -2.273199334011333, -0.3039200237919479, 1.850916595958042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196084406267, -0.44034092384720275, 0.023594268486829852]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.591008822977664e-06, 0.0003449465433696476, 0.001104476648661621, 0.0, 0.0004265396426407557, 0.00022045443886932763, 6.248143796103482e-05, 0.0005422711292714019, -3.296064400230728e-05, -0.0002763063573822093, -0.00018054204678421757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02871183597991043, 0.02576866462665916, -0.08200618247354668, -0.00557920734690619, -0.041244790534955666, 0.034035175501941975, 0.09451119756650121, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8291438123780864e-09, -2.2570332791828863e-09, -0.00036641096969553655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922255106794738, 0.23546013123742882, 0.8414867720698173, 0.0, -0.12366286242224352, -0.24414972837577267, -2.6081311939056873, -0.7123873802711952, -0.558131470146458, -1.1991013861642983, -2.876897373484767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43242675695397453, 0.9562573128632461, 0.8098307629874593, -1.2102024622712715, -2.2750240339463406, -0.30252510162345925, 1.8550265512441675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960840910455, -0.44034092395784474, 0.023572049757173866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.26468029088339e-06, 0.0004218541490494525, 0.0007085723961537018, 0.0, 0.0005188531574006369, 0.00028122948374484466, 6.901859164659148e-05, 0.0006573030812827114, -3.267400718439803e-05, -0.0003343958908373568, -0.00022153742504650204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02471282979091402, 0.022080841261251077, -0.07059816230343761, -0.004903793414171123, -0.036493998700152935, 0.027898443369773075, 0.0821991057225074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.304433286892409e-09, -2.2128403986714446e-09, -0.000444374593119745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922265159170025, 0.23548434886488395, 0.8415061255847035, 0.0, -0.1236330840946502, -0.24413351552177873, -2.608127454022146, -0.7123497254554765, -0.5581331059967973, -1.19912053705499, -2.8769101520880205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43135851539591985, 0.9572093754222624, 0.8067750353053372, -1.2104195732844663, -2.276643595151556, -0.3013598281014676, 1.8586187114510089, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960836810974, -0.44034092406159986, 0.023546586131306835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.010475057647412e-06, 0.0004843525491029461, 0.00038707029772529206, 0.0, 0.0005955665518662969, 0.0003242570798786655, 7.479767081710877e-05, 0.0007530963143733585, -3.2717006786872644e-05, -0.00038301781383230676, -0.00025557206506673664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021364831161093535, 0.01904125118032559, -0.06111455364244099, -0.00434222026389549, -0.032391224104307406, 0.023305470439832707, 0.07184320413682947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.19896031598218e-09, -2.0751025149419598e-09, -0.000509272517340654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922274555400075, 0.23551049919664788, 0.8415149219583403, 0.0, -0.12360081504552632, -0.24411619699799172, -2.6081235111311813, -0.712308950582451, -0.5581347560571188, -1.1991412817206182, -2.876924034508455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4304134333681977, 0.9580505897866057, 0.8040671225441811, -1.2106158703853926, -2.2781080914157794, -0.30034361325339415, 1.861827325592487, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960832140596, -0.44034092415520626, 0.023519010503724798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8792460097681025e-06, 0.0005230066352782863, 0.00017592747273691278, 0.0, 0.000645380982477355, 0.00034637047574014696, 7.885781929856352e-05, 0.0008154974605094604, -3.3001206429091666e-05, -0.00041489331256218425, -0.0002776484086882363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018901640554443433, 0.016824287286867967, -0.05415825522312133, -0.003925942018529482, -0.029289925284466382, 0.020324296961469136, 0.06417228282956303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.340756875042724e-09, -1.8721281955298883e-09, -0.0005515125516407263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922283902802277, 0.23553740499180734, 0.8415182253375447, 0.0, -0.12356741262006192, -0.244098656648433, -2.6081194585706613, -0.7122667452605677, -0.5581364278203959, -1.1991627663390112, -2.876938417438849, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295475700577736, 0.9588204602625764, 0.8015834397600468, -1.2107984291261271, -2.2794706522647883, -0.2994086858988451, 1.8647869579812928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960827229942, -0.4403409242374828, 0.02349046859225637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8694804402221444e-06, 0.0005381159031892923, 6.606758408896761e-05, 0.0, 0.000668048509288048, 0.00035080699117424197, 8.105121039951375e-05, 0.0008441064376684413, -3.3435265540814266e-05, -0.0004296923678604655, -0.000287658607876933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01731726620848244, 0.015397409519414065, -0.04967365568268607, -0.003651174814689638, -0.027251216980177163, 0.01869854709098071, 0.059192647776113216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.821306158070047e-09, -1.6455303699486633e-09, -0.0005708382293685547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092229362213521, 0.23556419214109076, 0.8415193673058253, 0.0, -0.12353391477712479, -0.24408145874473222, -2.608115372253596, -0.7122244048578634, -0.5581381237752528, -1.1991843319310758, -2.8769528395699946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42872445430342665, 0.9595510565704616, 0.7992223359452336, -1.2109731199137916, -2.280777720365814, -0.2985065236544123, 1.8676104953770492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196082231266, -0.4403409243088011, 0.02346183822581013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9438665863407815e-06, 0.0005357429856686259, 2.283936561278392e-05, 0.0, 0.0006699568587426542, 0.0003439580740157031, 8.17263413041995e-05, 0.000846808054083768, -3.39190971396814e-05, -0.0004313118412897082, -0.000288442622914387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01646231508693933, 0.01461192615770454, -0.04722207629626339, -0.003493815753291094, -0.026141362020514175, 0.018043244888655965, 0.056470747915129293, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.83456558593435e-09, -1.426367202242299e-09, -0.000572607328924798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922303880110799, 0.23559038168015178, 0.8415199852882396, 0.0, -0.1235009259124147, -0.24406483268837104, -2.6081113018315367, -0.7121826869037292, -0.5581398408669545, -1.1992055894462346, -2.876967032815702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42791895589001544, 0.9602641198930109, 0.7969141609822934, -1.2111440345584141, -2.2820628385253374, -0.2976091306509349, 1.8703766996585587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960817519064, -0.4403409243703063, 0.02343363234899367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0515951175859435e-06, 0.0005237907812203649, 1.2359648284266457e-05, 0.0, 0.0006597772942017476, 0.000332521127223907, 8.140844119091067e-05, 0.0008343590826838142, -3.4341834033013567e-05, -0.0004251503031771353, -0.00028386491415034406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016109968268223928, 0.014261266450985874, -0.04616349925880549, -0.0034182928924479396, -0.02570236319046215, 0.017947860069547936, 0.055324085630191866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.587193975638144e-09, -1.2301036995276342e-09, -0.00056411753632922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922314643975465, 0.23561584225978577, 0.8415206281416071, 0.0, -0.12346865914893124, -0.24404875443383964, -2.6081072718949243, -0.7121418622418272, -0.5581415717556476, -1.1992263960601717, -2.8769809036549896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4271176920472807, 0.9609710640627841, 0.7946219475397546, -1.2113134147462656, -2.2833449298152786, -0.29670604552711033, 1.8731283167796038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960812893364, -0.44034092442329237, 0.023406033978459983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152772933227082e-06, 0.0005092115926796831, 1.2857067350550212e-05, 0.0, 0.0006453352696690721, 0.0003215650906277757, 8.059873225149452e-05, 0.0008164932380410139, -3.461777386295665e-05, -0.00041613227874423325, -0.0002774167857476666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016025276854695188, 0.014138883395464165, -0.045844268850776165, -0.0033876037570306798, -0.025641825798819465, 0.018061702476492185, 0.05503234242090225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.251399377513169e-09, -1.0597212265636223e-09, -0.0005519674106737503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092232580107623, 0.23564067171667163, 0.8415212349419124, 0.0, -0.1234370605731956, -0.24403306406223987, -2.608103288474411, -0.7121018685308353, -0.5581433072688579, -1.1992467787880954, -2.87699447765998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42631633281947695, 0.9616754935931877, 0.792333738387956, -1.2114820654238903, -2.2846310717664897, -0.29579816557776584, 1.8758799956162546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960808423015, -0.4403409244688435, 0.023379000395382613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2314201529564266e-06, 0.0004965891377175496, 1.2136006107188386e-05, 0.0, 0.0006319715147126685, 0.0003138074319952333, 7.966841026668133e-05, 0.000799874219836588, -3.4710264206142476e-05, -0.0004076545584751738, -0.0002714800998085875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016027184556074832, 0.014088590608071366, -0.045764183035973204, -0.003373013552493929, -0.025722839024224495, 0.01815759898688995, 0.055033576733016905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.940694945966608e-09, -9.110227440188435e-10, -0.000540671661547411]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209223372539627, 0.23566506806782841, 0.8415217812975562, 0.0, -0.12340594956291107, -0.24401758090343914, -2.6080993451677648, -0.7120624836986472, -0.5581450407705657, -1.1992668474692554, -2.8770078362267806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42551557505713944, 0.9623767297213253, 0.7900514091170274, -1.2116499838904833, -2.2859214864877115, -0.29489107317242, 1.8786305914415817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960804069877, -0.44034092450770895, 0.023352380809571575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2905772941065556e-06, 0.00048792702313550185, 1.0927112874049084e-05, 0.0, 0.0006222202056907677, 0.00030966317601457835, 7.88661329248291e-05, 0.0007876966437629345, -3.4670034157743676e-05, -0.0004013736231996911, -0.00026717133601586484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01601515524674981, 0.014024722562751344, -0.045646585418570494, -0.003358369331861143, -0.0258082944244407, 0.018141848106916394, 0.055011916506542455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.706274311049773e-09, -7.773093037112224e-10, -0.0005323917162207316]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922348953618178, 0.23568922979927492, 0.8415222566785925, 0.0, -0.123375129465284, -0.24400216448610904, -2.608095430822606, -0.712023463875547, -0.5581467688719711, -1.1992867246130448, -2.8770210672879366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42471767050002407, 0.9630727822489621, 0.7877811163116816, -1.2118169029211905, -2.28721408021122, -0.29399025899148507, 1.8813739028142424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960799793762, -0.4403409245403216, 0.023326009828649293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3399310956571104e-06, 0.00048323462893022737, 9.507620725404603e-06, 0.0, 0.0006164019525410937, 0.00030832834660205323, 7.828690317029863e-05, 0.000780396462003816, -3.456202810875578e-05, -0.0003975428757877269, -0.00026462122312433816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015958091142307503, 0.013921050552737518, -0.045405856106917414, -0.003338380614145172, -0.02585187447017159, 0.018016283618698822, 0.05486622745321367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.552228758823872e-09, -6.522531359252474e-10, -0.000527419618445673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092236089442465, 0.2357133007651516, 0.8415226672037902, 0.0, -0.12334445117290906, -0.24398673651659994, -2.6080915348528966, -0.7119846230807773, -0.5581484910085028, -1.199306504474441, -2.877034237148521, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42392436326708854, 0.9637620898156535, 0.785527656721029, -1.2119826123190947, -2.2885072294691815, -0.29309891318302905, 1.8841050985136476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196079556518, -0.4403409245668912, 0.023299761418517764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.388161294365743e-06, 0.0004814193175336523, 8.210503954310316e-06, 0.0, 0.0006135658474991242, 0.00030855939018207835, 7.791939418756594e-05, 0.0007768158953953921, -3.4442730633713985e-05, -0.0003955972279284372, -0.00026339721168615413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015866144658710776, 0.013786151333827379, -0.045069191813052134, -0.003314187958082865, -0.02586298515922863, 0.01782691616911975, 0.054623913988103075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.457162595218221e-09, -5.313923472491648e-10, -0.0005249682026306076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922373096431715, 0.2357373554602591, 0.8415230305637231, 0.0, -0.12331383313096314, -0.24397127446279795, -2.6080876499174175, -0.71194585879409, -0.5581502083641651, -1.1993262395279525, -2.8770473817984348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4231361474736072, 0.9644441377747965, 0.7832924464386829, -1.2121470755077381, -2.2898008375515504, -0.292217667083622, 1.8868230698752826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960791368715, -0.44034092458751367, 0.023273566174345575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4404014132461273e-06, 0.00048109390215006183, 7.267198659375373e-06, 0.0, 0.0006123608389183291, 0.00030924107603955115, 7.769870958462718e-05, 0.0007752857337444723, -3.4347113243743554e-05, -0.00039470107022578484, -0.0002628929982758232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015764315869626497, 0.013640959182861963, -0.04470420564692132, -0.003289263772868496, -0.025872161647381108, 0.017624921988140904, 0.05435942723269867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.392931709869209e-09, -4.124487802740948e-10, -0.0005239048834437878]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092238558825656, 0.23576141053205174, 0.8415233686300534, 0.0, -0.12328325243654976, -0.2439557920151657, -2.6080837724010726, -0.7119071414159466, -0.5581519227870049, -1.199345945387338, -2.8770605110628282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4223523698543891, 0.9651193702015691, 0.7810737984948897, -1.2123104169868437, -2.2910962516623736, -0.29134533396449097, 1.8895301632215622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960787200638, -0.4403409246022554, 0.023247404124884127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4983649688536877e-06, 0.0004811014358528989, 6.761326606055589e-06, 0.0, 0.0006116138882675735, 0.00030964895264502747, 7.755032689620944e-05, 0.0007743475628682688, -3.4288456795332206e-05, -0.00039411718771227295, -0.0002625852878715163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015675552384362555, 0.013504648535452373, -0.04437295887586491, -0.0032668295821129466, -0.02590828221646176, 0.017446662382620555, 0.054141866925591864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.336152004959027e-09, -2.9483383204032195e-10, -0.0005232409892289644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922398394839423, 0.23578544723407127, 0.8415237008592102, 0.0, -0.12325272323726047, -0.2439403182548261, -2.608079901591061, -0.7118684876951991, -0.5581536360211438, -1.1993656140432984, -2.8770736183330112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42157170330215116, 0.9657887980086253, 0.7788682009049951, -1.2124728538313292, -2.292395659042311, -0.2904799007452496, 1.8922307511121659, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960783064311, -0.44034092461119667, 0.023221286690121322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5613165727152883e-06, 0.00048073404039043435, 6.644583136598058e-06, 0.0, 0.0006105839857859857, 0.0003094752067921484, 7.741620023622234e-05, 0.0007730744149506638, -3.426468277858962e-05, -0.00039337311920644867, -0.00026214540366160043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01561333104475981, 0.013388556141123548, -0.04411195179789197, -0.003248736889710461, -0.025988147598741438, 0.01730866438482799, 0.054011757812075435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.272654326006525e-09, -1.788258857433844e-10, -0.0005223486952560803]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092241153103414, 0.23580943343363525, 0.8415240404833962, 0.0, -0.1232222746465587, -0.24392488207649005, -2.608076038413205, -0.7118299333489168, -0.5581553493164322, -1.1993852276726218, -2.8770866904437438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42079265955417344, 0.9664535785191612, 0.7766716961082093, -1.212634621195772, -2.293701407394966, -0.2896193457177761, 1.8949296662867212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960778965756, -0.440340924614439, 0.02319523811198458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.627238943820995e-06, 0.000479723991279697, 6.792483720689729e-06, 0.0, 0.0006089718140354803, 0.0003087235667211426, 7.726355711621118e-05, 0.000771086925645637, -3.426590576893101e-05, -0.00039227258646606824, -0.0002614422146470036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015580874959554462, 0.013295610210719745, -0.04393009593571532, -0.003235347288853942, -0.02611496705310561, 0.017211100549470552, 0.05397830349110793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.197111136692185e-09, -6.484728093278991e-11, -0.0005209715627347895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092242500054431, 0.23583333917995253, 0.8415243937262556, 0.0, -0.12319193475318685, -0.24390950385004634, -2.6080721843085497, -0.7117915131284361, -0.5581570633418861, -1.1994047687729104, -2.8770997147905937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4200139636292416, 0.9671147104640737, 0.7744808856812928, -1.2127959181453245, -2.295015497776658, -0.28876212112143645, 1.8976310505495397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960774910598, -0.4403409246120918, 0.02316928194668761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6939020335182154e-06, 0.00047811492634575376, 7.064857187734985e-06, 0.0, 0.0006067978674369437, 0.00030756452887392905, 7.70820931088602e-05, 0.0007684044096126242, -3.428050907739793e-05, -0.0003908220057691243, -0.0002604869369985441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015573918498637348, 0.013222638898248726, -0.043816208538330355, -0.00322593899105221, -0.026281807633830957, 0.017144491926792838, 0.05402768525636815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.110315293499276e-09, 4.6944804177953823e-11, -0.0005191233059394407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922438798573534, 0.2358571444272394, 0.8415247611308359, 0.0, -0.12316172246009313, -0.24389419335789833, -2.608068340507095, -0.7117532505645536, -0.558158778287458, -1.199424225430224, -2.8771126829367297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41923473532055916, 0.9677728866796532, 0.7722934161990574, -1.212956881883158, -2.2963393354168686, -0.2879073096273501, 1.9003377944197228, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960770902595, -0.4403409246042542, 0.023143434124516634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7596058447164707e-06, 0.000476104945737298, 7.348091605041611e-06, 0.0, 0.0006042458618744598, 0.00030620984296020646, 7.687602909510037e-05, 0.0007652512776494267, -3.429891143800084e-05, -0.0003891331462746232, -0.00025936292271699256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0155845661736487, 0.013163524311589642, -0.04374938964470688, -0.0032192747566692206, -0.02647675280421163, 0.017096229881726443, 0.054134877403664294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.01600633038393e-09, 1.5675137198967494e-10, -0.0005169564434195082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922452916000858, 0.2358808403621116, 0.8415251397821107, 0.0, -0.12313164583970654, -0.24387895172115687, -2.6080645077163536, -0.711715155813482, -0.5581604940444943, -1.1994435924773454, -2.87712559131105, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41845450336903484, 0.9684284818251855, 0.7701080173027351, -1.2131175865810657, -2.2976737120383386, -0.2870545511453888, 1.9030514941192362, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196076694342, -0.4403409245910031, 0.02311770150108781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8234854651376114e-06, 0.0004739186974440934, 7.573025496729262e-06, 0.0, 0.0006015324077317446, 0.00030483273482931615, 7.66558148236624e-05, 0.0007618950214334908, -3.4315140727767546e-05, -0.0003873409424277983, -0.0002581674864028675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015604639030486773, 0.01311190291064501, -0.043707977926445755, -0.0032140939581541406, -0.026687532429398322, 0.01705516963922575, 0.054273993990267506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.918348766056197e-09, 2.650229335057428e-10, -0.000514652468576475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922467343183218, 0.2359044269142091, 0.8415255254644389, 0.0, -0.12310170444313419, -0.24386377493927877, -2.608060686115852, -0.7116772284471309, -0.5581622103830651, -1.1994628701224501, -2.8771384401500866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4176731159377752, 0.9690816227511331, 0.7679242635833511, -1.2132780573832522, -2.299018936029712, -0.28620385908414797, 1.9057727319204802, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960763033183, -0.440340924572389, 0.023092083757146897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8854364718654023e-06, 0.0004717310419500043, 7.713646564592234e-06, 0.0, 0.0005988279314469956, 0.00030353563756180154, 7.643201002834777e-05, 0.0007585473270231177, -3.4326771416632615e-05, -0.00038555290209570716, -0.00025697678073433646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015627748625193033, 0.013062818518951868, -0.043675074387681916, -0.003209416043731131, -0.02690447982746789, 0.017013841224816428, 0.05442475602487812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.820471259658485e-09, 3.7228274721579084e-10, -0.0005123548788182946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922482072344842, 0.2359279089154134, 0.841525914222004, 0.0, -0.1230718930598605, -0.24384865728966337, -2.608056875514007, -0.7116394620836728, -0.55816392708018, -1.1994820616189485, -2.8771512318041363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4168906142633456, 0.9697322875982185, 0.7657422392854535, -1.2134382896662679, -2.3003750177240807, -0.28535542471059344, 1.90850147292552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960759171188, -0.4403409245484401, 0.023066576541881698]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9458323249921477e-06, 0.00046964002408588835, 7.775151300331361e-06, 0.0, 0.000596227665474031, 0.00030235299230778275, 7.621203690126238e-05, 0.0007553272691621398, -3.433394229827986e-05, -0.0003838299299675208, -0.0002558330809954987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015650033488590995, 0.01301329694170914, -0.043640485957952946, -0.003204645660315158, -0.027121633887366898, 0.016968687471091107, 0.05457482010079753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.723991917998616e-09, 4.789779770359519e-10, -0.0005101443053039941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922487188422875, 0.2359512926173417, 0.8414798981621372, 0.0, -0.12304217007769358, -0.2438328025892432, -2.608053233455713, -0.7116018612972712, -0.5581654649798811, -1.1995011740929382, -2.87716403092832, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41622679897001835, 0.9702865401809379, 0.763883358433907, -1.2135778829397672, -2.3015461478541615, -0.284671909354924, 1.9108411860728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075585609, -0.44034092452713464, 0.023041174375794907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0232156067228836e-06, 0.0004676740385663791, -0.0009203211973347449, 0.0, 0.0005944596433383856, 0.0003170940084034714, 7.284116588084856e-05, 0.0007520157280314512, -3.0757994020575036e-05, -0.0003822494797954897, -0.000255982483672668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013276305866545001, 0.011085051654385976, -0.03717761703092988, -0.002791865469985349, -0.023422602601618707, 0.013670307113389343, 0.04679426294614361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.630193781554256e-09, 4.2610865232925507e-10, -0.0005080433217358516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092248984882419, 0.235974268389336, 0.8414506529541362, 0.0, -0.1230129407403171, -0.24381756337189522, -2.6080496259565082, -0.7115648801886544, -0.5581669870332563, -1.199520018068767, -2.87717661581652, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4157054495725053, 0.970726134875539, 0.7624113404522476, -1.2136924119698704, -2.302488665425653, -0.28416729112142136, 1.9127088918606323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960753270093, -0.44034092451105267, 0.02301618802811448]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.320802629738785e-07, 0.00045951543988579204, -0.0005849041600194818, 0.0, 0.0005845867475296946, 0.00030478434695945265, 7.214998409164552e-05, 0.0007396221723374655, -3.044106750547131e-05, -0.00037687951657553657, -0.00025169776400109383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010426987950260405, 0.00879189389202301, -0.02944035963318739, -0.00229058060206577, -0.018850351429836387, 0.010092364670052284, 0.03735411575610158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.171997670780403e-09, 3.216397380081335e-10, -0.0004997269536085335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922491494170983, 0.23599624983988501, 0.8414483496448353, 0.0, -0.122984921306867, -0.24380364302824198, -2.608046030740962, -0.7115293881312232, -0.5581685710940243, -1.1995381647932162, -2.8771886485782794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4153133445449481, 0.9710617032434499, 0.7612911261863405, -1.2137835548633018, -2.303218483848184, -0.2838093796255577, 1.9141429507514227, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751444154, -0.4403409245013862, 0.022992208098654425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2906935816892777e-07, 0.00043962901098051926, -4.606618601843708e-05, 0.0, 0.0005603886690020853, 0.0002784068730651544, 7.19043109229564e-05, 0.0007098411486224862, -3.1681215360431484e-05, -0.0003629344889806832, -0.00024065523518950488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007842100551144033, 0.006711367358216193, -0.022404285318141592, -0.0018228578686265181, -0.014596368450615259, 0.007158229917273065, 0.02868117781580587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.651877703104973e-09, 1.933301689856042e-10, -0.00047959858920105706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492437373727, 0.23601658623147476, 0.8414590466242347, 0.0, -0.12295889779171289, -0.2437913255747105, -2.608042497371656, -0.7114963632547027, -0.5581702289630247, -1.1995551136100802, -2.8771997770817075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41502627397516445, 0.9713122651738108, 0.760458530364623, -1.2138548491255416, -2.303770441791338, -0.2835593787138501, 1.9152187220931172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119607504069, -0.44034092450048995, 0.02296989711802654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8864054873582224e-07, 0.000406727831794947, 0.0002139395879865806, 0.0, 0.0005204703030823638, 0.00024634907062953237, 7.066738611790935e-05, 0.0006604975304108868, -3.315738000833834e-05, -0.0003389763372812621, -0.0002225700685628714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005741411395673626, 0.005011238607218407, -0.016651916434352116, -0.0014258852447985985, -0.011039158863079185, 0.005000018234151651, 0.02151542683389112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0745040033420788e-09, 1.7924738970382162e-11, -0.00044621961255772425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492933419876, 0.23603475577432742, 0.8414750227616592, 0.0, -0.1229355231945582, -0.2437809814534243, -2.6080390312703785, -0.7114666078848317, -0.5581720073977583, -1.1995704589743537, -2.877209698784248, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4148198000911033, 0.9714968972861152, 0.7598487496944001, -1.2139100078181488, -2.304181407589278, -0.2833847366983969, 1.9160138213012863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960750336107, -0.4403409245145704, 0.02294979900678752]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.920922989975184e-08, 0.00036339085705321047, 0.00031952274849119864, 0.0, 0.00046749194309373803, 0.0002068824257242287, 6.932202555167622e-05, 0.000595107397419589, -3.5568694672535596e-05, -0.00030690728546846455, -0.00019843405081240186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004129477681223238, 0.0036926422460890037, -0.012195613404458027, -0.0011031738521428088, -0.008219315958802705, 0.003492840309064276, 0.015901984163380244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4158986410701592e-10, -2.8160915053321025e-10, -0.0004019622247804496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493099129635, 0.23605046525805473, 0.8414448279092318, 0.0, -0.12291510482198442, -0.2437709778967978, -2.608035990795053, -0.7114406115277784, -0.5581735692497372, -1.1995838798835885, -2.877218364229198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4146730376185007, 0.9716318981989475, 0.7594062208513683, -1.2139523496896159, -2.304484103164397, -0.28326203612539763, 1.916595816208237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751141298, -0.44034092454431645, 0.022932238233061203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.314195200306826e-08, 0.00031418967454627315, -0.0006038970485487139, 0.0, 0.0004083674514753187, 0.0002000711325302667, 6.0809506508185485e-05, 0.0005199271410681618, -3.123703957631058e-05, -0.000268418184694739, -0.0001733088989992726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002935249452052032, 0.0027000182566449277, -0.008850576860634755, -0.0008468374293380021, -0.006053911502375485, 0.0024540114599855816, 0.011639898139017498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6103848084768415e-09, -5.949203318875397e-10, -0.0003512154745262834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493104040848, 0.23606365717311636, 0.8413724547795586, 0.0, -0.12289772275178933, -0.2437611459551833, -2.6080335107422443, -0.711418514534015, -0.5581747862028298, -1.199595274141099, -2.8772257708797935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41456955499475034, 0.9717301605493174, 0.7590869279578832, -1.213984645147714, -2.3047052786869795, -0.2831748818362176, 1.9170190087748016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075219521, -0.4403409245856499, 0.022917307953974907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0" + }, + "execution_count": 34, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "reset_giskard()\n", + "\n", + "js = {\n", + " # 'torso_lift_joint': 0.2999225173357618,\n", + " 'head_pan_joint': 0.041880780651479044,\n", + " 'head_tilt_joint': -0.37,\n", + " 'r_upper_arm_roll_joint': -0.9487714747527726,\n", + " 'r_shoulder_pan_joint': -1.0047307505973626,\n", + " 'r_shoulder_lift_joint': 0.48736790658811985,\n", + " 'r_forearm_roll_joint': -14.895833882874182,\n", + " 'r_elbow_flex_joint': -1.392377908925028,\n", + " 'r_wrist_flex_joint': -0.4548695149411013,\n", + " 'r_wrist_roll_joint': 0.11426798984097819,\n", + " 'l_upper_arm_roll_joint': 1.7383062350263658,\n", + " 'l_shoulder_pan_joint': 1.8799810286792007,\n", + " 'l_shoulder_lift_joint': 0.011627231224188975,\n", + " 'l_forearm_roll_joint': 312.67276414458695,\n", + " 'l_elbow_flex_joint': -2.0300928925694675,\n", + " 'l_wrist_flex_joint': -0.10014623223021513,\n", + " 'l_wrist_roll_joint': -6.062015047706399,\n", + "}\n", + "gs.motion_goals.add_joint_position(js)\n", + "gs.motion_goals.allow_all_collisions()\n", + "gs.add_default_end_motion_conditions()\n", + "gs.execute()\n", + "\n", + "goal_pose = PoseStamped()\n", + "goal_pose.header.frame_id = 'map'\n", + "goal_pose.pose.orientation = Quaternion(*quaternion_from_matrix([[1, 0, 0, 0],\n", + " [0, 1, 0, 0],\n", + " [0, 0, 1, 0],\n", + " [0, 0, 0, 1]]))\n", + "goal_pose.pose.position.x = 2.01\n", + "goal_pose.pose.position.y = -0.2\n", + "goal_pose.pose.position.z = 0.7\n", + "\n", + "goal_pose2 = deepcopy(goal_pose)\n", + "goal_pose2.pose.position.y = -0.6\n", + "goal_pose2.pose.position.z = 0.8\n", + "goal_pose2.pose.orientation = Quaternion(*quaternion_from_matrix([[0, 0, 1, 0],\n", + " [0, 1, 0, 0],\n", + " [-1, 0, 0, 0],\n", + " [0, 0, 0, 1]]))\n", + "\n", + "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", + "gs.motion_goals.add_cartesian_pose(goal_pose2, 'r_gripper_tool_frame', 'map', name='cart2')\n", + "\n", + "goal_point = PointStamped()\n", + "goal_point.header.frame_id = goal_pose.header.frame_id\n", + "goal_point.point = goal_pose.pose.position\n", + "pointing_axis = Vector3Stamped()\n", + "pointing_axis.header.frame_id = 'wide_stereo_optical_frame'\n", + "pointing_axis.vector.z = 1\n", + "gs.motion_goals.add_pointing(goal_point, 'wide_stereo_optical_frame', pointing_axis, 'map')\n", + "\n", + "x_base = Vector3Stamped()\n", + "x_base.header.frame_id = 'base_link'\n", + "x_base.vector.x = 1\n", + "x_goal = Vector3Stamped()\n", + "x_goal.header.frame_id = 'map'\n", + "x_goal.vector.x = 1\n", + "gs.motion_goals.add_align_planes(tip_link='base_link',\n", + " root_link='map',\n", + " tip_normal=x_base,\n", + " goal_normal=x_goal)\n", + "\n", + "tip_goal = PointStamped()\n", + "tip_goal.header.frame_id = 'map'\n", + "tip_goal.point = goal_pose.pose.position\n", + "gs.motion_goals.add_motion_goal(motion_goal_class=BaseArmWeightScaling.__name__,\n", + " root_link='map',\n", + " tip_link='l_gripper_tool_frame',\n", + " tip_goal=tip_goal,\n", + " gain=100000,\n", + " arm_joints=[\n", + " 'torso_lift_joint',\n", + " # 'head_pan_joint',\n", + " # 'head_tilt_joint',\n", + " 'r_upper_arm_roll_joint',\n", + " 'r_shoulder_pan_joint',\n", + " 'r_shoulder_lift_joint',\n", + " 'r_forearm_roll_joint',\n", + " 'r_elbow_flex_joint',\n", + " 'r_wrist_flex_joint',\n", + " 'r_wrist_roll_joint',\n", + " 'l_upper_arm_roll_joint',\n", + " 'l_shoulder_pan_joint',\n", + " 'l_shoulder_lift_joint',\n", + " 'l_forearm_roll_joint',\n", + " 'l_elbow_flex_joint',\n", + " 'l_wrist_flex_joint',\n", + " 'l_wrist_roll_joint'],\n", + " base_joints=['brumbrum'])\n", + "gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", + " root_link='torso_lift_link',\n", + " tip_link='r_gripper_tool_frame')\n", + "gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", + " root_link='torso_lift_link',\n", + " tip_link='l_gripper_tool_frame',\n", + " name='MaxMal2')\n", + "gs.add_default_end_motion_conditions()\n", + "gs.motion_goals.allow_all_collisions()\n", + "gs.execute()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.6" + } + }, + "nbformat": 4, + "nbformat_minor": 0 +} \ No newline at end of file From bfd6cbe8795727019192cc50d04bb5ffe8728bdb Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 6 Aug 2024 13:28:13 +0200 Subject: [PATCH 12/43] notebook --- scripts/giskard_examples.ipynb | 26 +++++++++----------------- 1 file changed, 9 insertions(+), 17 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 6780e5b093..5f06f5bb9e 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 1, + "execution_count": 2, "outputs": [ { "name": "stdout", @@ -62,7 +62,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 3, "outputs": [], "source": [ "rospy.init_node('giskard_examples')" @@ -76,7 +76,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 4, "outputs": [], "source": [ "gs = GiskardWrapper()" @@ -90,7 +90,7 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 14, "outputs": [], "source": [ "def reset_giskard():\n", @@ -312,7 +312,7 @@ "source": [ "When using the cartesian goals all degrees of freedom of the link are fully constrained. One Advantage of constraint-based control is that one can only constrain neccessary constraints.\n", "The unconstrained DOF can then be exploited during the motion, for example in the collision avoidance or other secondary tasks.\n", - "To use this in the python interface one can use motion goals that constrain only a singualar value (sometimes called constraints on feature functions)." + "To use this in the python interface one can use motion goals that constrain only a singualar value (sometimes called constraints on feature functions).|" ], "metadata": { "collapsed": false, @@ -399,27 +399,19 @@ }, { "cell_type": "code", - "execution_count": 34, + "execution_count": 13, "outputs": [ { "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999943677873273, 0.036489651127809095, -0.34861191507695366, 0.0, -1.0029954720697876, 0.48869320376572917, -0.9525215184807941, -1.3886278121725906, -2.334452544500386, -0.4558788900739724, 0.11051798980155325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424639103, 0.01537723122151193, 1.7420423753144298, -2.031187242709937, -1.4888851823925482, -0.10085496898309822, 0.2189845498620707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529550045, -0.0006253905029041468, -0.0006249999999543101]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011264425345431811, -0.10782259036973244, 0.24007968118780842, 0.0, 0.03470669267139551, 0.02650595782943679, -0.0749999999999986, 0.07499999999999744, -0.06632406743743047, -0.02018751168584966, -0.07499999999999926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999737, 0.074999999999998, 0.07499999999999606, -0.012777139263307391, -0.04774843784840461, -2.521049782918791e-13, -0.04371418946734415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059100089, -0.012507810058082935, -0.012499999999997631]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998925805181444, 0.0267630596697571, -0.3278931585753566, 0.0, -1.0000224659428705, 0.49049653362158574, -0.9619301047404497, -1.379593523733744, -2.3410342122554755, -0.4572018850649818, 0.10116315485063393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8674174204432588, 0.025183583202972704, 1.751384115653074, -2.0317932410205013, -1.493464451596551, -0.10085496898310194, 0.21493079853658995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024960475280989564, -0.0025039454747618935, -0.0018977869579240155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00010219471025693422, -0.1945318291610399, 0.4143751300319408, 0.0, 0.05946012253834131, 0.03606659711713095, -0.1881717251931117, 0.18068576877693243, -0.13163335510178822, -0.026459899820186556, -0.18709669901838655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.17671844041302845, 0.19612703962921552, 0.18683480677288364, -0.012119966211281892, -0.09158538408005376, -7.442134995683418e-14, -0.0810750265096152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742876550287904, -0.037571099437154934, -0.025455739159394107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998493688783553, 0.014583839048681577, -0.30283958239639125, 0.0, -0.9965298716413223, 0.4921355227464133, -0.9760200982822472, -1.36680060810211, -2.349875174327609, -0.45803239691922115, 0.08685564365031923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8549868214394558, 0.03999234575967991, 1.7648047375765166, -2.0314752473307713, -1.4992752177285162, -0.10085496898347529, 0.20999822574163152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005922552841754735, -0.005952405107086799, -0.003193360879578438]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.642327957848494e-05, -0.2435844124215104, 0.5010715235793077, 0.0, 0.06985188603096355, 0.03277978249655097, -0.2817998708359508, 0.25585831263267966, -0.17681924144267328, -0.016610237084787073, -0.2861502240062941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24861198007606106, 0.2961752511341441, 0.26841243846885016, 0.006359873794598259, -0.11621532263930487, -7.467089435582319e-12, -0.09865145589916838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853010627311555, -0.06896919264649809, -0.025911478433088442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999809068351237, 0.0014335378704646243, -0.2761944917194697, 0.0, -0.9929074957979815, 0.49347927487126664, -0.9934337460668297, -1.3521735729677822, -2.3599662038298526, -0.457824273575296, 0.06884865106772532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8406534822932354, 0.058139594719090186, 1.7805125395519898, -2.029647170337682, -1.505313962569741, -0.10102857327294908, 0.20517189543805536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010643678979208298, -0.010710374037979753, -0.0038867220396985465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.06010542364428e-05, -0.26300602356433905, 0.5329018135384308, 0.0, 0.07244751686681615, 0.02687504249706601, -0.34827295569164807, 0.29254070268655696, -0.2018205900448637, 0.004162466878503277, -0.3601398516518781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2866667829244086, 0.3629449791882055, 0.31415603950946397, 0.0365615398617862, -0.12077489682449417, -0.0034720857894756426, -0.09652660607152291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09442252274907126, -0.09515937861785909, -0.013867223202402175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997690652879782, -0.011702002331867939, -0.24928874587665734, 0.0, -0.989246276057703, 0.49468681123771097, -1.0130856680342577, -1.3371594841759553, -2.370582763613108, -0.45628347991271506, 0.04830253205125776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8255901082630048, 0.07823517963514391, 1.7972253898468225, -2.026066250201851, -1.510779505665099, -0.10158468126685208, 0.20121590048948146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01641292307501113, -0.01652437680067441, -0.0038640671749981628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.000612651748077e-05, -0.26271080404665126, 0.5381149168562469, 0.0, 0.0732243948055711, 0.024150727328886127, -0.39303843934856075, 0.3002817758365387, -0.21233119566511, 0.030815873251618307, -0.41092238032935124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30126748060461117, 0.40191169832107443, 0.3342570058966499, 0.07161840271662138, -0.10931086190716179, -0.01112215987806014, -0.07911989897147827, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11538488191605661, -0.1162800552538931, 0.00045309729400767884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997283474068714, -0.02422006317593057, -0.22265032601038354, 0.0, -0.9854888087372059, 0.4959988791581555, -1.0342328168154162, -1.3226446897264197, -2.381293431749223, -0.45328812762035114, 0.026100264362257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8104723735088248, 0.09932762778084879, 1.8141873846479377, -2.020712517349157, -1.5151246688409317, -0.10266626822918933, 0.1986374242225254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023024727213398023, -0.023179169679737342, -0.003240362997743023]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.143576221380755e-05, -0.2503612168812526, 0.532768397325476, 0.0, 0.07514934640994225, 0.026241358408890046, -0.42294297562316907, 0.2902958889907117, -0.21421336272229458, 0.05990704584727803, -0.4440453537800151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3023546950835998, 0.42184896291409757, 0.3392398960223039, 0.10707465705388071, -0.08690326351665349, -0.021631739246744976, -0.05156952533912154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13223608276773788, -0.13309585758125864, 0.0124740835451028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996865980793582, -0.03577252767613231, -0.19642956701394904, 0.0, -0.9815406337022685, 0.4976208882400833, -1.056396033113364, -1.3090816174212576, -2.3918853969091396, -0.4488199833015818, 0.0028533308283817463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7956428661300832, 0.12084202839815208, 1.831009251468635, -2.013679421858163, -1.5180326510469635, -0.10435473103804188, 0.19771778927297087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030315445650636933, -0.03050174984173772, -0.002180320475781348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.349865502641323e-05, -0.2310492900040347, 0.5244151799286898, 0.0, 0.07896350069874844, 0.032440181638556685, -0.44326432595895465, 0.271261446103241, -0.21183930319833585, 0.08936288637538736, -0.4649386706775051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.29659014757483493, 0.43028801234606573, 0.3364373364139436, 0.14066190981987875, -0.058159644120635956, -0.03376925617705119, -0.018392698991090466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1458143687447782, -0.14645160324000756, 0.02120085043923349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996442330373115, -0.04616995896947086, -0.17062210968011732, 0.0, -0.9773194217804638, 0.49955824438821456, -1.07920000541233, -1.2966864109287906, -2.402273896109887, -0.44290888219037877, -0.021025607826192387, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7812463341514053, 0.1424741886154075, 1.8475146134884695, -2.0051054194168927, -1.519369528373308, -0.10669360940779955, 0.1985627728675731, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03815425881537758, -0.03835359792954218, -0.0008307438256598999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.473008409361587e-05, -0.20794862586677107, 0.5161491466766346, 0.0, 0.08442423843609374, 0.03874712296262459, -0.45607944597932065, 0.24790412984934107, -0.20776998401494684, 0.11822202222406095, -0.47757877309148267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2879306395735574, 0.4326432043451085, 0.3301072403966928, 0.17148004882540202, -0.02673754652688798, -0.04677756739515352, 0.016899671892044166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1567762632948129, -0.15703696175608922, 0.026991533002428958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996040725524014, -0.055314282637708795, -0.14516865212623695, 0.0, -0.9727456966265481, 0.5009982242991801, -1.1019427606501693, -1.2858660976682268, -2.412379732756123, -0.4355618582535085, -0.04519470760038505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.767324519208989, 0.1640966399781355, 1.8636348863947714, -1.9951358832689376, -1.5191345486479253, -0.10970712890896582, 0.20115281807469315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04643623664364146, -0.046624149490955655, 0.0006903032687336236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.0320969820218e-05, -0.1828864733647586, 0.5090691510776074, 0.0, 0.0914745030783143, 0.028799598219310777, -0.4548551047567852, 0.216406265211273, -0.202116732924724, 0.14694047873740462, -0.48338199548385324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2784362988483254, 0.43244902725455975, 0.3224054581260395, 0.19939072295909918, 0.004699594507654364, -0.060270390023325224, 0.05180090414240096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656395565652775, -0.1654110312282694, 0.03042094188787047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995656080170937, -0.06315356264304221, -0.1199941524971841, 0.0, -0.9677747180971222, 0.5012873611605031, -1.1241369183257128, -1.2768487140584996, -2.422146155899913, -0.42689116470085037, -0.06940616153652623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753877220547299, 0.18568829153512362, 1.8793483881907975, -1.983904792192392, -1.517416586876193, -0.11341034879709012, 0.20538601171981455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.055076911032641694, -0.05522545682713539, 0.002283205327204916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.692907061534153e-05, -0.15678560010666837, 0.5034899925810568, 0.0, 0.09941957058851723, 0.005782737226461488, -0.44388315351087204, 0.18034767219454395, -0.19532846287580571, 0.1734138710531634, -0.4842290787228237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26894597323380076, 0.43183303113976196, 0.3142700359205242, 0.22462182153091065, 0.03435923543464532, -0.07406439776248616, 0.08466387290242797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17281348778000474, -0.17202614672359462, 0.03185804116942584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995281641503582, -0.06966866451748287, -0.09502117513016206, 0.0, -0.9624003387814247, 0.500116271030617, -1.1455779972015496, -1.269654870766623, -2.431548357049536, -0.4170777138025503, -0.09350309815341745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7408879145352454, 0.2072870992331846, 1.8946485238828072, -1.9715281295513343, -1.5143590200051038, -0.11781302443341707, 0.21111215767328254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06400807277254862, -0.0640877832741035, 0.003868547243061622]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.488773347092766e-05, -0.13030203748881303, 0.4994595473404408, 0.0, 0.10748758631395008, -0.023421802597722835, -0.42882157751673766, 0.14387686583753134, -0.1880440229924549, 0.1962690179660015, -0.4819387323378244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2597861202410735, 0.43197615396121986, 0.3060027138401966, 0.24753325282115302, 0.06115133742178465, -0.08805351272653884, 0.11452291906935952, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17862323479813863, -0.17724652893936235, 0.03170683831713413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994913107957552, -0.07486978452803561, -0.07017347678394761, 0.0, -0.9566474214950237, 0.4974535442189808, -1.1662723818940892, -1.2641571779351852, -2.4405939888037196, -0.406312552106569, -0.11740332790066152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7283317732074577, 0.22895947583181858, 1.9095291082817134, -1.9581026453043, -1.5101332014272366, -0.12292019476310419, 0.21815816901528123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07317453423226578, -0.07315595397288652, 0.005390281978841689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.370670920623152e-05, -0.1040224002110549, 0.4969539669242888, 0.0, 0.11505834572802173, -0.0532545362327229, -0.4138876938507903, 0.10995385662875751, -0.1809126350836694, 0.2153032339196265, -0.4780045949448813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25112282655575346, 0.43344753197267905, 0.29761168797812365, 0.2685096849406872, 0.08451637155734373, -0.10214340659374235, 0.1409202268399741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18332922919434316, -0.18136341397566022, 0.030434694715601344]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999454778588323, -0.0787932511944504, -0.04537638636620607, 0.0, -0.9505610930258132, 0.4934320662590068, -1.186347623731432, -1.2601449452411397, -2.4493170870303422, -0.394757933766431, -0.1410787049015602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7161772892543037, 0.2507809650795023, 1.9239788941423313, -1.9437069608164215, -1.504919569294214, -0.1287315809038877, 0.22634589764778879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08253162230411247, -0.0823863518059898, 0.006815783357143117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.306441486449107e-05, -0.07846933332829581, 0.49594180835483076, 0.0, 0.12172656938421006, -0.08042955919948017, -0.401504836746858, 0.08024465388091005, -0.1744619645324521, 0.23109236680276088, -0.4735075400179733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24308967906307802, 0.4364297849536748, 0.28899571721235584, 0.2879136897575728, 0.10427264266044811, -0.11622772281567015, 0.1637545726501511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18714176143693387, -0.1846079566620657, 0.028510027566028558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999418401004553, -0.08149615548172884, -0.020556340685526725, 0.0, -0.9441966043754932, 0.4882542696256191, -1.205982998975845, -1.2573734263664906, -2.457768988172567, -0.3825317687870865, -0.16453548044579352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7043869252787127, 0.27282430441754935, 1.9379806416962566, -1.9284037276933006, -1.4988950104392036, -0.13524091820649173, 0.2355038109280024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09204320725190959, -0.09174447697766148, 0.008132419216196427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.275516754014441e-05, -0.054058085745568765, 0.49640091361358685, 0.0, 0.12728977300639832, -0.10355593266775534, -0.39270750488825773, 0.05543037749298321, -0.16903802284449532, 0.24452329958688943, -0.4691355108846665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23580727951181774, 0.44086678676094054, 0.28003495107850934, 0.30606466246241537, 0.12049117710021234, -0.13018674605208075, 0.18315826560427226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19023169895594233, -0.1871625034334337, 0.026332717181066216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993820843096527, -0.08304951929192882, 0.004359732278485691, 0.0, -0.9376112471486444, 0.48212994460053066, -1.2253658774053524, -1.2555963712456997, -2.466009239976215, -0.36970820743538035, -0.18779826770983304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6929184906149766, 0.2951523694979101, 1.9515121768008965, -1.9122422732104816, -1.4922250618411221, -0.14243568346670238, 0.24547391998940069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10168012295086909, -0.10120299526375542, 0.009342140285319461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.263338980055095e-05, -0.031067276203999572, 0.4983214592802483, 0.0, 0.13170714453697593, -0.12248650050176803, -0.3876575685901491, 0.035541102415818024, -0.16480503607295707, 0.256471227034123, -0.4652557452807905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22936869327472115, 0.4465613016072156, 0.27063070209279794, 0.32322908965637986, 0.13339897196162795, -0.1438953052042129, 0.19940218122796569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19273831397919, -0.18917036572187879, 0.024194421382460668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999345787218696, -0.08353142067439112, 0.029445008079205522, 0.0, -0.9308586256850422, 0.47524219487126584, -1.244668886932497, -1.2545853835584841, -2.4740982777286065, -0.35632634252206563, -0.21089833098617597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6817271814852262, 0.31781441248440706, 1.9645481115374919, -1.8952614045937972, -1.4850596725245517, -0.15029731022491274, 0.2561152164303628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1114188792209438, -0.11074019912926589, 0.010455772812928171]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.259418191355444e-05, -0.009638027649246223, 0.5017055160143966, 0.0, 0.1350524292720445, -0.13775499458529636, -0.38606019054289176, 0.0202197537443123, -0.16178075504782638, 0.2676372982662945, -0.4620012655268586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22382618259500872, 0.4532408597299385, 0.26071869473190895, 0.33961737233368844, 0.14330778633140898, -0.1572325351642074, 0.2128259288192421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1947751254014942, -0.1907440773102094, 0.02227265055217421]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999310607111454, -0.08302938996233994, 0.05477321513919481, 0.0, -0.923991414112252, 0.46773330417573744, -1.2640402128919723, -1.2541392907820497, -2.482092733130743, -0.34240177658041, -0.23386587648540366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.670773099558801, 0.3407370161374479, 1.9768575873766403, -1.877623985725392, -1.4775504600158724, -0.1588547607254304, 0.2672813611253824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12124067996820441, -0.12033872601129876, 0.011496409058730188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.036021448414886e-05, 0.010040614241023614, 0.5065641411997858, 0.0, 0.13734423145580163, -0.1501778139105684, -0.38742651918950577, 0.00892185552869019, -0.15988910804273, 0.2784913188331126, -0.459350909984554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21908163852850127, 0.4584520730608169, 0.24618951678296816, 0.3527483773681055, 0.1501842501735842, -0.17114901001035326, 0.2233228939003923, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19643601494521215, -0.19197053764065736, 0.020812724916040352]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992804213393903, -0.08165764022566474, 0.08041948891832457, 0.0, -0.9170770735508773, 0.45970313497894394, -1.283601065526524, -1.254086813416885, -2.490043326135137, -0.3279381466345287, -0.2567255882798957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6600365308914813, 0.3634496468522489, 1.9875244374976193, -1.859987029478487, -1.4699013151136944, -0.1682919919079088, 0.2787573864212014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13113083499134293, -0.12998432922857048, 0.012517509370653924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0371544126995355e-05, 0.027434994733504064, 0.512925475582595, 0.0, 0.13828681122749548, -0.16060338393586998, -0.3912170526910351, 0.0010495473032916588, -0.15901186008788104, 0.28927259891762647, -0.4571942358898413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21473137334639292, 0.45425261429602043, 0.21333700241957979, 0.35273912493810033, 0.15298289804356144, -0.1887446236495683, 0.2295205059163795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1978031004627706, -0.19291206434543448, 0.020422006238474722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992545743305098, -0.0795159245272511, 0.10646074018709453, 0.0, -0.9101708458552307, 0.45121181250340664, -1.3034525260914236, -1.254290785018126, -2.4979930325894326, -0.31293292071170853, -0.2794942992600252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6494984100499197, 0.38552614818554565, 1.995875388686491, -1.842962512642937, -1.4623139445105957, -0.1786552829958554, 0.2903352443415077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14107795986408048, -0.13966523005111176, 0.013562634334371814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.169401776087522e-05, 0.04283431396827265, 0.5208250253753994, 0.0, 0.13812455391293332, -0.16982644951074582, -0.39702921129799257, -0.004079432024817522, -0.15899412908591287, 0.30010451845640373, -0.45537421960259006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2107624168312294, 0.44153002666593455, 0.16701902377743577, 0.340490336711002, 0.15174741206197195, -0.20726582175893182, 0.23155715840612628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19894249745475076, -0.19361801645082535, 0.02090249927435781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992322813680996, -0.07670867382958221, 0.1329763188290542, 0.0, -0.9032348264408785, 0.44214690901905485, -1.323493252842749, -1.254855348925615, -2.5059698634130587, -0.2980366560047832, -0.3021668847623032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.639108140516877, 0.40669613074814553, 2.001651537455167, -1.8269615651281002, -1.4549582247240107, -0.18982475365300422, 0.30184944505258826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15107350323247298, -0.14937142693135094, 0.014685286317639549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4585924820379004e-05, 0.05614501395337779, 0.5303115728391934, 0.0, 0.13872038828704258, -0.18129806968703563, -0.40081453502650954, -0.0112912781497776, -0.15953661647252596, 0.2979252941385066, -0.45345171004555895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20780539066085135, 0.42339965125199724, 0.11552297537352055, 0.32001895029673716, 0.1471143957317011, -0.22338941314297658, 0.23028401422161135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991086736785002, -0.19412393760478375, 0.02245303966535469]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992130626790985, -0.07340491572848924, 0.15994061314862004, 0.0, -0.8962724789649682, 0.4324964947242017, -1.3438263294093244, -1.2556221171898703, -2.514013184406461, -0.2835484250369043, -0.3247341376957751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6288354085764698, 0.42682450613392386, 2.0049347917272113, -1.8121833806064307, -1.4479642065666531, -0.20157012497956966, 0.31318554591657793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16111059208723302, -0.15909494212136988, 0.01586729616881353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8437378001899175e-05, 0.06607516202185941, 0.5392858863913167, 0.0, 0.13924694951820532, -0.19300828589706293, -0.4066615313315085, -0.015335365285106062, -0.1608664198680467, 0.28976461935757797, -0.4513450586694377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20545463880814627, 0.40256750771556626, 0.06566508544089172, 0.2955636904333909, 0.1398803631471516, -0.23490742653130897, 0.22672201727979394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007417770952007, -0.19447030380037839, 0.023640197023479626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991966840970793, -0.06977970537894607, 0.18726994136662176, 0.0, -0.8892701283554084, 0.42224521192470754, -1.3645891160146304, -1.256394921929232, -2.5221558967836404, -0.2696095747926342, -0.3471787210740257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6186465895692452, 0.4458749683982276, 2.0060105202825427, -1.7986622006434627, -1.4414223202292344, -0.21361339867696572, 0.32427683434982835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1711835067910226, -0.1688296131239169, 0.017074813798622437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.275716403852687e-05, 0.07250420699086339, 0.5465865643600344, 0.0, 0.14004701219119592, -0.20502565598988312, -0.4152557321061212, -0.015456094787236955, -0.16285424754359026, 0.27877700488540236, -0.44889166756501203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20377638014449317, 0.3810092452860746, 0.021514571106627384, 0.2704235992593596, 0.13083772674837285, -0.240865473947921, 0.22182576866500847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2014582940757915, -0.19469342005094056, 0.024150352596178155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991829704491304, -0.06595164889716351, 0.21486738391251042, 0.0, -0.8821869876742153, 0.4113580694793555, -1.3858915903241376, -1.2570265264617904, -2.5304170095375724, -0.25627574742973624, -0.36947639220324785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6085015888525278, 0.46387136236181853, 2.005249868742743, -1.7863216674809272, -1.4353896885281745, -0.22567821158055126, 0.3350945463214575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18128738829199612, -0.17857079626743272, 0.01827446757476247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.742729589774109e-05, 0.07656112963565102, 0.5519488509177736, 0.0, 0.14166281362386218, -0.21774284890704082, -0.4260494861901423, -0.012632090651166567, -0.165222255078642, 0.26667654725795925, -0.44595342258444315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.202900014334348, 0.3599278792718181, -0.015213030795990373, 0.24681066325070852, 0.12065263402119997, -0.24129625807171087, 0.21635423943258303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20207763001947027, -0.19482366287031647, 0.02399307552280062]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999171936687081, -0.06200489325961712, 0.24262760650810797, 0.0, -0.8749077381951124, 0.3997031550632148, -1.4076775335683605, -1.25758594128843, -2.5387972096710043, -0.24417857712991742, -0.391590489618162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.598342974240442, 0.48087099638066244, 2.003027721377976, -1.7750238484235246, -1.4298975236623708, -0.2375200347171883, 0.34563704259039363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19141825256944675, -0.1883148717070868, 0.019458676694438536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2067524098460056e-05, 0.07893511275092788, 0.555204451911951, 0.0, 0.1455849895820586, -0.23309828832281398, -0.43571886488445577, -0.011188296532793842, -0.16760400266863723, 0.24194340599637676, -0.4422819482982835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20317229224171607, 0.33999268037687863, -0.044442947295344856, 0.22595638114805344, 0.10984329731607509, -0.23683646273274064, 0.2108499253787216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20261728554901254, -0.19488150879308166, 0.023684182393521297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991632893154915, -0.057955381131714064, 0.27043383512585756, 0.0, -0.867367996397315, 0.3872512299726996, -1.429980287645491, -1.2580481042981049, -2.5472886953391627, -0.23334210046732623, -0.4134925815781258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.588134021490493, 0.49694044611680416, 1.9996814247534958, -1.7646048459974841, -1.4249597077185387, -0.24894317319441417, 0.3559190350014655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20157257289412323, -0.1980592924005522, 0.020596362724224826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7294743179113573e-05, 0.0809902425580611, 0.5561245723549918, 0.0, 0.1507948359559485, -0.24903850181030343, -0.4460550815426122, -0.009243260193495056, -0.16982971336316888, 0.21672953325182365, -0.43804183919927536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2041790549989801, 0.321388994722834, -0.06692593248960249, 0.20838004852081085, 0.09875631887663844, -0.2284627695445175, 0.2056398482214377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20308640649352938, -0.1948884138693078, 0.022753720595725828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991570323469426, -0.053798476309639034, 0.29815606018178514, 0.0, -0.8595176351390179, 0.37399993210151256, -1.4528474884205413, -1.2583752085214903, -2.5558745158296525, -0.22360631004274767, -0.43515990202702315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5778455511123288, 0.5121486757206983, 1.9954893594833063, -1.7549029483419794, -1.4205778231805546, -0.2598038304006368, 0.36596427551383576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21174720324770274, -0.20780235697116883, 0.0216640683540259]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2513937097453594e-05, 0.08313809644150058, 0.5544445011185514, 0.0, 0.1570072251659406, -0.2650259574237416, -0.4573440155010057, -0.006542084467708544, -0.17171640980979766, 0.19471580849157094, -0.4333464089779465, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2057694075632873, 0.30416459207788243, -0.08384130540378956, 0.19403795311009459, 0.08763769075968289, -0.2172131441244532, 0.2009048102474056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2034926070715904, -0.1948612914123327, 0.021354112596021484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991532140068302, -0.0495261124340122, 0.32565129367259676, 0.0, -0.8513100937361373, 0.3599504123409985, -1.4763174109024948, -1.2585407040120304, -2.564530809104911, -0.21478922970344114, -0.4565740300787786, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5674527919006813, 0.5265628008053821, 1.9906665842974844, -1.7457735158233119, -1.4167452974479746, -0.27000673079348886, 0.375800257381472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22193937709696854, -0.21754296453507113, 0.02265058158026335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.636680224744883e-06, 0.08544727751253674, 0.5499046698162328, 0.0, 0.16415082805761122, -0.28099039521028146, -0.4693984496390691, -0.0033099098108013477, -0.17312586550517142, 0.17634160678613053, -0.42828256103510925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20785518423294885, 0.288282501693675, -0.09645550371643657, 0.1825886503733485, 0.07665051465159964, -0.2040580078570406, 0.1967196373527248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20384347698531594, -0.19481215127804613, 0.019730264524749012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991519586375045, -0.04514634070765176, 0.3514006435865091, 0.0, -0.8426592115557481, 0.3450548782274425, -1.5003302905499343, -1.2586417207195475, -2.5732270149977454, -0.2073179997627597, -0.4777153494071629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569252279431307, 0.5402475213617974, 1.9853689104517105, -1.737095556272282, -1.41345007180058, -0.279497516553597, 0.3854550071751034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23214684001108826, -0.2272802767874083, 0.023568252139719102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.510738651493572e-06, 0.08759543452720886, 0.5149869982782466, 0.0, 0.1730176436077857, -0.2979106822711192, -0.4802575929487916, -0.002020334150341435, -0.17392411785668363, 0.1494245988136289, -0.42282638656768645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.210551279151014, 0.27369441112830695, -0.10595347691547766, 0.17355919102059403, 0.06590451294789099, -0.18981571520216345, 0.1930949958726276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2041492582823945, -0.19474624504674332, 0.018353411189115012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991531433682683, -0.040652203443944004, 0.3734640331474745, 0.0, -0.8335255223283966, 0.32932626206854554, -1.5248929540006286, -1.2586880015078965, -2.581930858881691, -0.20105999855085718, -0.498573411877532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5462492593169215, 0.5532608933159537, 1.9797051056484585, -1.7287711810021689, -1.4106774840942202, -0.28825605805658827, 0.3949547180241143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24236763948430182, -0.23701378075307267, 0.02441571502677804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.369461527810091e-06, 0.08988274527415509, 0.4412677912193081, 0.0, 0.18267378454702882, -0.3145723231779398, -0.4912532690138861, -0.0009256157669812709, -0.1740768776789138, 0.12516002423805006, -0.4171612494073814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2135193725241847, 0.26026743908312594, -0.11327609606504076, 0.16648750540226392, 0.055451754127197606, -0.17517083005982564, 0.18999421698021818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20441598946427111, -0.19467007931328703, 0.016949257741178766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991568038104338, -0.03604378387140768, 0.39102189623055855, 0.0, -0.8238822059508757, 0.3127923029678555, -1.5500276807358593, -1.2586642221456124, -2.5906074666517895, -0.19576593852907737, -0.5191436384328104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5354166890823266, 0.5656565402075744, 1.9737468833513334, -1.7207250504230756, -1.4084109998532808, -0.29628753156221943, 0.4043231753796419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25260010035560265, -0.24674318402336615, 0.02519559589684357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.320884331225334e-06, 0.09216839145072646, 0.35115726166168076, 0.0, 0.1928663275504183, -0.33067918201380153, -0.502694534704615, 0.0004755872456812329, -0.17353215540196934, 0.10588120043559658, -0.4114045311055688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21665140469189534, 0.2479129378324135, -0.11916444594250003, 0.16092261158186555, 0.045329684818788706, -0.1606294701126236, 0.1873691471105526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20464921742601713, -0.1945880654058694, 0.015597617401310607]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991629762965907, -0.0313301511200436, 0.4042356347770096, 0.0, -0.8137036635729823, 0.2954815505203647, -1.5757550714762791, -1.2585520824471372, -2.599220977602953, -0.19121333064802526, -0.539425331861611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5244213501439687, 0.5774842648355991, 1.9675384844805521, -1.7129005387961165, -1.4066329340866166, -0.30361497808066934, 0.41358166513866096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26284282183271745, -0.25646830713754026, 0.025915311458413366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2344972314041837e-05, 0.0942726550272815, 0.26427477092902024, 0.0, 0.2035708475578688, -0.3462150489498161, -0.5145478148083986, 0.0022427939695019595, -0.17227021902327067, 0.09105215762104218, -0.4056338685760125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21990677876715797, 0.2365544925604943, -0.12416797741562423, 0.15649023253918076, 0.03556131533328266, -0.14654893036899808, 0.18516979518038082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20485442954229588, -0.19450246228348259, 0.014394311231395939]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991716731154052, -0.026525558340783968, 0.41380240247527866, 0.0, -0.8029623156404427, 0.2774207428798835, -1.6020897913705852, -1.2583369909018103, -2.607736646785377, -0.1872381734880999, -0.5594203751179667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5132583434356306, 0.5887901948276059, 1.9611049586567002, -1.7052552910862158, -1.405324980846817, -0.3102732739851018, 0.42274918911505466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.273094660675004, -0.2661890497572536, 0.026584619763713735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.739363762884511e-05, 0.09609185558519262, 0.19133535396538198, 0.0, 0.21482695865079082, -0.36121615280962405, -0.5266943978861184, 0.0043018309065368885, -0.17031338364847823, 0.0795031431985073, -0.3999008651271129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2232601341667642, 0.22611859984013546, -0.12867051647703923, 0.15290495419801506, 0.026159064795992434, -0.13316591808864933, 0.1833504795278738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20503677684573077, -0.19441485239426728, 0.013386166106007354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991828863620853, -0.021645009132675964, 0.4205907108636889, 0.0, -0.791628159543138, 0.258635880996209, -1.6290408846014002, -1.2580090366093195, -2.6161224405769827, -0.18372994186970218, -0.5791323817827055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5019239113415281, 0.5996168454478135, 1.9544588074527132, -1.6977572570550705, -1.404468556059473, -0.31630444289788495, 0.4318428320375456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28335470022604436, -0.27590532282194086, 0.027213481376127325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.242649336002097e-05, 0.09761098416216009, 0.13576616776820377, 0.0, 0.22668312194609339, -0.3756972376734905, -0.5390218646163004, 0.006559085849813688, -0.16771587583211528, 0.07016463236795442, -0.39424013329477636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22668864188205057, 0.21653301240415293, -0.1329230240797412, 0.1499606806229051, 0.01712849574688053, -0.12062337825566287, 0.18187285844981813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2052007910208073, -0.19432546129374453, 0.01257723224827178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991965916541216, -0.016701056200382057, 0.4254225939679053, 0.0, -0.7796690759648334, 0.23915418238325292, -1.6566134421122871, -1.25756206611305, -2.624349893978199, -0.18061804771119994, -0.5985661845110753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904153737741563, 0.6100031613137556, 1.947604948074933, -1.6903814793287308, -1.404045026353251, -0.32175417684037083, 0.44087815263000113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29362221457316656, -0.285617048995376, 0.027810817361409907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7410584072310096e-05, 0.0988790586458781, 0.09663766208432883, 0.0, 0.23918167156609368, -0.3896339722591212, -0.5514511502177396, 0.008939409925390817, -0.16454906802433, 0.062237883170044736, -0.3886760545673955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23017075134743417, 0.20772631731884392, -0.1370771875556067, 0.1475155545267934, 0.008470594124443212, -0.10899467884971732, 0.18070641184911032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20535028694244367, -0.1942345234687028, 0.011946719705651644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992127501286358, -0.011702208613917686, 0.4289739422232274, 0.0, -0.7670512784878643, 0.21900591760066124, -1.684810411942989, -1.2569922982686135, -2.632394354661889, -0.17785914352096863, -0.617727581249097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787309925001368, 0.6199845755451108, 1.9405442054172986, -1.683107685070384, -1.4040358776467259, -0.3266693798282774, 0.44986952770788047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30389663225850994, -0.2953241545968568, 0.028383949432997407]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2316949028507026e-05, 0.09997695172928742, 0.0710269651064412, 0.0, 0.25235594953938256, -0.4029652956518339, -0.563939396614037, 0.011395356888729244, -0.1608892136737929, 0.0551780838046262, -0.3832279347604332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23368762548039063, 0.19962828462710325, -0.14121485315268698, 0.14547588516693374, 0.0001829741305017802, -0.09830405975813139, 0.17982750155758723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548835370686713, -0.1941421120296164, 0.01146264143174999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992313101318812, -0.006652692565644477, 0.4317498358492036, 0.0, -0.7537397487466786, 0.19822584140021687, -1.7136341431009776, -1.2562970072993924, -2.6402348296879428, -0.17542754335129496, -0.6366232662843543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4668697844299083, 0.6295930893252552, 1.933275611045951, -1.6759185806028578, -1.404422861464175, -0.33109652878027634, 0.458830413805529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31417750276953854, -0.30502657383305176, 0.02893846063414057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.712000649054735e-05, 0.10099032096546418, 0.05551787251952504, 0.0, 0.2662305948237139, -0.4156015240088871, -0.5764746231597715, 0.01390581938442012, -0.15680950052107492, 0.04863200339347323, -0.37791370070514646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2372241614045679, 0.19217027560288796, -0.1453718874269521, 0.14378208935052617, -0.00773967634898096, -0.08854297903997929, 0.1792177219529715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056174102205722, -0.1940483847238996, 0.011090224022863238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999252208256924, -0.0015530650799208427, 0.43409950235886813, 0.0, -0.7396986511357861, 0.17685419495564528, -1.7430875667126164, -1.255473436518051, -2.6478536261191183, -0.1733086480035227, -0.6552608821508061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4548313208956247, 0.638857379542875, 1.9257978066239203, -1.6687987189318956, -1.4051881357602882, -0.3350806539796887, 0.46777352030281205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32446446710359783, -0.3147242513390845, 0.02947827750528296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.179625008542345e-05, 0.10199254971447269, 0.04699333019329052, 0.0, 0.2808219522178488, -0.4274329288914317, -0.5890684722327764, 0.01647141562682765, -0.1523759286235147, 0.04237790695544556, -0.37275231732903635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24076927068567405, 0.1852858043523969, -0.14955608844061632, 0.14239723341924326, -0.015305485922267837, -0.07968250398824721, 0.17886212994566003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20573928668118585, -0.19395355012065485, 0.010796337422847802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992753700588597, 0.003598798511559146, 0.43624739217648045, 0.0, -0.724891741690841, 0.15493734916362287, -1.77317503344434, -1.2545179696671447, -2.65523591858819, -0.17149465918198545, -0.6736491402359694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4426155419967504, 0.6478029342278301, 1.9181098129680592, -1.6617337984280063, -1.4063144055645729, -0.33866476616335506, 0.4767109036375887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3347572324029258, -0.3244171475426142, 0.030005856709231834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6323603871767203e-05, 0.10303727182959976, 0.04295779635224643, 0.0, 0.2961381888989033, -0.43833691584044815, -0.6017493346344696, 0.01910933701812804, -0.1476458493814388, 0.036279776430745134, -0.36776516170326684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24431557797748968, 0.17891109369910227, -0.15375987311722422, 0.14129841007778507, -0.0225253960856932, -0.07168224367332676, 0.17874766669553313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20585530598655982, -0.19385792407059352, 0.010551584078977523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999300727479941, 0.008804094513933344, 0.43832674680155004, 0.0, -0.7092734812854777, 0.1325250230096199, -1.8038896617668416, -1.2534467156304505, -2.662369107290451, -0.170136386354041, -0.6917974923403458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4302206397529396, 0.656452392197265, 1.91021119496771, -1.654710318457212, -1.4077850093685291, -0.3418894014845274, 0.48565401651967277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34505557801701003, -0.3341052161568823, 0.03052500721608979]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.071484216269138e-05, 0.10410592004748395, 0.041587092501391226, 0.0, 0.3123652081072662, -0.4482465230800592, -0.6142925664500328, 0.02142508073388495, -0.14266377404522404, 0.02716545655888939, -0.3629670420875271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.247898044876214, 0.1729891593886999, -0.15797236000698112, 0.1404695994158832, -0.029412076079125125, -0.06449270642344677, 0.17886225764168148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596691228168415, -0.1937613722853621, 0.01038301013715913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993281607735924, 0.014069201764168223, 0.440554074676966, 0.0, -0.6928109809552064, 0.10967925831495132, -1.8352409943354022, -1.2522513346602826, -2.6692418402322686, -0.16918147937709843, -0.7097178193704274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4176478262465135, 0.6648252180781782, 1.9021025352490581, -1.6477151275537387, -1.4095841982762256, -0.3447930230988332, 0.4946136536266191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35535929515115294, -0.3437884526041532, 0.031034178355589064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.4866587303167144e-05, 0.10530214500469758, 0.044546557508319394, 0.0, 0.329250006605426, -0.4569152938933719, -0.627026651371214, 0.023907619403360444, -0.1374546588363505, 0.0190981395388514, -0.3584065406016334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2514562701285214, 0.1674565176182633, -0.16217319437304076, 0.13990381806946717, -0.035983778153928975, -0.05807243228611571, 0.17919274213892625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20607434268285799, -0.19366472894541778, 0.010183422789985429]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993575682648196, 0.019400616468993246, 0.44289768829019843, 0.0, -0.6754744605295335, 0.08646953830834081, -1.8672451722132992, -1.2509139006384626, -2.6758434597702183, -0.1685470814504019, -0.7274240181573949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4048984576701506, 0.6729382830732726, 1.8937852932352317, -1.640735717797071, -1.4116971315210167, -0.3474117904117522, 0.5035999569603018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3656681770246601, -0.3534668961450138, 0.031531318896992885]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.8814982454298406e-05, 0.10662829409650044, 0.04687227226464876, 0.0, 0.3467304085134582, -0.46419440013220997, -0.6400835575579383, 0.02674868043639765, -0.1320323907589963, 0.012687958533930593, -0.3541239757393488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2549873715272559, 0.16226129990188878, -0.16634484027652924, 0.1395881951333539, -0.04225866489582044, -0.05237534625838001, 0.17972606667365373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617763747014317, -0.1935688708172126, 0.009942810828076472]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993888393816484, 0.0248040893394555, 0.44529375356535134, 0.0, -0.657234770570855, 0.06297094490393922, -1.8999212050323753, -1.249412458692867, -2.682164551083141, -0.16816676905990524, -0.7449317767870256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3919731590322595, 0.6808061382983573, 1.8852615233704535, -1.6337601318767279, -1.4141099807966149, -0.3497796362304216, 0.5126224001403346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37598173324735323, -0.36314035844652015, 0.03201440817113183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.254223365770543e-05, 0.10806945740924509, 0.04792130550305777, 0.0, 0.3647937991735709, -0.4699718680880319, -0.6535206563815221, 0.03002883891191481, -0.12642182625846027, 0.007606247809932947, -0.35015517259261514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2585059727578234, 0.15735710450169496, -0.17047539729556585, 0.1395117184068595, -0.048256985511962884, -0.04735691637338743, 0.18044886360065446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20627112445386322, -0.19346924603012725, 0.00966178548277895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994218755304446, 0.03028111445937137, 0.4476983151298864, 0.0, -0.638051332776127, 0.03926257745153229, -1.9332743876008847, -1.2477508441344103, -2.688197452370262, -0.16810928445998144, -0.7622579496811501, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3788697670593844, 0.6884412863522363, 1.8765336079476393, -1.6267770578307548, -1.4168099483184164, -0.35192815298540625, 0.521689746529341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38629983835555937, -0.3728089685767702, 0.03248476983167084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.607229759236975e-05, 0.10954050239831736, 0.04809123129070107, 0.0, 0.3836687558945604, -0.4741673490481384, -0.6670636513701855, 0.03323229116913221, -0.12065802574241588, 0.001149691998475956, -0.3465234578824916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2620678394575032, 0.15270296107757883, -0.17455830845628348, 0.13966148091946143, -0.053999350436031546, -0.04297033509969325, 0.1813469277801277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063621021641231, -0.19337220260500151, 0.009407233210780217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994565462695438, 0.035833492498871876, 0.4500905981744083, 0.0, -0.6178842585120434, 0.015431057167064749, -1.9673061459951764, -1.2459416831053933, -2.6939362728567957, -0.16848615907127737, -0.7794214344100959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3655861790610817, 0.695854000809875, 1.8676041606193066, -1.6197754582617239, -1.4197854587358523, -0.35388704398114024, 0.5308099776510703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3966223687317779, -0.382472854002744, 0.03294257592190131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.934147819820369e-05, 0.11104756079001019, 0.04784566089043712, 0.0, 0.40334148528167124, -0.47663040568935083, -0.6806351678858344, 0.03618322058034058, -0.11477640973067882, -0.007537492225918648, -0.3432696945789163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26567175996605197, 0.1482542891527731, -0.1785889465666572, 0.14003199138061714, -0.05951020834871641, -0.03917781991467974, 0.18240462243458555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064506075243705, -0.1932777085194761, 0.009156121804609322]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994927114146885, 0.04146423281254037, 0.4524652423308594, 0.0, -0.5967002839762974, -0.008428315810264247, -2.002019540532723, -1.2439956941687156, -2.6993758339653144, -0.16940299491767172, -0.7964438610998594, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3521212162123777, 0.7030525069188116, 1.8584760797939717, -1.6127446918799009, -1.4230261952653138, -0.35568434019006, 0.539990275195647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4069491874556222, -0.3921321596665384, 0.0333861414163522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.233029028954226e-05, 0.1126148062733699, 0.04749288312902246, 0.0, 0.42367949071492217, -0.4771874595465799, -0.694267890750924, 0.038919778733553526, -0.10879122217037608, -0.018336716927886926, -0.3404485337952699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2692992569740784, 0.14397012217873117, -0.18256161650669792, 0.14061532763645895, -0.0648147305892294, -0.035945924178395046, 0.1836059508915353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20653637447688533, -0.19318611327588817, 0.008871309889017753]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995302292547737, 0.04717719163981723, 0.45482467173455715, 0.0, -0.5744743481247945, -0.03221191560342329, -2.0374207516577627, -1.2419173313528997, -2.704510349690118, -0.17094461988618306, -0.8133500607854194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.338474363592058, 0.710043323425046, 1.849152611281147, -1.6056747744240032, -1.4265230589240911, -0.3573465118464638, 0.5492370613052514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4172801236089696, -0.40178706148223914, 0.03381250417578785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.50356801704552e-05, 0.1142591765455371, 0.0471885880739552, 0.0, 0.4445187170300572, -0.47567199586318076, -0.7080242225007946, 0.041567256316315505, -0.10269031449607864, -0.030832499370226814, -0.3381239937112001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27293705240639565, 0.13981633012468742, -0.18646937025649496, 0.14139834911795557, -0.06993727317554597, -0.03324343312807645, 0.18493572219208787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2066187230669484, -0.1930980363140145, 0.008527255188713103]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995689562569696, 0.0529764013584553, 0.4571740315963459, 0.0, -0.5511892882837658, -0.05580878834381451, -2.0735186015691505, -1.2397038596385224, -2.70933229877117, -0.17317392474171134, -0.8301683189783522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3246456650861915, 0.716831383794669, 1.8396373038523934, -1.5985564082349324, -1.4302681534635762, -0.3588985346995499, 0.558555999158406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42761497664776876, -0.4114377704488579, 0.03421828106622663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.745400439178555e-05, 0.1159841943727615, 0.046987197235774894, 0.0, 0.4657011968205729, -0.4719374548078243, -0.7219569982277539, 0.04426943428754573, -0.09643898162103368, -0.044586097110565416, -0.33636516385865606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2765739701173271, 0.1357612073924629, -0.19030614857507142, 0.1423673237814152, -0.07490189078970134, -0.03104045706172176, 0.18637875706309256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20669706077598285, -0.1930141793323752, 0.008115537808775676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996089890845417, 0.05888883692989693, 0.4595184800629568, 0.0, -0.526901883015525, -0.07893182781676603, -2.110092321432455, -1.2373198520905968, -2.7134998146319544, -0.17613304333447521, -0.8465907922731724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.310653127481421, 0.7234196128227636, 1.8299352386537378, -1.5913806634700793, -1.4342550396317781, -0.36036587707562534, 0.5679520932180644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4379532912986751, -0.421084771078369, 0.03457703990224904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.006565514422405e-05, 0.11824871142883255, 0.046888969332218, 0.0, 0.485748105364817, -0.4624607894590302, -0.7314743972660956, 0.047680150958511774, -0.08335031721568739, -0.05918237185527777, -0.32844946589640434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27985075209540916, 0.13176458056189136, -0.19404130397311342, 0.14351489529706157, -0.07973772336403934, -0.029346847521508145, 0.18792188119316772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20676629301812666, -0.1929400125902228, 0.007175176720448172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999650598841945, 0.06497439219545284, 0.4618620525147836, 0.0, -0.5017975861345425, -0.10103100307083646, -2.1465184654326808, -1.234674623861658, -2.7161027121378716, -0.17985000619381897, -0.8617340947443358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2965438552155464, 0.7298096042905275, 1.8200545056691093, -1.5841400898195637, -1.4384785532693973, -0.36177571462075087, 0.5774299590274339, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4482940391134155, -0.43072916432052577, 0.034829289387686035]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.3219514806687e-05, 0.12171110531111831, 0.046871449036536506, 0.0, 0.5020859376196491, -0.4419835050814085, -0.7285228800045104, 0.05290456457877694, -0.052057950118340725, -0.07433925718687479, -0.30286604942326895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28218544531749395, 0.1277998293552787, -0.1976146596925673, 0.14481147301031166, -0.0844702727523845, -0.028196750902510892, 0.18955731618739077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2068149562948069, -0.19288786484313503, 0.0050449897087399016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996936354723793, 0.07126622309335441, 0.4642074181845505, 0.0, -0.4760551418039262, -0.12167984801784872, -2.1822476332991476, -1.2316783456747256, -2.716361757472941, -0.18434645519981743, -0.8748556332219445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.282349992373356, 0.7360038559743707, 1.8100036805633035, -1.5768306365002767, -1.4429338617451328, -0.36315222153362153, 0.5869939497017014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4586358746761437, -0.44037239127138705, 0.0349420811878866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.607326086861515e-05, 0.12583661795803136, 0.046907313395338227, 0.0, 0.5148488866123256, -0.4129768989402451, -0.7145833573293369, 0.05992556373864878, -0.005180906701383242, -0.08992898011996939, -0.26243076955217426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28387725684381143, 0.12388503367686289, -0.20101650211611713, 0.14618906638573945, -0.08910616951470839, -0.027530138257413045, 0.1912798134853488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683671125456485, -0.19286453901722592, 0.0022558360040113136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997379143001764, 0.07776899639084262, 0.46655600538470354, 0.0, -0.4498147428041323, -0.1406513385680828, -2.2169279753438587, -1.228267958933324, -2.7138063538676853, -0.18962681856315414, -0.8855349017778712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2680810973387941, 0.7420045623063706, 1.7997893976568422, -1.5694488605442787, -1.4476169525708655, -0.36451601216623863, 0.5966479672555021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46897740788126946, -0.4500159440950995, 0.03491072156614704]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.855765559401911e-05, 0.13005546594976414, 0.046971744003060124, 0.0, 0.5248079799958779, -0.3794298110046814, -0.6936068408942236, 0.0682077348280285, 0.05110807210511245, -0.1056072672667343, -0.21358537111853512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2853779006912345, 0.12001412663999692, -0.20428565812922733, 0.1476355191199587, -0.09366181651465605, -0.02727581265234201, 0.19308035107601457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683066410251555, -0.1928710564742491, -0.00062719243479135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997859488869993, 0.08449411927742755, 0.46890829058041245, 0.0, -0.423228987139392, -0.15802175540469443, -2.249987385598714, -1.2241457216270608, -2.7084187345750443, -0.1957180323196668, -0.893782711064083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.253748187745712, 0.7478123549353348, 1.7894169406863398, -1.5619896511407834, -1.4525252844554515, -0.36588689044702444, 0.6063954373352898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4793171384805335, -0.4596614333567058, 0.03472380389854716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.606917364578337e-05, 0.1345024577316986, 0.047045703914178304, 0.0, 0.5317151132948059, -0.3474083367322327, -0.6611882050971059, 0.08244474612526588, 0.10775238585281527, -0.12182427513025361, -0.1649561857242356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.286658191861644, 0.11615585257928451, -0.20744913941004678, 0.14918418806990458, -0.09816663769171755, -0.027417565615715768, 0.19494940159575466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2067946119852808, -0.19290978523212576, -0.0037383533519975355]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998346517918872, 0.09141406724463508, 0.4712641065329575, 0.0, -0.3963772718905486, -0.17371562945071847, -2.2814760175244753, -1.219360925440738, -2.7002327508410016, -0.20256769550311668, -0.8997134077907735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.239329617790521, 0.7534266524824335, 1.7788887401772873, -1.5544474328996274, -1.4576573351045903, -0.3672799495537857, 0.6162389829320788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48965387642560615, -0.4693104482638417, 0.03440900117209651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.740580977579372e-05, 0.13839895934415067, 0.047116319050902106, 0.0, 0.5370343049768674, -0.31387748092048084, -0.629772638515227, 0.0956959237264568, 0.16371967468085852, -0.13699326366899722, -0.11861393453380784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28837139910381737, 0.11228595094197273, -0.21056401018104937, 0.15084436482312133, -0.1026410129827759, -0.027861182135225065, 0.19687091193577935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20673475890145315, -0.19298029814271903, -0.006296054529012879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998837262983027, 0.0984876371474542, 0.4736228512128817, 0.0, -0.36931688053387773, -0.18773598357623295, -2.3116213955634004, -1.2140251347964188, -2.6893801310269607, -0.21009366952295444, -0.903551021511901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2247864723311725, 0.7588446208607488, 1.7682046484249256, -1.5468142979099502, -1.463013101024749, -0.3687074540384244, 0.6261802995106079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49998676525617464, -0.47896382469304655, 0.03400803337286887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.814901283098824e-05, 0.14147139805638256, 0.04717489359848419, 0.0, 0.5412078271334178, -0.2804070825102892, -0.6029075607785047, 0.1067158128863861, 0.21705239628081968, -0.15051948039675508, -0.07675227442255034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2908629091869693, 0.10835936756630725, -0.21368183504723234, 0.1526626997935423, -0.1071153184031709, -0.028550089692774814, 0.1988263315705836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20665777661136933, -0.19306752858409676, -0.008019355984552914]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999333034850686, 0.105673669795564, 0.4759836606629676, 0.0, -0.3420989319308359, -0.2001784404608327, -2.3406676079286513, -1.2082366255708006, -2.676068847338364, -0.2181991233110978, -0.9055950446480462, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.210074347685301, 0.7640609965663732, 1.7573630303574068, -1.53907990480734, -1.4685941695923914, -0.3701801278166298, 0.636220089338161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5103153663581976, -0.4886219727508629, 0.03356302377694085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.915437353183409e-05, 0.14372065296219605, 0.047216189001717875, 0.0, 0.5443589720608369, -0.2488491376919947, -0.5809242473050138, 0.11577018451236276, 0.2662256737719409, -0.16210907576286726, -0.04088046272290302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2942424929174305, 0.10432751411248795, -0.2168323613503749, 0.1546878620522016, -0.11162137135285063, -0.02945347556410772, 0.2007957965510602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20657202204046005, -0.19316296115632664, -0.00890019191856041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999985724046607, 0.11296025548712392, 0.47834557029358193, 0.0, -0.314801405808413, -0.21118625359244553, -2.3685314160903346, -1.2018226217381398, -2.660668603774185, -0.2268306392523497, -0.906272283081831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.195169438262761, 0.7690689721673792, 1.746363206779349, -1.531232376173149, -1.474403504951756, -0.3717100360535933, 0.6463583943527268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5206393882958547, -0.49828517094116875, 0.03308743223331075]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010484112307689969, 0.1457317138311984, 0.04723819261228707, 0.0, 0.5459505224484582, -0.22015626263225668, -0.5572761632336668, 0.12828007665321645, 0.3080048712835719, -0.17263031882503777, -0.013544768675696726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.298098188450805, 0.10015951202012112, -0.21999647156115473, 0.15695057268381932, -0.11618670718729492, -0.030598164739270173, 0.20276610029131695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20648043875314065, -0.19326396380611774, -0.00951183087260194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000386188984348, 0.1203205677287292, 0.48070759131574803, 0.0, -0.287474989770132, -0.22085635045821775, -2.3954222793204267, -1.1948892232481507, -2.643436904418872, -0.23587381765469737, -0.9059314193362062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.180038166023946, 0.7738608510681475, 1.7352056038860497, -1.5232611904860027, -1.4804446693925655, -0.3733069528951633, 0.6565944608268954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5309588079582727, -0.5079534101611066, 0.032609806416965675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010578970365539403, 0.14720624483210576, 0.04724042044332186, 0.0, 0.5465283207656204, -0.19340193731544422, -0.5378172646018428, 0.1386679697997807, 0.34463398710626403, -0.18086356804695347, 0.006817274912495987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30262544477629516, 0.09583757801536633, -0.22315205786598608, 0.15942371374292477, -0.12082328881618842, -0.031938336831399336, 0.20472132948337274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063883932483591, -0.1933647843987567, -0.009552516326901475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000916494083057, 0.12770763567726107, 0.4830687392069244, 0.0, -0.26019308643958283, -0.22931048175714647, -2.4215463400455506, -1.1875815492128718, -2.6246036628231084, -0.24515225513938024, -0.9048815573555332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1647218529199097, 0.7783765005428815, 1.723859375416625, -1.5150999797468971, -1.486737404398827, -0.37496984157688623, 0.6669070107583583, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5412740650655505, -0.5176261007453624, 0.03217890689697536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010606101974169083, 0.1477413589706372, 0.04722295782352715, 0.0, 0.5456380666109822, -0.16908262597857465, -0.522481214502478, 0.1461534807055757, 0.37666483191527816, -0.1855687496936574, 0.020997239613460877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30632626208072616, 0.09031298949467995, -0.22692456938849484, 0.16322421478210972, -0.12585470012523042, -0.03325777363445849, 0.20625099862925758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20630514214555695, -0.19345381168511577, -0.008617990399806234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001438740509397, 0.13491240604240237, 0.4854280578776173, 0.0, -0.23325017153039881, -0.23668803750654724, -2.4469621100956136, -1.180043409121759, -2.604441923727538, -0.2542616803190728, -0.9034046231800951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1500139995816223, 0.7820642540186723, 1.711999903987663, -1.5061554522402196, -1.4934494542740804, -0.37658879725504163, 0.6770756911532064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5515865469940715, -0.5272662582455687, 0.03200561485251141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444928526822455, 0.1440954073028262, 0.04718637341385814, 0.0, 0.5388582981836805, -0.14755111498801532, -0.5083154010012589, 0.15076280182225638, 0.4032347819114077, -0.18218850359385164, 0.029538683508763354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2941570667657477, 0.07375506951581443, -0.23718942857923855, 0.17889055013354835, -0.13424099750506613, -0.03237911356310805, 0.20337360789696188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2062496385704195, -0.1928031500041254, -0.0034658408892790024]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001956923917136, 0.14209490819490286, 0.48778483406484985, 0.0, -0.20719014955641507, -0.2431537045007487, -2.4717559018778976, -1.1723466381173246, -2.5832851837647595, -0.26272698890159707, -0.9018119287954139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1362925875347156, 0.7846942107354439, 1.6995945594881667, -1.4962533594938423, -1.500654434469294, -0.37804175814020746, 0.6869377230363743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5618772554935478, -0.5362481924237863, 0.03193009384487926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001036366815479113, 0.14365004305001008, 0.047135523744650826, 0.0, 0.5212004394796748, -0.12931333988402918, -0.4958758356456816, 0.15393542008868819, 0.42313479925557457, -0.16930617165048542, 0.031853887693621664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2744282409381327, 0.052599134335431535, -0.24810688998992422, 0.1980418549275443, -0.1440996039042721, -0.029059217703316893, 0.1972406376633577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20581416998952623, -0.17963868356435048, -0.001510420152642911]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20002491398495875, 0.1494178801698363, 0.49014213867983025, 0.0, -0.18248615642303045, -0.24874252779424932, -2.495791256850934, -1.1643342319297219, -2.561549609322388, -0.27017462278306265, -0.9004516927928198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1235910388524077, 0.7862627988346579, 1.686786930289798, -1.4854969415594632, -1.5083462475227143, -0.3792270963843562, 0.6964032961833078, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5721284937799476, -0.544042023523245, 0.03174277720679715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010689491574809543, 0.14645943949866824, 0.047146092299607985, 0.0, 0.494079862667692, -0.11177646587001251, -0.4807070994607294, 0.1602481237520551, 0.43471148884742883, -0.14895267762931144, 0.027204720051883843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25403097364615596, 0.031371761984279836, -0.2561525839673737, 0.21512835868758007, -0.15383626106840426, -0.023706764882974334, 0.1893114629386691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2050247657279953, -0.15587662198917399, -0.00374633276164229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000302436587149, 0.1568804363366327, 0.4925089959261279, 0.0, -0.15942620646426864, -0.2535716429058741, -2.5191037233799887, -1.1561081590561926, -2.5395311185199434, -0.2762882019431225, -0.8995733094187667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1117286539701878, 0.7868744141902151, 1.6737792940401723, -1.474100709544747, -1.5164731868474546, -0.3800749465354888, 0.705439711141863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.582334625025694, -0.5505038053914475, 0.031328551739566904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010659347512320952, 0.14925112333592852, 0.04733714492595309, 0.0, 0.46119899917523643, -0.09658230223249553, -0.4662493305810919, 0.16452145747058344, 0.4403698160488929, -0.12227158320119691, 0.017567667481062112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23724769764439968, 0.012232307111143079, -0.26015272499251113, 0.2279246402943277, -0.16253878649480763, -0.016957003022651775, 0.1807282991711045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.204122624914929, -0.12923563736404983, -0.008284509344604833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000355409762551, 0.1643493632969471, 0.4948989781480506, 0.0, -0.138134306608576, -0.25778286324663996, -2.541755761063006, -1.1478203450866038, -2.517453701537978, -0.2808626769029118, -0.8993496529219878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1004377528853015, 0.7866677740581992, 1.6607635289911855, -1.4622859299485154, -1.5249653079719356, -0.38055155981383115, 0.7140521457823096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5924971178994362, -0.5556901650508949, 0.03066177407118626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010594635080377414, 0.14937853920628794, 0.047799644438453984, 0.0, 0.42583799711385245, -0.08422440681531787, -0.45304075366034996, 0.16575627939177673, 0.4415483396393033, -0.09148949919578589, 0.00447312993557779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22581802169772486, -0.004132802640316704, -0.2603153009797381, 0.2362955919246301, -0.16984242248962297, -0.00953226556684723, 0.17224869280893232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324985747484237, -0.1037271931889466, -0.01333555336761289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004081292641204, 0.17163111684490254, 0.4973273540293955, 0.0, -0.11861098806654552, -0.261506003937954, -2.563792455725704, -1.1396190617008346, -2.4954889007469143, -0.2838319038624897, -0.8998890469110882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0894421809363275, 0.7857788657157315, 1.6478909021820578, -1.4502320834056803, -1.5337515051369732, -0.3806565744431942, 0.7222674722419069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6026210959822068, -0.559746501253625, 0.029776897416194534]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010543900313926698, 0.14563507095910855, 0.048567517626897164, 0.0, 0.3904663708406098, -0.0744628138262803, -0.44073389325396295, 0.1640256677153848, 0.4392960158212723, -0.059384539191558075, -0.010787879782008984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21991143897947918, -0.017778166849353613, -0.2574525361825549, 0.2410769308567017, -0.17572394330075108, -0.0021002925872602293, 0.16430652919194655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20247956165541275, -0.08112672405460414, -0.01769753309983457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004606432832564, 0.1785368757147403, 0.4998084022537411, 0.0, -0.10078082637104352, -0.264847160038961, -2.5852379440488384, -1.131630598596612, -2.4737657902986205, -0.28524416183276086, -0.9012452613483256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.078500262559309, 0.7843260714150962, 1.6352650158000486, -1.4380627524161154, -1.5427684175926506, -0.3804169066440311, 0.7301226067745017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6127129574718959, -0.5628429113478618, 0.028737698239593924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001050280382721323, 0.1381151773967553, 0.04962096448691232, 0.0, 0.35660323391003995, -0.06682312202014098, -0.4289097664626888, 0.15976926208445047, 0.43446220896587195, -0.02824515940542372, -0.027124288744748738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21883836754036934, -0.029055886012705798, -0.2525177276401867, 0.24338661979130038, -0.1803382491135461, 0.004793355983261567, 0.1571026906518956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20183722979378182, -0.06192820188473633, -0.020783983532012218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005129930180776, 0.1849245954383537, 0.5023535969404489, 0.0, -0.0845365476780033, -0.26789192708329723, -2.606108693073243, -1.1239444492086228, -2.452378330247755, -0.2852004259172213, -0.903428031037695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0674226840202274, 0.7824081342080057, 1.6229472251942958, -1.4258507451503226, -1.5519634683297958, -0.3798798984965973, 0.7376575659920607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6227788903479773, -0.5651382965458367, 0.027612209173982813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010469946964228746, 0.12775439447226813, 0.05090389373415543, 0.0, 0.32488557386080436, -0.06089534088672406, -0.4174149804880978, 0.1537229877597814, 0.42774920101731634, 0.0008747183107913163, -0.04365539378738713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22155157078163232, -0.038358744141811715, -0.24635581211505642, 0.24424014531585422, -0.18390101474290552, 0.010740162948676057, 0.15069918435117943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2013186575216267, -0.0459077039594976, -0.02250978131222222]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005652136933838, 0.1907115542078159, 0.5049708022133425, 0.0, -0.06976173780440523, -0.27070753685227544, -2.6264208198234114, -1.116616946684467, -2.4313907896673914, -0.2838218803566358, -0.906412585221189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0560736135802962, 0.7801058082827312, 1.6109657132036308, -1.4136290432962257, -1.5612950664604608, -0.37910605441542466, 0.7449113819247415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6328242153560852, -0.5667667343942321, 0.026461026087480004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444135061213921, 0.1157391753892438, 0.052344105457870035, 0.0, 0.29549619747196143, -0.05631219537956404, -0.40624253500336754, 0.14655005048311465, 0.4197508116072699, 0.02757091121170977, -0.05969108366987838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22698140879862486, -0.046046518505490075, -0.23963023981329837, 0.24443403708193845, -0.18663196261329876, 0.015476881623452673, 0.14507631865361617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200906500162158, -0.032568756967906835, -0.023023661730056176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006173377981204, 0.19586946360562876, 0.5076644609626558, 0.0, -0.05634179204398947, -0.27334548158613015, -2.646193322366273, -1.1096790839813315, -2.410842927702957, -0.2812329746831892, -0.9101485177967618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0443638223042633, 0.7774845919923008, 1.5993249042842526, -1.4014024614291, -1.570731417155611, -0.3781624858127281, 0.751920026015881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6428532286355354, -0.5678352846961159, 0.025332638215552584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010424820947313969, 0.10315818795625725, 0.05387317498626852, 0.0, 0.26839891520831505, -0.05275889467709448, -0.3954500508572305, 0.138757254062713, 0.4109572392886899, 0.051778113468932276, -0.07471865151145703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23419582552065923, -0.05242432580860899, -0.23281617838756566, 0.24453163734251182, -0.1887270139030052, 0.018871372053931603, 0.14017288182279053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005802655890033, -0.02137100603767564, -0.02256775743854842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006693974018563, 0.20041148659983554, 0.5104356354131638, 0.0, -0.04416856961827303, -0.2758444403769414, -2.6654490711305923, -1.103143801672166, -2.3907551627710806, -0.2775528776658062, -0.9145677909379701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.032240873995808, 0.7745974410638581, 1.588013709038981, -1.3891577880418844, -1.5802488161344124, -0.37711757562047643, 0.7587156306949181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6528692669109263, -0.5684268272253782, 0.024262524580118537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010411920747207684, 0.09084045988413576, 0.0554234890101607, 0.0, 0.24346444851432894, -0.049979175816224464, -0.3851149752863885, 0.1307056461833094, 0.4017552986375233, 0.07360194034765936, -0.08838546282416829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2424589661691047, -0.05774301856885468, -0.2262239049054323, 0.24489346774431225, -0.19034797957602634, 0.020898203845033683, 0.13591209358074058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032076550781866, -0.011830850585245457, -0.02140227270868092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007214257134473, 0.2043774343813399, 0.5132834444778108, 0.0, -0.033141879221293254, -0.27823311442357535, -2.684214783748266, -1.0970116831686958, -2.3711334911723347, -0.27289151361168223, -0.9195916030855968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0196792372387637, 0.7714870996542419, 1.577012080120262, -1.3768717128358068, -1.5898299178620672, -0.376037003117718, 0.7653264677326032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6628748614477549, -0.5686045085855391, 0.023274225345194223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010405662318178713, 0.07931895563008712, 0.05695618129293898, 0.0, 0.22053380793959546, -0.04777348093267944, -0.3753142523534738, 0.12264237006940129, 0.3924334319749157, 0.09322728108248012, -0.10047624295253367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.251232735140885, -0.06220682819232286, -0.22003257837437873, 0.24572150412155103, -0.191622034553094, 0.02161145005516844, 0.13221674075370154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001118907365725, -0.003553627203219339, -0.019765984698486314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007734580778586, 0.20782070618049545, 0.5162057356413299, 0.0, -0.02316952921589255, -0.2805327086574647, -2.7025206472294165, -1.0912751301891823, -2.3519738846130913, -0.26734808709481267, -0.9251359659670314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0066716891018626, 0.7681879876718668, 1.5662958363212114, -1.364516539676587, -1.5994622264425942, -0.3749810550619353, 0.7717773035049438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728719094996554, -0.5684161418783988, 0.022381311534141354]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010406472882246143, 0.06886543598311097, 0.0584458232703806, 0.0, 0.19944700010801403, -0.04599188467778787, -0.36611726962300406, 0.11473105959026818, 0.3831921311848679, 0.11086853033739165, -0.11088725762869056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26015096273802274, -0.06598223964750083, -0.21432487598101155, 0.24710346318439644, -0.19264617161054026, 0.021118961115654065, 0.1290167154468116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994096103801032, 0.003767334142805944, -0.017858276221057384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008255327007832, 0.2107984551058236, 0.5192101868201725, 0.0, -0.014166840177746965, -0.2827589651423013, -2.7203998728202277, -1.085921389661834, -2.333265997210729, -0.2610109256209237, -0.9311159707638332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.993222525276789, 0.76472770791297, 1.5558399599130788, -1.3520640084958147, -1.609136898369661, -0.3740030351449078, 0.7780898891731596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6828618146769264, -0.5678979208460078, 0.02158961746419203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010414924584927073, 0.059554978506562724, 0.060089023576853036, 0.0, 0.18005378076291173, -0.044525129696731926, -0.35758451181622114, 0.10707481054696666, 0.3741577480472417, 0.12674322947777925, -0.11960009593603711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2689832765014719, -0.06920559517793774, -0.2091175281626519, 0.24905062361544741, -0.19349343854133583, 0.01956039834054967, 0.12625171336431662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19979810354541996, 0.01036442064782242, -0.015833881398986463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008787845500087, 0.21333432017666262, 0.522278620524105, 0.0, -0.005963419259842758, -0.2847067784692105, -2.737706908660592, -1.0808938141815105, -2.3150267722676117, -0.25438667800412285, -0.9374635516762867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9793618168468088, 0.7611051078601969, 1.545609423592007, -1.3394608678986315, -1.6188542055022237, -0.3731361931769705, 0.784273511539081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6928467960164502, -0.5671346529160782, 0.02093020073211555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010650369845106335, 0.050717301416780575, 0.06136867407865102, 0.0, 0.16406841835808414, -0.038956266538184035, -0.34614071680728536, 0.10055150960646979, 0.3647844988623467, 0.13248495233601743, -0.12695161824906995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27721416859960457, -0.07245200105546167, -0.20461072642143427, 0.2520628119436626, -0.194346142651256, 0.01733683935874627, 0.12367244731842914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19969962679047468, 0.015265358598590295, -0.013188334641529539]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000932460772157, 0.2154911957901415, 0.5254075520960675, 0.0, 0.0015154044261366864, -0.28641516619292723, -2.7544320930412285, -1.076174171725622, -2.2972498271597006, -0.24759982073920533, -0.9441141009023792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9651278873460428, 0.757327427091728, 1.535580448860818, -1.326672138264618, -1.628612812424153, -0.37240896197700574, 0.7903376336523634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7028278828753675, -0.5661656331890602, 0.020389486558202795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010735244429674809, 0.04313751226957778, 0.0625786314392504, 0.0, 0.14957647371958888, -0.03416775447433472, -0.33450368761273663, 0.09439284911777152, 0.35553890215822376, 0.13573714529835043, -0.13301098452185098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2846785900153182, -0.07555361536937943, -0.20057949462378213, 0.25577459268027014, -0.19517213843858824, 0.01454462399929483, 0.12128244226564817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.199621737178345, 0.019380394540359974, -0.010814283478255146]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000986504638207, 0.2173348800863795, 0.5285963538711298, 0.0, 0.008311286985787932, -0.2879703140158385, -2.770613356296178, -1.071752895513645, -2.2799188962291113, -0.24064150349451635, -0.9510100879683961, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9505529498723302, 0.7534056826233598, 1.5257378740419243, -1.3136770586139697, -1.63841007581735, -0.37184397678607, 0.7962921332243709, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7128055169800916, -0.5650064298475672, 0.019945411914984862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010808773209972387, 0.036873685924759945, 0.06377603550124566, 0.0, 0.13591765119302487, -0.031102956458224976, -0.32362526509899225, 0.08842552423953609, 0.3466186186117867, 0.13916634489377944, -0.13791974132033838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2914987494742535, -0.07843488936736323, -0.19685149637787305, 0.25990159301296684, -0.19594526786394395, 0.011299703818714464, 0.11908999144014908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19955268209448396, 0.023184066829859785, -0.008881492864358671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001040952281578, 0.21892164502751066, 0.5318443998538492, 0.0, 0.014455434372994066, -0.2894449297458632, -2.7863038589103057, -1.0676217341506595, -2.263014026217533, -0.23346849295648808, -0.9581014231716674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9356598942300804, 0.7493518268839664, 1.5160721145437042, -1.3004642700198759, -1.6482428027961602, -0.37145864779806914, 0.8021471910765554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7227798395497232, -0.5636600458570635, 0.019578016659266558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010889528674247463, 0.03173529882262352, 0.0649609196543887, 0.0, 0.12288294774412264, -0.029492314600493903, -0.313810052282559, 0.08262322725971165, 0.33809740023156404, 0.14346021076056528, -0.14182670406542525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2978611128449939, -0.08107711478786886, -0.19331518996440414, 0.2642557718818771, -0.19665453957620216, 0.007706579760017614, 0.11710115704369055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19948645139263124, 0.026927679810074084, -0.007347905114366092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001095818476272, 0.2202943968225748, 0.535150869996002, 0.0, 0.019976112404964497, -0.2908868408754237, -2.801560742506763, -1.0637723948338313, -2.246514853532375, -0.2260387914595803, -0.9653442577370467, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9204627132754218, 0.7451771967137655, 1.5065767335510407, -1.2870279213106035, -1.6581079764407811, -0.3712661111733493, 0.8079130441774274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7327508384249672, -0.5621229025816208, 0.01927182718937029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010973238938801623, 0.027455035901282798, 0.06612940284305621, 0.0, 0.11041356063940856, -0.028838222591209578, -0.3051376719291418, 0.07698678633656415, 0.3299834537031666, 0.1485940299381555, -0.14485669130758602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3039436190931732, -0.08349260340401757, -0.189907619853269, 0.26872697418544794, -0.19730347289241743, 0.003850732494397405, 0.11531706201743988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19941997750488044, 0.030742865508854446, -0.0061237893979253916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20011511096299092, 0.2214825190671099, 0.5385151065100857, 0.0, 0.02490084713840034, -0.2923229338625861, -2.8164412711336357, -1.060196351782816, -2.2304025030501005, -0.21832156697497618, -0.9726993825050722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9049681306376484, 0.740891755553815, 1.4972467377444765, -1.2733648666517141, -1.6680033011218867, -0.3712761292836445, 0.8135997040895893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7427184266565153, -0.560388285861029, 0.019015717754810958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011058230727444141, 0.023762444890702263, 0.06728473028167319, 0.0, 0.09849469466871684, -0.028721859743248285, -0.2976105725374558, 0.07152086102030841, 0.32224700964548914, 0.15434448969208248, -0.14710249536050946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30989165275546887, -0.08570882319900835, -0.1865999161312844, 0.27326109317778985, -0.19790649362210908, -0.00020036220590430396, 0.11373319824323874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935176463096194, 0.03469233441183588, -0.0051221886911865955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012068354139295, 0.22250349531401678, 0.5419369045324964, 0.0, 0.029256928531896972, -0.29376602433815924, -2.8310013768663658, -1.0568847414431133, -2.2146607151661373, -0.21029745116627052, -0.9801307890007165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8891775148909307, 0.7365037811966567, 1.4880774850525833, -1.2594727666522887, -1.677927543943993, -0.37149579637202673, 0.8192166918784729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.752682486082162, -0.5584484377725315, 0.018802084615086322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011145156804087516, 0.020419524938137586, 0.06843596044821347, 0.0, 0.08712162786993259, -0.02886180951146266, -0.2912021146546042, 0.06623220679405235, 0.3148357576792621, 0.1604823161741131, -0.14862812991288768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3158123149343549, -0.08775948714316552, -0.18338505383786374, 0.2778419999885099, -0.19848485644212302, -0.00439334176764448, 0.112339755777672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19928118851293328, 0.0387969617699493, -0.004272662794492707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012628164617755, 0.22332134060079772, 0.54541662471814, 0.0, 0.03317120156856523, -0.29518464960895535, -2.8451380890300952, -1.053961604220274, -2.1992726208632316, -0.20265878664500153, -0.9876002580722529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8730997429735209, 0.7319946575093498, 1.4790548783712623, -1.2453195416574887, -1.687887002196704, -0.37191213155652425, 0.8247616904031708, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7626439397110358, -0.556356609092534, 0.018669902169850008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001119620956917603, 0.01635690573561878, 0.06959440371287186, 0.0, 0.07828546073336504, -0.02837250541592201, -0.282734243274592, 0.05846274445678641, 0.30776188605811694, 0.15277329042537996, -0.14938938143072922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32155543834819605, -0.0901824737461377, -0.18045213362641968, 0.28306449989600013, -0.1991891650542251, -0.00832670368995064, 0.11089997049395796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19922907257747532, 0.04183657359994846, -0.002643648904726283]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013192442139177, 0.2239482275425103, 0.5489548371269524, 0.0, 0.0366715792278375, -0.296586524353173, -2.8588493933976524, -1.0514203929343469, -2.184236114366281, -0.1954379262848652, -0.9950902730344263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8567527786674105, 0.7273588576734159, 1.4701719485389229, -1.230888881533351, -1.6978848911636142, -0.37251543196268055, 0.8302341701041117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7726029312808944, -0.5541258337645512, 0.018610119682379557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001128555042845191, 0.0125377388342514, 0.07076424817624641, 0.0, 0.07000755318544544, -0.028037494884353635, -0.27422608735114595, 0.050824225718544155, 0.3007301299390082, 0.14441720720272663, -0.1498002992434688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32693928612220846, -0.09271599671867779, -0.17765859664678813, 0.28861320248275546, -0.1999577793382039, -0.012066008123126602, 0.1094495940188172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917983139717088, 0.044615506559656834, -0.0011956497494090225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013761457522716, 0.22440734591479483, 0.5525510066268541, 0.0, 0.03975911638397082, -0.29798216934315713, -2.8721656295211786, -1.0492191300271183, -2.1695526216527776, -0.18848173123026996, -1.0025971718647806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8401509814292484, 0.7225974376254728, 1.461426296142665, -1.2161747018287186, -1.7079221563356972, -0.3732971774069232, 0.8356348772421495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7825592728935553, -0.5517519790258053, 0.018604268532772555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011380307670761093, 0.009182367445690917, 0.07192338999803456, 0.0, 0.06175074312266636, -0.027912899799682093, -0.2663247224705193, 0.044025258144572164, 0.29366985427007, 0.13912390109190506, -0.15013797660708325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3320359447632418, -0.09522840095886133, -0.17491304792515783, 0.2942835940926487, -0.20074530344166105, -0.01563490888485266, 0.1080141427607551, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19912683225321814, 0.04747709477491714, -0.00011702299214006178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014335289543783, 0.22472031035488813, 0.5562052394000923, 0.0, 0.042430718224349184, -0.2993775663249582, -2.885124494559544, -1.0473129015067846, -2.155222804147192, -0.1816201348745458, -1.01012474190697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8233031935612874, 0.7177142448998596, 1.4528175204778178, -1.2011759013625687, -1.7179983908228533, -0.374249479327445, 0.8409652330108597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925126832685195, -0.5492244957458804, 0.018635373875526565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011476640421320383, 0.006259288801865879, 0.07308465546476407, 0.0, 0.05343203680756739, -0.027907939636021756, -0.25917730076730283, 0.03812457040667647, 0.28659635011170964, 0.13723192711448282, -0.1505514008437909, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.33695575735921823, -0.09766385451226353, -0.17217551329694306, 0.2999760093229975, -0.2015246897431223, -0.019046038410436672, 0.10660711537420353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906820749928394, 0.05054966559849752, 0.0006221068550801514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014914122512492, 0.22490281905863652, 0.5599181172915517, 0.0, 0.044685009011025914, -0.3007746371064331, -2.897763192892381, -1.0456630527405861, -2.1412454289020606, -0.1747151974114972, -1.0176787139885983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8062133777782159, 0.7127138428914443, 1.4443454795666644, -1.1858927542576552, -1.7281125254817933, -0.37536492761112034, 0.8462267964200866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8024628663707979, -0.5465312346100106, 0.018690277971370874]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011576659374156097, 0.0036501740749680742, 0.0742575578291891, 0.0, 0.04508581573353464, -0.027941415629497295, -0.25277396665674096, 0.03299697532397076, 0.2795475049026293, 0.13809874926097254, -0.15107944163256468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3417963156614319, -0.100008040168305, -0.1694408182230674, 0.30566294209827055, -0.20228269317880074, -0.022308965673506504, 0.10523126818453868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1990036620455675, 0.05386522271739528, 0.0010980819168861728]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20015498241295324, 0.22496358788852341, 0.5636906952949815, 0.0, 0.046523124895129254, -0.30217304171259973, -2.910116870810712, -1.0442383548647112, -2.127617660175425, -0.16766711338600437, -1.025262800625812, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7888816327849963, 0.7076004604520697, 1.4360093419839672, -1.170324783273599, -1.7382632426248827, -0.3766364801543263, 0.8514208330493006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8124095464110179, -0.5436605129536562, 0.018759558823811803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011682375656639517, 0.0012153765977381483, 0.0754515600685947, 0.0, 0.036762317682066795, -0.027968092123332625, -0.2470735583666168, 0.028493957517499034, 0.2725553745327172, 0.1409616805098563, -0.15168173274427474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3466348998643898, -0.10226764878749364, -0.16672275165394146, 0.31135941968112435, -0.20301434286178807, -0.02543105086411955, 0.10388073258428018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19893360080440123, 0.05741443312708689, 0.0013856170488185833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001608631206162, 0.22486724977568132, 0.5675244651508963, 0.0, 0.04804091382447449, -0.3035412422848025, -2.922052328864245, -1.043124700167149, -2.114336383673618, -0.16144541042735452, -1.0328762966158225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7713251667984461, 0.7023538524834112, 1.4278003950431948, -1.1544406355268644, -1.7484541924423087, -0.3780359169281584, 0.8565366409104427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8223535527855577, -0.5406644830067112, 0.018874481121896925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011761415325926333, -0.0019267622568418198, 0.0766753971182944, 0.0, 0.030355778586904754, -0.02736401144405591, -0.23870916107066367, 0.022273093951243095, 0.2656255300361335, 0.1244340591729968, -0.15226991980021082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35112931973100436, -0.10493215937317057, -0.16417893881545068, 0.3176829549346932, -0.20381899634852044, -0.02798873547664122, 0.1023161572228418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19888012749079415, 0.05992059893890097, 0.0022984459617024834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20016679470852397, 0.22461810660336734, 0.5714204886721297, 0.0, 0.0492515606625755, -0.3048795567549562, -2.9335321144560953, -1.0423074447214344, -2.10140738073954, -0.15596642624339424, -1.0405372644415392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7535642511419999, 0.6969653494000717, 1.4197151124779401, -1.1382226627253809, -1.7586848946400433, -0.37953926699620993, 0.8615644584658677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8322950464256667, -0.5375590699744391, 0.019029445546714298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011863175815503065, -0.0049828634462796215, 0.0779204704246687, 0.0, 0.024212936762020215, -0.026766289403073663, -0.229595711837008, 0.01634510891429119, 0.25858005868156314, 0.1095796836792056, -0.15321935651433463, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3552183131289241, -0.10777006166679028, -0.16170565130509318, 0.3243594560296713, -0.2046140439546916, -0.030067001361030556, 0.10055635110850149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1988298728021799, 0.06210826064544102, 0.003099288496347424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200172776239212, 0.2242322692592346, 0.5753793197616183, 0.0, 0.050143828812840734, -0.3061910582581071, -2.944550534505061, -1.041743376056535, -2.0888357341121013, -0.15093367718695333, -1.048277236264781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7356141941268067, 0.691432512186373, 1.4117532741877563, -1.121661763852356, -1.7689514159459603, -0.3811251082443771, 0.86649506189296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8422339086677469, -0.5343440199178914, 0.019210896739374525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001196306137608304, -0.007716746882654741, 0.07917662178977203, 0.0, 0.0178453630053046, -0.026230030063017495, -0.2203684009793198, 0.011281373297985921, 0.25143293254877075, 0.1006549811288182, -0.15479943646483557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3590011403038624, -0.11065674427397341, -0.15923676580367516, 0.3312179774604951, -0.2053304261183416, -0.031716824963344104, 0.09861206854184656, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19877724484160614, 0.06430100113095442, 0.003629023853204522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017880771966834, 0.2237276625238269, 0.5794013303291399, 0.0, 0.050699909006210096, -0.30747661967759615, -2.9551116517246165, -1.0413867886406278, -2.0766216597974223, -0.14608404137141487, -1.0561326296271798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7174848001385788, 0.6857562710597147, 1.4039161304800842, -1.10475315105645, -1.7792470152797084, -0.3827741958966008, 0.871319355442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8521699154814953, -0.5310119017509993, 0.01940522188486421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012062960912663622, -0.01009213470815384, 0.08044021135043324, 0.0, 0.011121603867387315, -0.025711228389780374, -0.21122234439110926, 0.007131748318146876, 0.2442814862935846, 0.09699271631076936, -0.1571078672479778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36258787976455753, -0.11352482253316624, -0.1567428741534436, 0.33817225591812267, -0.20591198667496285, -0.032981753044473566, 0.0964858709840395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.198720136274969, 0.06664236333784118, 0.0038865029097937334]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001848920125801, 0.22311939837896405, 0.5834870489289138, 0.0, 0.05090078540002527, -0.308735882796434, -2.9652229966883774, -1.0411980034684942, -2.064759670416598, -0.14123323192581774, -1.0641371565315465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6991809830148032, 0.679939291147258, 1.3962051220839664, -1.087493451223696, -1.7895626538601601, -0.3844693487373193, 0.8760279613648302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8621028082079024, -0.5275522348262791, 0.01960080649115936]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012168585823553865, -0.012165282897256904, 0.08171437199547749, 0.0, 0.004017527876303342, -0.025185262376756567, -0.2022268992752162, 0.0037757034426703215, 0.23723978761649236, 0.09701618891194237, -0.16009053808733326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3660763424755128, -0.1163395982491342, -0.15422016792235796, 0.34519399665507955, -0.2063127716090326, -0.03390305681437007, 0.09417211845336478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19865785452814178, 0.06919333849440365, 0.003911692125903012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001910339768254, 0.22241740746155528, 0.5876373692829787, 0.0, 0.05072825256032961, -0.3099686862518699, -2.9748947407521658, -1.0411450762759276, -2.0532395768694993, -0.13626393879654164, -1.0723170910833948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6807032804433021, 0.6739849745819401, 1.388621114169803, -1.0698788282800074, -1.7998873562412572, -0.3861952801931571, 0.8806108106665858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8720323358314703, -0.5239535080029184, 0.019788621026410307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012283928490566007, -0.014039818348175664, 0.083006407081299, 0.0, -0.0034506567939130836, -0.024656069108718866, -0.19343488127577046, 0.0010585438513315741, 0.2304018709419729, 0.09938586258552179, -0.1635986910369645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3695540514300244, -0.1190863313063596, -0.15168015828326817, 0.3522924588737728, -0.20649404762193996, -0.03451862911675506, 0.09165698603511138, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19859055247135768, 0.07197453646721513, 0.0037562907050189094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001972276229123, 0.22160015992593438, 0.5918536565550914, 0.0, 0.05023534327615232, -0.31115485912438157, -2.98399731890119, -1.0412776896283897, -2.0420522122641835, -0.1323673535576393, -1.08069297108184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6620730424338469, 0.6678791574614724, 1.3811606617335281, -1.0518815424837384, -1.8102108812872644, -0.3879171685167433, 0.8850471905233438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8819592391097035, -0.5202568933142251, 0.019987756381997294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012387292173853077, -0.016344950712418115, 0.08432574544225284, 0.0, -0.00985818568354585, -0.023723457450233045, -0.1820515629804796, -0.0026522670492431072, 0.22374729210631697, 0.07793170477804703, -0.16751759996890506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3726047601891036, -0.12211634240935253, -0.1492090487254995, 0.35994571592537883, -0.2064705009201449, -0.034437766471724654, 0.08872759713516082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853806556466372, 0.07393229377386722, 0.0039827071117397314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20020347439010194, 0.22066886640840974, 0.5961368789821828, 0.0, 0.04942137616753238, -0.3122911282120764, -2.9924717451619225, -1.0415807058060549, -2.0311924115217646, -0.12926459359144046, -1.0893046900564256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6433087343387187, 0.6616151695062485, 1.3738233634988397, -1.0334828954614335, -1.820518215348053, -0.3896034935502784, 0.8893152917455368, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918837518366295, -0.5164777926262232, 0.020196315181244682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001249353437924127, -0.018625870350492735, 0.0856644485418279, 0.0, -0.0162793421723988, -0.0227253817538959, -0.1694885252146481, -0.0060603235533009635, 0.21719601484837767, 0.06205519932397649, -0.17223437949171228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3752861619025646, -0.12527975910447817, -0.1467459646937689, 0.36797294044609824, -0.20614668121577498, -0.03372650067070167, 0.08536202444386097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984902545385202, 0.07558201376003792, 0.004171175984947794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002097713156489, 0.21963330701260128, 0.6004876430588264, 0.0, 0.04826735161790908, -0.31337521052871675, -3.0002854311434213, -1.042017856951844, -2.020651124882025, -0.12654774583476963, -1.0982068765058308, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6244231401634923, 0.6551909860127477, 1.3666107181270413, -1.014669781954262, -1.830789814952071, -0.3912255494765068, 0.8933920015145673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9018058862955415, -0.5126188329621287, 0.020406874864572447]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001259385109389794, -0.020711187916169344, 0.08701528153287227, 0.0, -0.023080490992466042, -0.021681646332807118, -0.1562737196299728, -0.008743022915782392, 0.21082573279478972, 0.054336955133416694, -0.17804372898810442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37771188350452867, -0.12848366987001567, -0.14425290743596728, 0.3762622701434281, -0.2054319920803594, -0.032441118524568074, 0.08153419538060984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19844268917823923, 0.07717919328188974, 0.004211193666555281]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021612092282184, 0.21850629281013784, 0.6049063830180879, 0.0, 0.04674694556987107, -0.3144054031470295, -3.0074185370116227, -1.0425507553929605, -2.010411408134718, -0.12394384477934386, -1.1074574531963899, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6054236679376318, 0.6486078022609617, 1.3595250401006225, -0.9954321389298569, -1.8410018235275876, -0.3927577856739413, 0.897252692534199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9117255410177183, -0.5086754720012359, 0.020610626904816205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001269921434586169, -0.022540284049268652, 0.08837479918522834, 0.0, -0.030408120960760072, -0.02060385236625595, -0.1426621173640283, -0.01065796882233028, 0.20479433494613986, 0.052078021108515345, -0.18501153381118132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37998944451720995, -0.1316636750357197, -0.1417135605283744, 0.38475286048810226, -0.20424017151033333, -0.030644723948690555, 0.07721382039263426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19839309444353564, 0.07886721921785816, 0.004075040804875125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022253027785625, 0.2172997061063792, 0.6093940275144712, 0.0, 0.044831410138811985, -0.31538213075779564, -3.0138605032598287, -1.0431464819052012, -2.0004478758145035, -0.12130496351048073, -1.1171087473807155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5863125474238096, 0.6418689300364602, 1.3525686390384142, -0.975760852223192, -1.8511263198677277, -0.3941779859496728, 0.9008708398699348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9216425579681401, -0.5046390286167527, 0.020799215252272733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012818710068790215, -0.024131734075172735, 0.08975288992766754, 0.0, -0.03831070862118175, -0.01953455221532188, -0.12883932496411699, -0.011914530244816071, 0.19927064640429257, 0.05277762537726262, -0.1930258836865146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38222241027644466, -0.13477744449003068, -0.13912802124416684, 0.39342573413329984, -0.20248992680280403, -0.02840400551462917, 0.07236294671471433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19834033900843503, 0.08072886768966328, 0.0037717669491305742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022900860672177, 0.21602149077378158, 0.6139508566643666, 0.0, 0.04249304529260065, -0.3163082802897171, -3.019609641149978, -1.0437794882828788, -1.9907280811770776, -0.11855834742913957, -1.127203397503628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56708689339683, 0.6349787981933329, 1.3457432785905576, -0.9556459545254953, -1.8611315315344155, -0.39546708486206655, 0.9042174428273831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9315567687691604, -0.5004987690426352, 0.020966024033625068]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012956657731027664, -0.02556430665195258, 0.09113658299790565, 0.0, -0.04676729692422672, -0.01852299063842921, -0.11498275780298244, -0.012660127553552256, 0.1943958927485175, 0.054932321626823176, -0.20189300245824846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38451308053959093, -0.13780263686254624, -0.136507208957131, 0.4022979539539349, -0.20010423333375432, -0.02578197824787499, 0.06693205914896853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982842160204063, 0.08280519148234991, 0.003336175627046675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20023567613729168, 0.21468232598148812, 0.618579669380404, 0.0, 0.039716685832498946, -0.3170317589450412, -3.0246594038591277, -1.0443415770723183, -1.9812217011084206, -0.11567135386636834, -1.13777905015814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477513703633965, 0.6279428756470102, 1.3390496574407549, -0.9350758302929199, -1.8709811549442146, -0.39660843413451846, 0.9072602766909373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9414681136338643, -0.49624739219259395, 0.02109857982582755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013335061139804465, -0.02678329584586907, 0.09257625432074831, 0.0, -0.05552718920203407, -0.014469573106482808, -0.1009952541829951, -0.011241775788790789, 0.19012760137314005, 0.05773987125542451, -0.21151305309023985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3867104606686719, -0.14071845092645366, -0.13387242299605406, 0.4114024846515084, -0.1969924681959818, -0.022826985449038478, 0.06085667727108461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982268972940784, 0.08502753700082558, 0.0026511158440496816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024248448796664, 0.2132817010339462, 0.6232850539165122, 0.0, 0.03648736491123274, -0.3176151113242534, -3.029022659188296, -1.0448138848933215, -1.9718877847713319, -0.11262628356749618, -1.1488617258468545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.52829997285123, 0.6207655905849384, 1.332488202871619, -0.914035823072634, -1.8806351577949825, -0.39758655139198784, 0.909962810616463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.951376543075006, -0.49187641030852547, 0.02119267081108958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013616701349902424, -0.028012498950838564, 0.0941076907221639, 0.0, -0.06458641842532403, -0.011667047584244146, -0.08726510658336331, -0.009446156420062756, 0.1866783267417718, 0.060901405977443104, -0.2216535137742917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3890279502433304, -0.1435457012414359, -0.1312290913827172, 0.42080014440571706, -0.19308005701535966, -0.01956234514938717, 0.054050678510513796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19816858882283422, 0.08741963768137005, 0.0018818197052405962]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024942643988033, 0.21179744237757436, 0.6280614356300516, 0.0, 0.032837414321974116, -0.31812578977269435, -3.0326111904443955, -1.0452508930410527, -1.9626876112700173, -0.11087403638981642, -1.1604767590735159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5087462976732324, 0.6134391523867183, 1.3260590187239967, -0.8924938010822095, -1.8900486175493625, -0.3983666197484187, 0.9122756140155615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9612828171656946, -0.48741756737242403, 0.021263334940033223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001388390382738015, -0.029685173127436876, 0.09552763427078588, 0.0, -0.07299901178517247, -0.010213568968818868, -0.07177062512199014, -0.008740162954621399, 0.18400347002629233, 0.035044943553595116, -0.23230066453322595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.391073503559951, -0.14652876396440218, -0.1285836829524449, 0.430840439808488, -0.1882691950876016, -0.015601367128617337, 0.04625606798196829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1981254818137743, 0.0891768587220289, 0.0014132825788728686]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025648617165462, 0.2102159997234052, 0.6329105085744566, 0.0, 0.02877294974059154, -0.31860398466958934, -3.0353794732601376, -1.0456722544572943, -1.9535790164030598, -0.10975106669980453, -1.1726841966576451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48909731099497733, 0.6059579119762081, 1.3197643797852852, -0.8704192973769448, -1.8991693651637631, -0.39891412960312955, 0.9141417636527343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711873739518471, -0.4828893418700921, 0.0213193368087825]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001411946354858873, -0.03162885308338303, 0.09698145888810075, 0.0, -0.08128929162765157, -0.009563897937899444, -0.05536565631484504, -0.008427228324830742, 0.18217189733915135, 0.022459393800237974, -0.24414875168258673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39297973356510235, -0.1496248082102037, -0.12589277877422897, 0.44149007410529506, -0.1824149522880104, -0.01095019709421708, 0.03732299274345578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19809113572304787, 0.0905645100466391, 0.0011200373749855554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20026365067228066, 0.20853153423470647, 0.6378348053398177, 0.0, 0.024287414359991967, -0.31906383544072553, -3.03730358821359, -1.0460803808476857, -1.944506846300838, -0.10880336925481057, -1.1855679286607015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46935386567918885, 0.5983182674664688, 1.3136084475674703, -0.8477824018146772, -1.9079370164244762, -0.3991966785218747, 0.9154962070713135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9810904491676253, -0.47830120746567945, 0.021365983100818976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014329001252086628, -0.0336893097739748, 0.09848593530722288, 0.0, -0.08971070761199146, -0.009197015422723371, -0.03848229906904507, -0.008162527807830557, 0.18144340204443837, 0.018953948899879114, -0.2576746400611291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39486890631576926, -0.1527928901947863, -0.12311864435629659, 0.4527379112453502, -0.17535302521426147, -0.005650978374902695, 0.02708886837158525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19806150431556513, 0.09176268808825254, 0.0009329258407294982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002709181633583, 0.2067445984866543, 0.6432883074780156, 0.0, 0.019368020415770022, -0.319506030596099, -3.0383767612417256, -1.0464716606443134, -1.93539817392384, -0.10785793321986444, -1.1992183447754208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.449511737566043, 0.5905186190172917, 1.30759712755751, -0.8245528155742337, -1.9162819395303767, -0.39918565990323196, 0.9162647015301013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9909921334418351, -0.4736560022976525, 0.021405717349798476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014534982155259296, -0.035738714961043055, 0.1090700427639566, 0.0, -0.0983878788844389, -0.008843903107469055, -0.021463460562710514, -0.007825595932554615, 0.1821734475399597, 0.018908720698922653, -0.2730083222943843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39684256226291714, -0.15599296898354148, -0.1202264001992059, 0.46459172480887045, -0.1668984621180081, 0.0002203723728545822, 0.015369889175756525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19803368548419537, 0.09290410336053989, 0.000794684979589968]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20027829438051795, 0.20485868510348465, 0.6490013560727583, 0.0, 0.014002434650858962, -0.31992610835046786, -3.0386077281967667, -1.0468412358708508, -1.9261612032181843, -0.10686461645591573, -1.2137239690189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295630481332781, 0.5825587072681266, 1.3017382359732208, -0.8006983855868464, -1.9241240546061331, -0.39885668361580096, 0.9163618604901093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0008924345494923, -0.4689530184259971, 0.02143932756822293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001475243431933699, -0.037718267663393076, 0.11426097189485505, 0.0, -0.10731171529822119, -0.008401555087377478, -0.0046193391008222465, -0.007391504530747066, 0.18473941411311273, 0.01986633527897399, -0.2901124848695834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39897378865529753, -0.15919823498330188, -0.11717783168578469, 0.4770885997477463, -0.15684230151512948, 0.006579525748620504, 0.0019431792001582751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980060221531453, 0.09405967743310696, 0.0006722043684891009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028578925979554, 0.20287743274338085, 0.6547406686796089, 0.0, 0.008185018820865536, -0.32031794640898287, -3.0380197116706626, -1.0471838245626715, -1.9166848868198592, -0.10581108299932915, -1.2291713152384198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.409497880984442, 0.5744384300934184, 1.2960420336682963, -0.7761829962429637, -1.9313712603623479, -0.39818884409194577, 0.9156880981674309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0107913532621287, -0.46419123734401335, 0.021467110255929775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014989758555187285, -0.03962504720207571, 0.11478625213701081, 0.0, -0.11634831659986852, -0.007836761170300528, 0.011760330522081603, -0.0068517738364139965, 0.18952632796650123, 0.02107066913173159, -0.30894692439039756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4013033429767219, -0.16240554349416467, -0.11392404609848922, 0.49030778687765375, -0.1449441151242955, 0.013356790477103832, -0.01347524645356626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19797837425272766, 0.09523562163967537, 0.0005556537541368603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20029341668299114, 0.20080310284452807, 0.6604121090446456, 0.0, 0.001921849586408484, -0.3206748265522026, -3.036649950845352, -1.0474931959378289, -1.9068372060650318, -0.10469342341170036, -1.2456491252742798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38930633750726457, 0.5661566921582276, 1.2905223641067847, -0.750964653980663, -1.9379170515353874, -0.3971633693842987, 0.9141253637504341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0206889396240197, -0.45937220777499244, 0.021489539567299338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015254846391213545, -0.04148659797705568, 0.11342880730073404, 0.0, -0.12526338468914103, -0.007137602864394741, 0.027395216506216978, -0.006187427503146391, 0.1969536150965476, 0.022353191752575823, -0.32955620071719854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.403830869543549, -0.16563475870381658, -0.11039339123023295, 0.5043668452460132, -0.13091582346079012, 0.020509494152941406, -0.03125468833993677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979517272378216, 0.09638059138041875, 0.00044858622739128284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030119568854826, 0.19863638606599057, 0.6660139722038477, 0.0, -0.0047654859416252715, -0.32098958444084497, -3.034549899605448, -1.047761372718335, -1.8964610837443059, -0.10350850752967147, -1.2632545889497222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3689808614367368, 0.5577104480698207, 1.2851985271167368, -0.7249939125996567, -1.9436369605967867, -0.39576205076792975, 0.9115313297721367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305853548399064, -0.45450238080270544, 0.021507407707782908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015558011114232356, -0.04333433557074981, 0.1120372631840425, 0.0, -0.1337467105606751, -0.006295157772847987, 0.04200102479807478, -0.005363535610125525, 0.207522446414517, 0.023698317640577764, -0.3521092735088453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40650952141055535, -0.16892488176813872, -0.10647673980095607, 0.5194148276201257, -0.11439818122798806, 0.028026372327378497, -0.05188067956594836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792830431773525, 0.09739653944573959, 0.0003573628096714333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030914634140978, 0.19637390500117713, 0.6715828451201916, 0.0, -0.011823845857501004, -0.32125109674842384, -3.0317232352621573, -1.047993758889174, -1.8853759253989026, -0.10350850752923797, -1.282109695006647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34853531759768974, 0.5490903893140774, 1.2800996783217704, -0.6982100150772024, -1.9483808813828611, -0.3939543090524812, 0.9077272656514751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0404812611623253, -0.44961272326613566, 0.021525033954934155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001590130572305638, -0.045249621296268805, 0.11137745832687744, 0.0, -0.14116719831751465, -0.005230246151577747, 0.056533286865820584, -0.004647723416777062, 0.22170316690806577, 8.670054257864379e-12, -0.37710212113849784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4089108767809417, -0.17240117511486672, -0.10197697589932689, 0.535677950449087, -0.09487841572149006, 0.036154834308971096, -0.07608128241323243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19791812644837758, 0.09779315073139577, 0.00035252494302495706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003172693409572, 0.1940175527107981, 0.6771603689056768, 0.0, -0.019193679667741763, -0.321440476638921, -3.028179268613157, -1.0481732072969074, -1.8733471366727263, -0.10350850752836022, -1.3024202699248018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3279913270141919, 0.5402847239915176, 1.2752683565321803, -0.670544663390444, -1.9519661143688292, -0.39170631156022995, 0.9024892898828979, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0503774344917505, -0.4447394511672975, 0.021544256271463894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016245999094805286, -0.047127045807580724, 0.11155047570970374, 0.0, -0.1473966762048152, -0.0037875978099430434, 0.07087933298000587, -0.003588968154669996, 0.24057577452352463, 1.7555029717154477e-11, -0.40621149836309306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4108798116699565, -0.17611330645119624, -0.09662643579180089, 0.5533070337351663, -0.07170465971936085, 0.04495994984502532, -0.10475951537154438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792346658850413, 0.09746544197676281, 0.000384446330594774]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032562408611035, 0.19157898268789894, 0.6827789936632113, 0.0, -0.02680877064690194, -0.32154935222513786, -3.0239496911498267, -1.048269333871253, -1.8600634801830365, -0.10350850752892245, -1.3244520270897273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3073749799692585, 0.5312801892863821, 1.2707653820007925, -0.641920890359514, -1.9541671935741474, -0.38898616714406864, 0.8955337475218497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0602746926488202, -0.43992003567794874, 0.02156267750140531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016709490306319699, -0.04877140045798318, 0.11237249515069075, 0.0, -0.15230181958320357, -0.002177511724336902, 0.0845915492666035, -0.0019225314869087012, 0.2656731297937968, -1.1244587338957728e-11, -0.440635143298511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41232694089866834, -0.18009069410271097, -0.09005949062775538, 0.5724754606185991, -0.04402158410636586, 0.05440288832322622, -0.13911084722096373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979451631413971, 0.09638830978697575, 0.0003684245988282738]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003343827899983, 0.18908234189505516, 0.6884591475134899, 0.0, -0.03458886264762535, -0.32156845280526186, -3.019089507224257, -1.0482170064255085, -1.8451117116401439, -0.10350850752801133, -1.348545726744807, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.28671800434849704, 0.5220618657484017, 1.2666775150992649, -0.6122492040576393, -1.9547005956772974, -0.38576786993113416, 0.886494070350839, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0701739237493035, -0.4351940617873942, 0.02157207271245176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017517407775899616, -0.04993281585687589, 0.11360307700557186, 0.0, -0.15560184001446814, -0.0003820116024801435, 0.09720367851139555, 0.0010465489148875277, 0.29903537085785037, 1.8222420301728088e-11, -0.48187399310159584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4131395124152298, -0.18436647075960821, -0.08175733803055242, 0.5934337260374951, -0.010668042062998706, 0.06436594425868974, -0.18079354342021137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19798462200966607, 0.09451947781108981, 0.00018790422092902821]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003437113012565, 0.1865590655037719, 0.6942110743842566, 0.0, -0.042433366863801565, -0.32148710723549906, -3.013687044176947, -1.0479506258393319, -1.8279278250508226, -0.10350850752730906, -1.3751539477281702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26605257839378216, 0.5126101957533383, 1.263130067889564, -0.5814169572975708, -1.953201116026987, -0.38203307191891245, 0.8748821920655593, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0800761664844183, -0.43060595297904586, 0.021563618093416753]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018657022516393627, -0.05046552782566498, 0.11503853741533392, 0.0, -0.15689008432352433, 0.0016269113952556665, 0.10804926094620285, 0.00532761172353181, 0.34367773178642597, 1.4045463697372213e-11, -0.5321644196672647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41330851909429756, -0.1890333999012687, -0.07094894419401514, 0.6166449352013684, 0.02998959300620538, 0.07469596024443391, -0.23223756570559562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19804485470229513, 0.09176217616696702, -0.00016909238070013938]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20035384746092152, 0.18404512675042728, 0.7000380490622289, 0.0, -0.050212851054079896, -0.32129764731835564, -3.007872020375405, -1.047408573474381, -1.807714696520507, -0.1035085075265131, -1.4049158957652377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24540734864367067, 0.5028965248793075, 1.260308356335637, -0.5492699698748068, -1.949181545315102, -0.3777738292535714, 0.8600228144996451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899826588460824, -0.42620844655981927, 0.021530459334271956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020272319330068492, -0.050278775066892704, 0.11653949355944743, 0.0, -0.1555896838055666, 0.003789198342868636, 0.11630047603084057, 0.01084104729901766, 0.4042625706063127, 1.5919110619624917e-11, -0.5952389607413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41290459500222965, -0.19427341748061752, -0.0564342310785417, 0.6429397484552792, 0.08039141423770374, 0.08518485330682168, -0.2971875513182835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19812984723328245, 0.08795012838453235, -0.0006631751828959446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036843163460358, 0.18136281953048786, 0.7059390781648229, 0.0, -0.057767388905325394, -0.3210710738639323, -3.0019894450633307, -1.0466631557182662, -1.7833826261393904, -0.10350850752649103, -1.4386498684378064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22607875701511615, 0.49392618538752037, 1.2587569083891101, -0.5184133404197366, -1.941897647938553, -0.3738639731587597, 0.8417880744913834, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0998962708048692, -0.4221692529637803, 0.021686362584224045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002916834736410404, -0.053646144398788474, 0.1180205820518809, 0.0, -0.1510907570249099, 0.0045314690884670624, 0.1176515062414791, 0.014908355122296033, 0.4866414076223328, 4.4136456503999646e-13, -0.6746794534513738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3865718325710906, -0.17940678983574165, -0.03102895893053481, 0.6171325891014039, 0.1456779475309793, 0.07819712189623458, -0.36469480016523564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19827223917573664, 0.08078387192078006, 0.0031180649990417805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003942537113021, 0.17828529615059197, 0.7119086970749711, 0.0, -0.06481104577349599, -0.32095649077276867, -2.9965751754981027, -1.0458472146225162, -1.753576222358894, -0.10350850752557518, -1.476720268237994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21045717232158523, 0.4874910167006223, 1.2591597974561297, -0.492597068932329, -1.930827428581285, -0.371992393713558, 0.821011277691062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1098211641847406, -0.4187433454099081, 0.02231639502794631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000516441533970284, -0.061550467597917866, 0.11939237820296275, 0.0, -0.14087313736341175, 0.0022916618232726514, 0.10828539130455896, 0.016318821914997908, 0.5961280756099278, 1.8317036250482457e-11, -0.7614079960037541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.31243169387061864, -0.12870337373796226, 0.008057781340389522, 0.5163254297481521, 0.22140438714536217, 0.03743158890403379, -0.4155359360064289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984978675974289, 0.06851815107744402, 0.012600648874445338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004388397255267, 0.17485617009380533, 0.7179373658089209, 0.0, -0.0708799625458358, -0.32108736955233547, -2.9921991868446067, -1.0449728458633074, -1.7183656050601326, -0.103508507551078, -1.5186732699592207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20058607313259408, 0.48488016496026076, 1.261770084558291, -0.47557115538422545, -1.9164565911539984, -0.3734251779064008, 0.7994134183993886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1197616468296943, -0.41613950387568394, 0.023478168149860274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008917202844920643, -0.06858252113573299, 0.12057337467899516, 0.0, -0.12137833544679619, -0.002617575591335923, 0.08751977306991583, 0.01748737518417392, 0.70421234597523, -5.100565746783541e-10, -0.8390600344245331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19742198377982317, -0.052217034807230445, 0.052205742043229766, 0.34051827096207177, 0.2874167485457316, -0.028655683856854998, -0.43195718583346787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19880965289907265, 0.0520768306844828, 0.023235462438279234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005152505839828, 0.1713391455780551, 0.7240261343656306, 0.0, -0.0757735884958979, -0.3213355926797959, -2.9889814816028712, -1.0440263392981617, -1.6783008240333939, -0.10350850760301146, -1.5640162619985774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19755116875234574, 0.48665761041572353, 1.2661729829388388, -0.4710855997270218, -1.9005937735528882, -0.3787027586782937, 0.7798707452587533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.129720437439687, -0.4144030404743032, 0.02505428898970948]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015282171691219392, -0.07034049031500482, 0.12177537113419343, 0.0, -0.09787251900124191, -0.004964462549208628, 0.0643541048347083, 0.018930131302915862, 0.8012956205347723, -1.0386692511734449e-09, -0.9068598407871321, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06069808760496673, 0.03554890910925572, 0.08805796761095572, 0.08971111314407304, 0.31725635202220503, -0.10555161543785882, -0.3908534628127065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917581219985286, 0.034729268027614696, 0.03152241679698409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20065601839622627, 0.16807247951426837, 0.7301320595769725, 0.0, -0.07969648408535791, -0.32176962153628585, -2.986607289663825, -1.0431390960024967, -1.6342489992114075, -0.10350850760306361, -1.6122408329025861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20067328395522496, 0.492400892843251, 1.2716015314676967, -0.47859763667929617, -1.8855827822470475, -0.3876223444709693, 0.7649963838140723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1396650036073466, -0.41338405076823215, 0.026870077922475817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0028153562448687964, -0.06533332127573466, 0.12211850422683904, 0.0, -0.07845791178920039, -0.008680577129799173, 0.04748383878092355, 0.017744865913298997, 0.881036496439728, -1.042922814899149e-12, -0.9644914180801775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062442304057584455, 0.11486564855054912, 0.10857097057715762, -0.1502407390454879, 0.30021982611681386, -0.1783917158535125, -0.29748722889361945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19889132335319332, 0.02037979412142081, 0.036315778655326744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20096542306793036, 0.1654449932387038, 0.7362508424313801, 0.0, -0.08304710453424663, -0.32573663391034274, -2.9837188757965825, -1.0443762733868391, -1.5870075393538325, -0.10521373332923009, -1.662240832902595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2086725093691195, 0.5012186466235822, 1.2773543946865247, -0.496107667472857, -1.874211870670797, -0.3994081790168006, 0.7573401079606881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1494812901559333, -0.4128914605340995, 0.02866861537375455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006188093434081931, -0.0525497255112915, 0.1223756570881518, 0.0, -0.06701240897777443, -0.07934024748113738, 0.05776827734485358, -0.024743547686851254, 0.9448291971514986, -0.034104514523329695, -1.0000000000001805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998450827789035, 0.17635507560662322, 0.1150572643765603, -0.35020061587121726, 0.22741823152500568, -0.2357166909166251, -0.15312551706768568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1963257309717322, 0.009851804682653769, 0.03597074902557463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20152838728931086, 0.16369481209325562, 0.7423906816198869, 0.0, -0.08691864583703286, -0.3314701379428469, -2.9768146445403336, -1.0486542064114133, -1.5393105615783342, -0.11197817370281932, -1.712240832902578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22038123413262947, 0.5120842470988328, 1.282798670935164, -0.5219493598008356, -1.870009977014743, -0.4126385789809851, 0.7601173661938881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158737285299586, -0.41276466205298745, 0.030274916064017]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011259284427610077, -0.035003622908963465, 0.12279678377013534, 0.0, -0.07743082605572461, -0.11467008065008287, 0.13808462512497643, -0.08555866049148067, 0.9539395555099669, -0.13528880747178448, -0.999999999999657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2341744952701998, 0.21731200950501292, 0.1088855249727857, -0.5168338465595709, 0.08403787312108424, -0.2646079992836903, 0.05554516466400122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18511990287305707, 0.0025359696222403425, 0.03212601380524895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20202627967430978, 0.16284106308747984, 0.7485249734313544, 0.0, -0.09344210826657097, -0.33808688780499263, -2.962144595895054, -1.0563212869545757, -1.4949080658849068, -0.1275518286405913, -1.7622408329025676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2350154259370006, 0.5242289585463547, 1.287687448692728, -0.5546227136632432, -1.873673089113286, -0.42613294628406545, 0.7728950815705997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1674067985535097, -0.41296480272338026, 0.031647632194646884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009957847699978529, -0.017074980115515438, 0.12268583622935114, 0.0, -0.1304692485907622, -0.1323349972429145, 0.29340097290509703, -0.15334161086325052, 0.8880499138684388, -0.31147309875544, -0.9999999999997944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.29268383608742216, 0.24289422895043714, 0.09777555515128335, -0.6534670772481537, -0.0732622419708612, -0.2698873460616072, 0.25555430753423225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17339026507847224, -0.004002813407856775, 0.027454322612597743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.202398800107997, 0.16280683147053426, 0.7545672663418745, 0.0, -0.10236052291981554, -0.34514526068085766, -2.938669555357371, -1.066806922522258, -1.4566519388420978, -0.15099873731396388, -1.8122408329025614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2521359232549917, 0.5371313790297202, 1.2922238548942178, -0.5927613967532037, -1.8839800229080845, -0.4391346299700987, 0.794086424033654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1756525480679787, -0.413549951262761, 0.03278605831622804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007450408673744192, -0.0006846323389115214, 0.12084585821040356, 0.0, -0.17836829306489152, -0.141167457517301, 0.4695008107536621, -0.2097127113536453, 0.7651225408561788, -0.4689381734674513, -0.9999999999998763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3424099463598216, 0.2580484096673115, 0.090728124029795, -0.76277366179921, -0.20613867589596885, -0.26003367372066566, 0.42382684926108727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16491499028938097, -0.01170297078761519, 0.022768522431623063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2027163628310531, 0.163548418785463, 0.7604249409633889, 0.0, -0.1129019331978828, -0.34889525657054227, -2.9078895229271913, -1.0783023625548778, -1.4236392592615992, -0.1812568968502859, -1.862240832902567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27156293012603155, 0.5504404420941427, 1.2967143864739177, -0.6352723432251367, -1.8997476245278966, -0.4511342511228243, 0.8224317087991058, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.18355943573368, -0.4145957872726459, 0.03365033610337059]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006351254461121899, 0.014831746298575024, 0.11715349243028593, 0.0, -0.21082820556134538, -0.07499991779359372, 0.6156006486035991, -0.2299088006523955, 0.6602535916099723, -0.6051631907264403, -1.000000000000111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3885401374207975, 0.26618126128844893, 0.08981063159399902, -0.85021892943866, -0.31535203239624304, -0.23999242305451118, 0.5669056953090346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15813775331402652, -0.020916720197697428, 0.01728555574285116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20300062721202383, 0.16503843169782795, 0.7660373673432823, 0.0, -0.12443766154595379, -0.35264525165413685, -2.8712654969834506, -1.0900256812328397, -1.3939445447531358, -0.217290875746959, -1.9122408329024576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29321619565331164, 0.563902471783936, 1.3017963568395874, -0.6812811004027302, -1.920152501583522, -0.46209018873095564, 0.856740237231522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1912604617573923, -0.41613681364612143, 0.0342114464647145]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005685287619414848, 0.029800258247298695, 0.11224852759786824, 0.0, -0.23071456696141968, -0.07499990167189127, 0.7324805188748166, -0.23446637355923902, 0.5938942901692699, -0.7206795779334619, -0.9999999999978096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4330653105456018, 0.2692405937958666, 0.10163940731339415, -0.92017514355187, -0.4080975411125062, -0.21911875216262716, 0.6861705686483266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1540205204742444, -0.030820527469511003, 0.01122220722687825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20327350143028525, 0.16728785758489248, 0.7713944842449668, 0.0, -0.1366453821212773, -0.35264524971890543, -2.829966276228405, -1.1011813700863278, -1.3659979985495936, -0.25811805886428807, -1.9622408329024688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.317005942110701, 0.5772663034002397, 1.3082663081475974, -0.7300881061447986, -1.9449740073709518, -0.4723040399021917, 0.8960526609708361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1988628223791276, -0.4181387944267183, 0.034438861496440466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005457484365228559, 0.04498851774129044, 0.10714233803369108, 0.0, -0.24415441150647035, 3.8704628849139944e-08, 0.8259844151009157, -0.2231137770697607, 0.5589309240708441, -0.8165436623465813, -1.000000000000223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47579492914778665, 0.26727663232607307, 0.12939902616019983, -0.976140114841369, -0.49643011574859736, -0.2042770234247212, 0.786248474786281, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1520472124347034, -0.040039615611937036, 0.004548300634519246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354427407946665, 0.17029590589764237, 0.7765242390469841, 0.0, -0.14957609567993307, -0.3526452497225634, -2.784926899624365, -1.111502092915575, -1.3387330147559335, -0.30277980535815, -2.012240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3425978958829109, 0.59021135720085, 1.3168912697811177, -0.7800881312000915, -1.9743114642801527, -0.4823756353417002, 0.939502599962036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2064712450597492, -0.42048907395168095, 0.0343385347184016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005415452983628351, 0.06016096625499762, 0.10259509604034556, 0.0, -0.25861427117311553, -7.315934072253455e-11, 0.900787532080797, -0.20641445658494453, 0.5452996758732007, -0.8932349298772394, -0.9999999999999883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5118390754441977, 0.258901076012207, 0.17249923267040806, -1.0000005011058573, -0.5867491381840184, -0.20143190879016956, 0.8689987798239975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15216845361243223, -0.047005590499253035, -0.0020065355607773996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20380902679416726, 0.1740250608263596, 0.7814815414939414, 0.0, -0.16345409175240433, -0.35264524972256756, -2.7368953983411313, -1.1210488685706324, -1.3114909002989157, -0.3505092025532365, -2.062240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3694491359183932, 0.6024375144364038, 1.3280363297310942, -0.8300881562554033, -2.008190975646627, -0.49297056126018424, 0.9862625511421699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2141691199585547, -0.4230301045584226, 0.033953799488170976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005295054294012406, 0.07458309857434448, 0.09914604893914625, 0.0, -0.277559921449425, -8.306185477170416e-14, 0.960630025664667, -0.19093551310114656, 0.544842289140358, -0.954587943901729, -0.9999999999999948, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5370248007096454, 0.2445231447110752, 0.22290119899952948, -1.0000005011062378, -0.6775902273294845, -0.2118985183696804, 0.9351990236026778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15395749797610853, -0.05082061213483312, -0.007694704604612444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20405302516662302, 0.17839110823571697, 0.7863344254845989, 0.0, -0.17851430003789928, -0.35264524972255495, -2.686895373285901, -1.1300227185258729, -1.2838256251509144, -0.40050922760850854, -2.112240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3969237492142522, 0.613741097894437, 1.3415486574536832, -0.8800881813106121, -2.0459772709518442, -0.504647076992953, 1.0355802259860223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2220102602948362, -0.4255933560538981, 0.03335268787598558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004879967449115027, 0.0873209481871476, 0.09705767981314739, 0.0, -0.30120416570989883, 2.525265043987572e-13, 1.000000501104607, -0.17947699910481119, 0.5533055029600262, -1.0000005011054416, -0.9999999999999959, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5494922659171806, 0.22607166916066412, 0.2702465544517814, -1.0000005011041742, -0.7557259061043429, -0.23353031465537516, 0.9863534968770462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15682280672562757, -0.05126502990950946, -0.012022232243707826]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20427427775571064, 0.1832657630480131, 0.7911560606975594, 0.0, -0.19402046241882806, -0.3526452497225476, -2.6369255548772657, -1.1381357395602882, -1.2541818029209706, -0.4505092526637864, -2.1622408329024654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4241780894055525, 0.6240109137311005, 1.3565984597849061, -0.9300882063658712, -2.086394358193773, -0.5175612797107543, 1.085580225986022, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2299439964350036, -0.4280393053467843, 0.03261250819647751]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004425051781752245, 0.09749309624592228, 0.09643270425921166, 0.0, -0.3101232476185755, 1.46698788079243e-13, 0.9993963681727096, -0.16226042068830895, 0.5928764445988757, -1.0000005011055564, -0.9999999999999505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5450868038260062, 0.2053963167332707, 0.3009960466244557, -1.0000005011051827, -0.8083417448385756, -0.2582840543560268, 0.9999999999999947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15867472280334796, -0.04891898585772456, -0.014803593590161389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20448925460959733, 0.1884861482941713, 0.7960013837556438, 0.0, -0.20812797112921447, -0.3526452497225536, -2.590735943115225, -1.1442111287049983, -1.2195158208931738, -0.5005092777190392, -2.2122408329024843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4501567220181025, 0.6334540335899963, 1.3712930643842167, -0.9782469378031894, -2.1265963620534154, -0.531072591019149, 1.1355802259860202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2377756105301416, -0.43028076956376143, 0.03180917214483589]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004299537077733934, 0.10440770492316372, 0.09690646116168819, 0.0, -0.28215017420772837, -1.204229784694197e-13, 0.923792235240814, -0.12150778289419997, 0.6933196405559353, -1.0000005011050557, -1.000000000000377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5195726522509989, 0.1888623971779163, 0.29389209198621125, -0.9631746287463633, -0.8040400771928422, -0.2702262261678953, 0.9999999999999597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1566322819027592, -0.04482928433954309, -0.016066721032832413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2047468885177489, 0.19387014210656023, 0.8008866381240283, 0.0, -0.21961803998109392, -0.3521226426517718, -2.5514919148248616, -1.1465010588890092, -1.1798068664050003, -0.5505093027742914, -2.262240832902491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4737450900696767, 0.642079354452608, 1.3843459861892113, -1.0220309843042243, -2.1630376093293977, -0.5443202336407252, 1.1818302260191775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2452004234030019, -0.4322623985728623, 0.031009374273467866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005152678163031458, 0.10767987624777886, 0.09770508736768965, 0.0, -0.2298013770375888, 0.010452141415636393, 0.784880565807272, -0.04579860368021922, 0.794179089763471, -1.0000005011050457, -1.0000000000001337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47176736103148464, 0.17250641725223376, 0.2610584360998941, -0.8756809300207011, -0.7288249455196422, -0.2649528524315232, 0.9250000006631481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14849625745720518, -0.03963258018201765, -0.015995957427360454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2051287495455325, 0.19923065914216656, 0.8057737414679297, 0.0, -0.2281785742138778, -0.35022616837644915, -2.519391471608246, -1.1433405956760947, -1.136039702814632, -0.6005093278295216, -2.3122408329025026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4940033565817461, 0.6497248585809339, 1.3951808982628564, -1.059285479802085, -2.192812112797505, -0.5564281233814546, 1.2207959277732934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2519001603691544, -0.4339526108995303, 0.030265197010617452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007637220555672521, 0.10721034071212654, 0.09774206687802872, 0.0, -0.1712106846556775, 0.03792948550645252, 0.6420088643323169, 0.06320926425829188, 0.8753432718073637, -1.0000005011046043, -1.0000000000002376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4051653302413882, 0.15291008256651703, 0.21669824147290176, -0.7450899099572149, -0.5954900693621484, -0.24215779481458866, 0.7793140350823167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13399473932305103, -0.03380424653335981, -0.014883545257008256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20576022076715375, 0.2043888656870428, 0.8105783890627817, 0.0, -0.2337123229928388, -0.3464879381815168, -2.4940922874295155, -1.1337999009427524, -1.0890259719424475, -0.650509352884751, -2.362240832902516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510514236160238, 0.6564071831994994, 1.403620965527082, -1.0890059379932011, -2.214526068245795, -0.5667107378922177, 1.2507736607049844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2576710963515167, -0.4353477493425074, 0.029610162330812134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012629424432424752, 0.10316413089752449, 0.09609295189704037, 0.0, -0.11067497557922014, 0.07476460389864714, 0.5059836835746102, 0.19081389466684653, 0.9402746174436897, -1.0000005011045867, -1.0000000000002702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33021759156983965, 0.133646492371311, 0.16880134528450907, -0.5944091638223233, -0.43427910896580035, -0.20565229021526063, 0.5995546586338187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11541871964724648, -0.027902768859541856, -0.013100693596106397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064101730111816, 0.20918969614030278, 0.8151985088088208, 0.0, -0.23619468757488218, -0.34091006903492105, -2.475337384198103, -1.1177464421455081, -1.0394149872447274, -0.7005093779400104, -2.412240832902519, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.523403301297924, 0.6622822239167705, 1.4098182069669167, -1.1113813433797564, -2.2283755764191837, -0.5748417513451253, 1.2719013258029221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2624608795377155, -0.43646862893810046, 0.029057378771169932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880557524, 0.09601660906519982, 0.09240239492078313, 0.0, -0.04964729164086727, 0.11155738293191456, 0.375098064628254, 0.3210691759448877, 0.9922196939544017, -1.0000005011051882, -1.0000000000000613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2577813027537198, 0.11750081434542253, 0.1239448287966965, -0.44750810773110444, -0.27699016346777455, -0.16262026905815133, 0.42255330195875485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.095795663723975, -0.022417591911861316, -0.011055671192844046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2070601252552261, 0.2135221305357053, 0.8195134890305069, 0.0, -0.23592775110245523, -0.33388518964591246, -2.462551220837017, -1.0959194558390715, -0.9894149872447394, -0.7505094029952885, -2.4622408329025243, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5333287265246551, 0.667481948193073, 1.4142498397471182, -1.1277963513126714, -2.2360476984196853, -0.5810006042943882, 1.2859313215966783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.266386030912219, -0.4373574993376022, 0.028596672850609083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880889928, 0.08664868790805016, 0.08629960443372142, 0.0, 0.005338729448539366, 0.1404975877801714, 0.25572326722171174, 0.4365397261287322, 0.9999999999997586, -1.0000005011055593, -1.0000000000001035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19850850453462252, 0.10399448552605098, 0.08863265560402797, -0.32830015865830164, -0.1534424400100285, -0.12317705898525709, 0.2805999158751256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07850302749007283, -0.017777407990034997, -0.009214118411216964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20771007749924222, 0.2173234455155467, 0.823412480102414, 0.0, -0.2331721748620815, -0.3259143561449327, -2.4553099141551606, -1.0691483838741687, -0.9394149872447404, -0.8005094280505596, -2.512240832902523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5410462930877361, 0.6720870992422457, 1.4174490504828554, -1.1398783046788483, -2.23955831534367, -0.5855875325806078, 1.2949642850495815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2696122536938677, -0.43805918705077557, 0.028207867985896987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880322287, 0.07602629959682783, 0.0779798214381413, 0.0, 0.05511152480747473, 0.1594166700195956, 0.14482613363713087, 0.5354214392980579, 0.9999999999999802, -1.0000005011054218, -0.9999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15435133126162043, 0.09210302098345298, 0.0639842147147435, -0.2416390673235393, -0.07021233847969158, -0.09173856572439221, 0.18065926905806198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0645244556329731, -0.014033754263467138, -0.007776097294241945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20836002974325324, 0.220580738424814, 0.8268497555052778, 0.0, -0.22776557192265945, -0.3174532650407923, -2.453736299899618, -1.0373651970028064, -0.8894149872447474, -0.8505094531076175, -2.562240832903147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5471275253317054, 0.6760967766719892, 1.419812030834297, -1.1488903227386842, -2.2406049125982195, -0.5889740129652162, 1.3007316657284402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2722569064454363, -0.43861191622931434, 0.02786773997931919]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880220122, 0.06514585818534588, 0.06874550805727751, 0.0, 0.10813205878844129, 0.1692218220828084, 0.03147228511085087, 0.6356637374272478, 0.9999999999998577, -1.0000005011411581, -1.0000000000124751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12162464487938615, 0.08019354859486817, 0.04725960702883106, -0.18024036119671732, -0.020931945090991222, -0.067729607692168, 0.1153476135771768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0528930550313747, -0.011054583570775578, -0.006802560131555889]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20890236731276418, 0.22331947192858484, 0.8299126941352141, 0.0, -0.21963384384261464, -0.3087547466632327, -2.457943386608462, -1.0008838400568223, -0.8394149872448201, -0.9005094781628663, -2.6122408329031273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519614181536695, 0.6795011419163419, 1.4215954927811791, -1.1557017087656305, -2.2403813722918278, -0.5914575442271724, 1.3044574108583427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2744018531044412, -0.43904510173632294, 0.027557092385001702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010846751390218888, 0.05477467007541689, 0.06125877259872422, 0.0, 0.16263456160089598, 0.17397036755119216, -0.08414173417687226, 0.7296271389196829, 0.9999999999985463, -1.0000005011049757, -0.9999999999996081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0966778564392827, 0.06808730488705383, 0.035669238937643385, -0.13622772053892793, 0.004470806127835566, -0.04967062523912445, 0.07451490259804805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04289893318009702, -0.008663710140172066, -0.006212951886349732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924014300176616, 0.22558907526272806, 0.832516028451838, 0.0, -0.2088784119570595, -0.29988190631457157, -2.4679101480898793, -0.9600673236121545, -0.7894149872448852, -0.9505095032181211, -2.6622408329031124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558093246584372, 0.6822883123648255, 1.4229550903934498, -1.1609092407972317, -2.239690744526241, -0.5932717611957165, 1.3069797006688277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2761077168336417, -0.4393805271434575, 0.027263123491609406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006755513780039767, 0.04539206668286434, 0.0520666863324798, 0.0, 0.2151086377111026, 0.17745680697322283, -0.19933522962834466, 0.8163303288933546, 0.9999999999986986, -1.0000005011050965, -0.9999999999997062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07695813009535564, 0.05574340896967034, 0.027191952245415554, -0.10415064063202173, 0.01381255531173049, -0.03628433937087952, 0.050445796209702576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03411727458400836, -0.006708508142691235, -0.00587937786784593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932616161286308, 0.22744569050308344, 0.834826254295132, 0.0, -0.19579154426530776, -0.2908321419076912, -2.483469466430795, -0.9154141104565975, -0.739414987245167, -1.000509528273315, -2.712240832902818, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5588604330257323, 0.6844420565639199, 1.4239877225131137, -1.164969402369256, -2.239103536428652, -0.5946108692553929, 1.3089117387084355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2774277204317501, -0.4396341865431943, 0.02698265280572664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017203722219384116, 0.037132304807107774, 0.04620451686587979, 0.0, 0.2617373538350347, 0.18099528813760773, -0.3111863668183114, 0.8930642631111416, 0.9999999999943651, -1.0000005011038793, -0.9999999999941117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06102216734590005, 0.04307488398188946, 0.020652642393276476, -0.08120323144048687, 0.011744161951782052, -0.0267821611935287, 0.03864076079215309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026400071962168384, -0.005073187994736585, -0.005609413717655272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20933056938417735, 0.228938372466004, 0.8366688095526873, 0.0, -0.18217453223378702, -0.2814297402669101, -2.500887728282853, -0.870306111972243, -0.6931649872445551, -1.0491367343047637, -2.7584908329056668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5612536679267874, 0.6860483734709207, 1.4247430436927009, -1.168155308410831, -2.2387880875171633, -0.595590809248792, 1.3105357742296277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.278425135211993, -0.4398232632180623, 0.02672449963672147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.815542628558227e-05, 0.029853639258411103, 0.03685110515110657, 0.0, 0.2723402406304148, 0.18804803281562182, -0.3483652370411696, 0.9021599696870902, 0.9250000000122373, -0.9725441206289748, -0.9250000000569817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.047864698021103345, 0.032126338140017016, 0.01510642359174525, -0.06371812083149866, 0.006308978229771619, -0.0195987998679837, 0.032480710423844435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01994829560486069, -0.003781533497360421, -0.005163063380103397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932884115003778, 0.23011316550761649, 0.8381225057841533, 0.0, -0.1693528861440909, -0.27255979656795276, -2.518771328661458, -0.8284933281084138, -0.654414987213272, -1.0926411213852207, -2.7972408329494938, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631048045192583, 0.687252723211333, 1.4252317019514358, -1.1706501793212163, -2.2387012797308765, -0.5962762215751217, 1.3119750197448723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2791678862882272, -0.4399629161625189, 0.02649902814853944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.456468279174673e-05, 0.023495860832250186, 0.029073924629319937, 0.0, 0.2564329217939224, 0.17739887397914625, -0.35767200757209533, 0.836255677276582, 0.7750000006256631, -0.8700877416091413, -0.7750000008765425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0370227318494159, 0.024086994808245304, 0.009773165174699198, -0.04989741820770852, 0.001736155725733773, -0.013708246526593065, 0.0287849103048912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014855021524681263, -0.002793058889132289, -0.004509429763640606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932788289126003, 0.23101798821627914, 0.8391026888525631, 0.0, -0.15818501666305668, -0.26483319096932273, -2.5359587088692606, -0.7937257558710759, -0.6250680896836437, -1.1277424437604398, -2.8260974817958933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564512246192544, 0.6882110000970189, 1.4254194277410992, -1.172594032649529, -2.2387410078804804, -0.5966909778580843, 1.3133183993931452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2797159619590375, -0.4400654543891233, 0.026310697312253172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9165175554961214e-05, 0.018096454173253205, 0.0196036613681976, 0.0, 0.22335738962068408, 0.15453211197260083, -0.34374760415605077, 0.6953514447467598, 0.5869379505925651, -0.7020264475043795, -0.5771329769279895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02814883346571545, 0.01916553771371786, 0.0037545157932705603, -0.0388770665662527, -0.0007945629920774432, -0.008295125659251692, 0.02686759296545663, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010961513416206263, -0.002050764532088299, -0.003766616725725312]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209326967977962, 0.23170153162576393, 0.8397180196333647, 0.0, -0.14905358832275853, -0.25852071302748747, -2.5515493738647765, -0.7668782370757354, -0.6040801048930344, -1.1540211237438165, -2.8459557199745085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5655600193084604, 0.6890612677378614, 1.4252544891234067, -1.1741005473302502, -2.2388086006669075, -0.5968383061702716, 1.3146469020890874, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2801180324457406, -0.44014044847222306, 0.0261579683581745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.829826596068004e-05, 0.013670868189695779, 0.01230661561603071, 0.0, 0.1826285668059628, 0.12624955883670494, -0.31181329991032136, 0.5369503759068073, 0.4197596958121855, -0.5255735996675329, -0.397164763572303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02095546231832748, 0.01700535281684921, -0.003298772353851691, -0.030130293614425267, -0.001351855728544265, -0.002946566243744073, 0.02657005391884625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008041409734061587, -0.001499881661994671, -0.003054579081573399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093259380204269, 0.23220977394247713, 0.8400854275917896, 0.0, -0.14197612515217423, -0.2536482214865198, -2.564986775067951, -0.7473180611300209, -0.5895743811466219, -1.1724845390217244, -2.858801959448876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663198497966578, 0.6899025586887599, 1.424707731640309, -1.1752628476276366, -2.2388339068055143, -0.5967248652769541, 1.3160195454508985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2804118817113503, -0.440195155718598, 0.02603609857431136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0599150701613132e-05, 0.010164846334263896, 0.007348159168498353, 0.0, 0.14154926341168605, 0.09744983081935366, -0.2687480240634872, 0.39120351891429056, 0.29011447492825215, -0.36926830555815804, -0.2569247894873526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015196609763948796, 0.016825819017970946, -0.010935149661955473, -0.023246005947725922, -0.0005061227721400406, 0.0022688178663480153, 0.027452867236222957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005876985312195564, -0.0010941449274996567, -0.002437395677262807]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932478082939882, 0.23258303632233118, 0.8403182736213654, 0.0, -0.13673976621698192, -0.25009048605629397, -2.5760634691920976, -0.7338035035911181, -0.5797348308047431, -1.1846861181123198, -2.8666674562661716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5668496073376568, 0.690808718640863, 1.423754695329556, -1.176157114405769, -2.2387707525162717, -0.5963535131611295, 1.3174903452101003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2806261112024597, -0.4402349952513054, 0.02593967049718884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.314382056186457e-05, 0.007465247597081032, 0.004656920591515499, 0.0, 0.10472717870384635, 0.07115470860451609, -0.22153388248293018, 0.2702911507780543, 0.19679100683757533, -0.24403158181190557, -0.1573099363459114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010595150819977833, 0.018123199042062353, -0.019060726215059675, -0.017885335562650054, 0.001263085784849995, 0.007427042316493482, 0.02941599518403489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004284589822188753, -0.0007967906541475968, -0.00192856154245041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932339724114024, 0.2328547249447787, 0.8404844977878413, 0.0, -0.13302175330080057, -0.2476419798401231, -2.5848497946527678, -0.7249578381638652, -0.5731054595349542, -1.1922294288601571, -2.8712263686173403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5671915980120815, 0.6918542953571599, 1.4223367074189475, -1.1768459124727995, -2.2385826009709686, -0.5957045777303653, 1.3191371386595554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2807820429389665, -0.440263974177527, 0.025863793622816735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.76717651716686e-05, 0.0054337724489508295, 0.003324483329518648, 0.0, 0.0743602583236267, 0.048970124323417547, -0.17572650921339994, 0.17691330854505882, 0.13258742539577828, -0.1508662149567478, -0.09117824702337414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006839813488494819, 0.020911534325937276, -0.028359758212169114, -0.013775961340610206, 0.0037630309060581193, 0.012978708615283687, 0.03293586898910326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003118634730133735, -0.000579578524432414, -0.001517537487442093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932160909258068, 0.2330513790842077, 0.840695975766972, 0.0, -0.1304781107382692, -0.24608019902554626, -2.5915906810501066, -0.7195101586413297, -0.5686273915797048, -1.1965227031409893, -2.873712065986655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5673716881041702, 0.6931383151733975, 1.420324885976035, -1.1773812592468422, -2.2382285951112917, -0.5947182660780783, 1.321087474954143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2808954222641762, -0.44028503700835714, 0.025804395699238862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.576297119099514e-05, 0.003933082788579588, 0.004229559582612759, 0.0, 0.05087285125062718, 0.031235616291536917, -0.1348177279467748, 0.1089535904507085, 0.08956135910498746, -0.08586548561664105, -0.04971394738629807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003601801841772482, 0.02568039632475126, -0.0402364288582501, -0.01070693548085521, 0.007080117193534543, 0.019726233045739956, 0.03900672589175434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022675865041934746, -0.000421256616602761, -0.0011879584715574895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931920301568352, 0.2331934293386948, 0.8408585872212334, 0.0, -0.12879737342821995, -0.245203650165338, -2.5966091754426435, -0.7164018528654865, -0.5655782245461377, -1.198687194199383, -2.8749662449540203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56739952898861, 0.6947976467255678, 1.417501623225868, -1.1778071478137369, -2.2376551247952263, -0.5932859412217962, 1.3235316849239758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.280977805635369, -0.4403003384623748, 0.025758135598587646]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.812153794340694e-05, 0.0028410050897417867, 0.0032522290852278627, 0.0, 0.03361474620098516, 0.017530977204165292, -0.10036988785073828, 0.0621661155168642, 0.06098334067134223, -0.04328982116787521, -0.02508357934730481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005568176887978771, 0.033186631043404066, -0.056465255003339654, -0.008517771337891071, 0.011469406321307846, 0.02864649712564206, 0.04888419939665492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016476674238530644, -0.0003060290803538771, -0.0009252020130243051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931618104453162, 0.23329626311703922, 0.8409724071782145, 0.0, -0.12772312341066705, -0.24481395712687198, -2.6002446659971485, -0.7148146095129365, -0.5634795661829842, -1.199550618643628, -2.875531087473784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5672778537988058, 0.6969542188524047, 1.4136642286778873, -1.1781593437099984, -2.2368185258139257, -0.5913055409781842, 1.3266454613493943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810376429208725, -0.44031145120516274, 0.02572219668437234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0439423038208124e-05, 0.002056675566888427, 0.002276399139622121, 0.0, 0.021485000351057923, 0.007793860769319941, -0.07270981109009911, 0.03174486705099942, 0.041973167263069225, -0.01726848888489693, -0.011296850395268064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024335037960834314, 0.04313144253673796, -0.07674789095961343, -0.007043917925231801, 0.016731979626013978, 0.03960800487223917, 0.06227552850837193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011967457100707489, -0.00022225485575790908, -0.0007187782843061262]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093132596300379, 0.2333713576137685, 0.8411024824889938, 0.0, -0.12705684411839407, -0.2447149090405895, -2.602818979415272, -0.7141544056546724, -0.5620128669998177, -1.199683608494942, -2.8757399307150244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5670300950976542, 0.6995436439667067, 1.4089507589655348, -1.1784599753817526, -2.2357609555553686, -0.5888537791612296, 1.3303470237452841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810810937432404, -0.4403195204187482, 0.0256940742681744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.842828987430867e-05, 0.0015018899345859969, 0.0026015062155844244, 0.0, 0.013325585845459686, 0.00198096172564936, -0.0514862683624715, 0.013204077165283132, 0.029333983663330492, -0.002659797026282086, -0.004176864824815902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004955174023030489, 0.05178850228603931, -0.09426939424704964, -0.0060126334350839375, 0.021151405171141162, 0.04903523633909185, 0.07403124791779794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008690164473574144, -0.00016138427170990318, -0.0005624483239587907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931107145574457, 0.23342725960843494, 0.8412299048084414, 0.0, -0.1266536488275151, -0.24475560750623362, -2.6046089182401073, -0.71401434648281, -0.56096890190329, -1.1994554876513186, -2.875785908046203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5667027024736216, 0.7023252529122656, 1.4038254173463194, -1.1787187226710483, -2.234602608355407, -0.5861785294179096, 1.334307758548752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811126383451363, -0.44032537855362475, 0.02567146062408601]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3763485867001316e-05, 0.001118039893328548, 0.002548446388953234, 0.0, 0.008063905817579597, -0.0008139693128823918, -0.035798776496701455, 0.002801183437245544, 0.020879301930553273, 0.004562416872467299, -0.0009195466235717882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006547852480650781, 0.05563217891117837, -0.10250683238430679, -0.005174945785914244, 0.023166943999231908, 0.053504994866400785, 0.07921469606935587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006308920379176483, -0.00011716269753029164, -0.0004522728817677998]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093095357777038, 0.23347030733254687, 0.8413333933949931, 0.0, -0.12641317592168402, -0.2448425633689893, -2.6058359713905936, -0.7141318406218842, -0.5602121250904676, -1.1990895838369133, -2.8757726831399966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663405076834858, 0.7050641520890193, 1.398739313522182, -1.1789408532348258, -2.23345759570976, -0.5835200154982266, 1.3382051322199189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281135535361113, -0.44032963089928073, 0.02565226245036766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0713560815450024e-05, 0.0008609544822384934, 0.002069771731034684, 0.0, 0.00480945811662164, -0.001739117255113497, -0.024541063009727, -0.0023498827814825117, 0.015135536256447077, 0.007318076288105374, 0.0002644981241333316, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007243895802718277, 0.0547779835350745, -0.10172207648274745, -0.004442611275548488, 0.022900252912939713, 0.05317027839365999, 0.07794747342334042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00045794031953013753, -8.504691312025128e-05, -0.0003839634743670364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093083863401872, 0.23350509051701604, 0.8413646252815028, 0.0, -0.12626914210007656, -0.2449286003817336, -2.606668321483937, -0.7143485456589677, -0.5596551025701284, -1.1987097357395833, -2.875750105900365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.565974677304888, 0.7076153731996925, 1.393973547800686, -1.1791313171364814, -2.2323958449919328, -0.5810281181019368, 1.3418399661678189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811521534988537, -0.4403327173759992, 0.025634732928234014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2988750332211854e-05, 0.0006956636893833827, 0.0006246377301939144, 0.0, 0.0028806764321491277, -0.001720740254886341, -0.016647001866865102, -0.004334100741669422, 0.011140450406784304, 0.007596961946602426, 0.0004515447926331461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007316607571954944, 0.051024422213464565, -0.09531531442991814, -0.0038092780331124413, 0.021235014356552527, 0.049837947925796156, 0.07269667895799907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000332362754814236, -6.172953436950594e-05, -0.0003505904426728646]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093074345213319, 0.23353476076684745, 0.8413867836530399, 0.0, -0.12617978319897336, -0.2449968772106131, -2.6072287718098015, -0.714577054554873, -0.559240923775451, -1.1983759739779265, -2.8757378530791198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5656226078371608, 0.7099212289243557, 1.3896443520739996, -1.1792953816447265, -2.2314451351174696, -0.5787651709376522, 1.345133091682759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811642136478232, -0.4403349575490008, 0.02561761009628726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9036377105635495e-05, 0.0005934049966281783, 0.000443167430740441, 0.0, 0.0017871780220643492, -0.0013655365775899187, -0.011209006517291896, -0.0045701779181072716, 0.008283575893547793, 0.006675235233133516, 0.00024505642489917266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007041389354544094, 0.0461171144932648, -0.08658391453372918, -0.003281290164901044, 0.01901419748926482, 0.045258943285691154, 0.06586251029880365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002412029793911311, -4.480346003190916e-05, -0.0003424566389351333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930656804015205, 0.23356129882315158, 0.8413701620718517, 0.0, -0.12612001251429453, -0.24504422559840863, -2.607604653229138, -0.7147753717799153, -0.5589313399745239, -1.1981100556589004, -2.8757403173484275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5652913274534491, 0.7119836069201142, 1.385754835100013, -1.1794382729338133, -2.2306047665306026, -0.5767333927952603, 1.3480873651022844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281172965508997, -0.440336583464336, 0.025600174956988263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7329623597052658e-05, 0.0005307611260826335, -0.00033243162376509416, 0.0, 0.0011954136935767837, -0.0009469677559102456, -0.007517628386735238, -0.003966344500848236, 0.006191676018541968, 0.005318366380524382, -4.928538615713067e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006625607674232605, 0.04124755991517044, -0.077790339479733, -0.0028578257817353727, 0.01680737173734279, 0.040635562847839264, 0.059085468390505325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017503722347327722, -3.2518306703991607e-05, -0.00034870278597991196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930571697289413, 0.23358578927657528, 0.8413301762265463, 0.0, -0.1260756570374459, -0.24507464315984007, -2.6078564227091303, -0.7149285725174833, -0.5586999459037346, -1.1979128602868756, -2.8757551078398103, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5649807970422012, 0.7138384212270887, 1.3822426312907556, -1.1795648525660125, -2.229858153091005, -0.5749001873910619, 1.3507527457911412, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811793163762348, -0.4403377635721811, 0.02558220222703967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.702134515844646e-05, 0.0004898090684743421, -0.000799716906108358, 0.0, 0.0008871095369727812, -0.0006083512286286783, -0.0050353895998431234, -0.0030640147513591332, 0.004627881415787143, 0.003943907440495759, -0.0002958098276514625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006210608224958936, 0.03709628613948982, -0.07024407618514973, -0.0025315926439827795, 0.014932268791951654, 0.036664108083967424, 0.05330761377713449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001270173447574517, -2.360215690101155e-05, -0.00035945459897185014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093048289687132, 0.23360869936906162, 0.8412687929570802, 0.0, -0.12603921694238535, -0.24509250940629626, -2.6080254533918, -0.7150364279503766, -0.5585275030750284, -1.197775332567186, -2.8757778356522703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5646863279103231, 0.7155384116720686, 1.3790120388227531, -1.1796795240936315, -2.229181352658341, -0.5732152525497688, 1.3532028827256402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811839248259298, -0.44033862013547376, 0.02556383189244487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7760083618687023e-05, 0.0004582018497266741, -0.0012276653893209275, 0.0, 0.0007288019012108107, -0.00035732492912375895, -0.0033806136533930773, -0.0021571086578656457, 0.00344885657412393, 0.002750554393789047, -0.00045455624919883757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005889382637561511, 0.03399980889959524, -0.06461184936005213, -0.002293430552380959, 0.013536008653279674, 0.033698696825861935, 0.04900273868997617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.216899389749787e-05, -1.713126585362548e-05, -0.0003674066918959724]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093038618960449, 0.23363013314251516, 0.8412021612596656, 0.0, -0.12600711441060672, -0.24510213748602921, -2.6081395104400515, -0.7151055316030717, -0.5583997009662818, -1.1976850765639133, -2.8758042432433197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5644002197876236, 0.7171431776920782, 1.3759527757440497, -1.1797862949051272, -2.228548011012204, -0.571620595983273, 1.3555215766006095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811872688471595, -0.44033924188535506, 0.02554541065054421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9341453365596536e-05, 0.00042867546907065216, -0.0013326339482925987, 0.0, 0.0006420506355724892, -0.00019256159465898116, -0.0022811409650317937, -0.00138207305390175, 0.0025560421749317797, 0.0018051200654563017, -0.0005281518209890811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005722162453991348, 0.03209532040019296, -0.06118526157406873, -0.002135416229915026, 0.01266683292273626, 0.03189313132991613, 0.04637387749938665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.688042459223199e-05, -1.243499762654782e-05, -0.0003684248380132118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930277955712914, 0.23365003479002197, 0.841142355991144, 0.0, -0.12597786919762735, -0.2451067040304369, -2.608217050437533, -0.7151446630045013, -0.5583056253473476, -1.1976298647099906, -2.875831082964572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564112916098539, 0.718713631945134, 1.3729505868607748, -1.1798888818872901, -2.227932048589906, -0.5700562098209019, 1.3577952065121577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811896953317157, -0.44033969321508903, 0.025527345973332755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1646778315541915e-05, 0.0003980329501363525, -0.0011961053704323751, 0.0, 0.0005849042595874469, -9.133088815418519e-05, -0.0015507999496303946, -0.0007826280285938342, 0.001881512378682125, 0.0011042370784556759, -0.0005367944250410268, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005746073781690693, 0.03140908506111582, -0.06004377766550069, -0.002051739643259896, 0.012319248445959628, 0.03128772324742158, 0.04547259823096527, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.852969112507101e-05, -9.026594679226684e-06, -0.0003612935442291047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930155521577734, 0.23366833009605906, 0.841094961488964, 0.0, -0.12595099681958702, -0.24510830575426978, -2.608270244854492, -0.7151623127094201, -0.5582368711318413, -1.1975992576938694, -2.8758562656040474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5638140257817605, 0.7203079847006745, 1.369895085563649, -1.1799907533268417, -2.227309439495549, -0.5684642412888999, 1.360107104727664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281191456016363, -0.440340020855898, 0.02550999675993775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4486827036107972e-05, 0.0003659061207415492, -0.0009478900435981089, 0.0, 0.0005374475608064811, -3.203447665762285e-05, -0.0010638883391749958, -0.0003529940983749414, 0.0013750843101261174, 0.0006121403224216934, -0.0005036527895113157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0059778063355689585, 0.03188705511080903, -0.061110025942516716, -0.0020374287910290695, 0.012452181887139795, 0.03183937064003895, 0.046237964310127326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.521369294633575e-05, -6.552816180006944e-06, -0.0003469842679000255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930018081720683, 0.23368500968621683, 0.8410609628302775, 0.0, -0.125926388040214, -0.24510836130916702, -2.6083070567133824, -0.7151655660674753, -0.5581869933210988, -1.1975851125906631, -2.875878686583119, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.563493591706401, 0.7219767244682881, 1.3666896025534783, -1.18009501357608, -2.226660223367573, -0.5667941725697253, 1.3625303249008929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811927335841258, -0.44034025872312105, 0.025493606580810426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7487971409974618e-05, 0.00033359180315545664, -0.0006799731737292077, 0.0, 0.0004921755874602552, -1.1110979447739581e-06, -0.0007362371778133676, -6.506716110269497e-05, 0.0009975562148499739, 0.0002829020641273661, -0.0004484195814282261, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006408681507189875, 0.033374795352271634, -0.06410966020341216, -0.002085204984763627, 0.012984322559509329, 0.033401374383493235, 0.04846440346457676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5551355253924737e-05, -4.757344460149128e-06, -0.00032780358254653704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929867884331144, 0.2337001652461733, 0.8410398000736337, 0.0, -0.1259039816055719, -0.24510771241587442, -2.608332691702937, -0.7151597804444204, -0.5581510785125475, -1.1975814871566215, -2.875897971265622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631438560880656, 0.7237552448328658, 1.3632656213457324, -1.180204082582403, -2.225971326545408, -0.5650103653121799, 1.365116883684307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281193660600752, -0.4403404314317798, 0.025478275340491713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0039477908181726e-05, 0.00030311119912921383, -0.00042325513287815654, 0.0, 0.0004481286928418511, 1.2977865851722881e-05, -0.0005126997910942445, 0.00011571246109806768, 0.0007182961710260918, 7.250868083288599e-05, -0.0003856936500588376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006994712366707671, 0.03557040729155468, -0.0684796241549184, -0.002181380126459792, 0.013777936443305007, 0.03567614515090822, 0.051731175668285306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8540332523773255e-05, -3.4541731755088937e-06, -0.00030662480637424854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092971066962968, 0.23371399345663038, 0.8410315183894932, 0.0, -0.12588360240755486, -0.24510639356105499, -2.6083506489147124, -0.7151486795474746, -0.5581253344249605, -1.1975842653907938, -2.875914255468676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5627612462555937, 0.7256557504430601, 1.3595986979929144, -1.180319265356326, -2.225239514424052, -0.5631003451914094, 1.3678858125913502, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811943332514166, -0.44034055684806567, 0.025463959270514265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.144294029240099e-05, 0.000276564209141811, -0.0001656336828101733, 0.0, 0.00040758396034068956, 2.6377096388984554e-05, -0.00035914423550959505, 0.00022201793891585123, 0.0005148817517415824, -5.55646834436625e-05, -0.0003256840610755665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007652196649439385, 0.03801011220388612, -0.07333846705635926, -0.0023036554784603078, 0.014636242427122956, 0.03820040241540994, 0.055378578140861626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3453013296197203e-05, -2.508325717375635e-06, -0.000286321399548956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929554240381656, 0.23372677844954556, 0.8410309175430131, 0.0, -0.12586495439624742, -0.24510451324511714, -2.608363229770946, -0.715134626654381, -0.5581069586289285, -1.1975907620666153, -2.875927934791054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5623475532949853, 0.7276636348005215, 1.355715874881219, -1.1804404942998248, -2.2244724050053057, -0.5610786053208363, 1.3708175312484436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811948213291113, -0.4403406479415184, 0.025450491256586823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.128584960460454e-05, 0.0002556998583034697, -1.2016929603494417e-05, 0.0, 0.00037296022614867746, 3.7606318756892435e-05, -0.0002516171246731703, 0.00028105786187182383, 0.00036751592064140806, -0.00012993351642981148, -0.00027358644755902454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008273859212166279, 0.040157687149229564, -0.07765646223390661, -0.002424578869977944, 0.015342188374920577, 0.040434797411462116, 0.05863437314186746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.7615538926286e-06, -1.8218690544552197e-06, -0.00026936027854881727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209294053398125, 0.23373885868698788, 0.8410335748135789, 0.0, -0.12584763873052435, -0.24510210272088584, -2.6083719747967073, -0.7151189612611795, -0.558093895091273, -1.197599327374643, -2.8759395243000445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.561909294418856, 0.7297428023174414, 1.3516858663276905, -1.1805665121830295, -2.2236858833252864, -0.5589813906049087, 1.3738611251068245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195175474863, -0.4403407141278588, 0.025437617055845567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9780113831033408e-05, 0.00024160474884648138, 5.314541131553214e-05, 0.0, 0.00034631331446133593, 4.821048462616556e-05, -0.00017490051522889565, 0.00031330786403151347, 0.0002612707531080156, -0.00017130616055594606, -0.00023179017981265172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008765177522586246, 0.041583350338396, -0.080600171070569, -0.0025203576640966487, 0.01573043360038643, 0.04194429431855181, 0.060871877167615614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.082915030469657e-06, -1.3237268083657956e-06, -0.0002574840148251435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929267402278356, 0.23375058401338336, 0.8410368464974026, 0.0, -0.1258312071972287, -0.24509912738008263, -2.608377934289759, -0.7151023257509268, -0.5580846474444042, -1.1976090235471704, -2.8759495580003933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5614554637779701, 0.7318480731070073, 1.3475954379145076, -1.180695442257408, -2.222898841005886, -0.5568542851154894, 1.3769520004783893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195432432936, -0.4403407622430411, 0.0254250422090177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7587506829197594e-05, 0.00023450652790980332, 6.543367647447401e-05, 0.0, 0.0003286306659130794, 5.9506816063916064e-05, -0.00011918986102826232, 0.0003327102050529317, 0.00018495293737567448, -0.00019392345054728718, -0.00020067400697726577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009076612817717112, 0.04210541579131824, -0.08180856826365653, -0.0025786014875700805, 0.015740846388008323, 0.04254210978838492, 0.06181750743129771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.139161459139613e-06, -9.623036454801814e-07, -0.0002514969365572958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929140492578405, 0.23376226979364867, 0.8410366838434314, 0.0, -0.1258152304891205, -0.24509561131307556, -2.6083818247290775, -0.7150849474311873, -0.5580781479145169, -1.1976193739597198, -2.875958516984219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5609949280913906, 0.7339380409830827, 1.3435246690204103, -1.180825424830752, -2.22212797938815, -0.5547392558008276, 1.380030415191857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811956188667661, -0.44034079724974484, 0.025412482780436875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.538193999048871e-05, 0.00023371560530605358, -3.2530794247178512e-06, 0.0, 0.0003195341621644069, 7.032134014142217e-05, -7.78087863706458e-05, 0.0003475663947893592, 0.00012999059774529547, -0.00020700825098755003, -0.0001791796765088974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009210713731589496, 0.04179935752150859, -0.08141537788194497, -0.002599651466876533, 0.015417232354719007, 0.042300586293236575, 0.06156829426935478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7286766039075745e-06, -7.001340752734186e-07, -0.0002511885716165004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929022605121414, 0.23377415724123438, 0.8410354043712006, 0.0, -0.12579936807991787, -0.245091880159618, -2.6083840897483874, -0.7150668577609607, -0.55807369540577, -1.197630180755887, -2.8759667720472466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5605345511860355, 0.7359832897091294, 1.3395309574510912, -1.1809550542929945, -2.2213846728043958, -0.552666304106167, 1.3830534858866987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811957541294259, -0.44034082274968717, 0.025399710587983983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3577491398254557e-05, 0.000237748951714319, -2.5589444615739494e-05, 0.0, 0.0003172481840523629, 7.462306915097544e-05, -4.5300386200787526e-05, 0.00036179340453244813, 8.905017493845235e-05, -0.00021613592333979306, -0.0001651012605533446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009207538107104077, 0.040904974520935396, -0.07987423138638482, -0.002592589244853728, 0.01486613167508669, 0.04145903389321194, 0.06046141389683468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7052531964609267e-06, -5.099988465446153e-07, -0.00025544384905784367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092891087142332, 0.2337863889700238, 0.8410360082603573, 0.0, -0.12578335826999573, -0.24508741702397602, -2.6083851827022246, -0.715048050955997, -0.5580706532528865, -1.1976413418152407, -2.8759746453116835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5600783519138955, 0.7379690563802977, 1.3356436247608887, -1.1810835571516842, -2.2206741594981336, -0.5506506833394155, 1.3859992698826669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811958522663727, -0.4403408413557531, 0.025386583483815072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2346739618580776e-05, 0.0002446345757885683, 1.207778313352136e-05, 0.0, 0.0003201961984425355, 8.926271283950733e-05, -2.18590767437206e-05, 0.0003761360992743255, 6.084305766997865e-05, -0.00022322118707697718, -0.00015746528873960834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009123985442799153, 0.03971533342336723, -0.07774665380405146, -0.002570057173793344, 0.014210266125241882, 0.04031241533503041, 0.058915679919361294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9627389349568807e-06, -3.721213176678822e-07, -0.0002625420833782228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928802517115022, 0.23379900514934923, 0.8410349328638245, 0.0, -0.125767081482586, -0.24508231676848866, -2.6083853909718746, -0.7150285610661412, -0.5580686155401812, -1.1976528125791381, -2.8759823294466824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5596274722157201, 0.7398939844199924, 1.3318660572606382, -1.1812107802490412, -2.219996308616668, -0.5486940638167193, 1.3888652079976598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959234561143, -0.4403408549627982, 0.025373054806792944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1670861659835338e-05, 0.00025232358650895104, -2.1507930657501184e-05, 0.0, 0.00032553574819482414, 0.00010200510974724494, -4.1653930017752455e-06, 0.0003897977971152688, 4.075425410771976e-05, -0.0002294152779486388, -0.0001536826999770408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00901759396351018, 0.038498560793894, -0.07555135000501167, -0.002544461947141193, 0.013557017629314352, 0.03913239045392443, 0.05731876229985881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4237948324154929e-06, -2.721409020453415e-07, -0.00027057354044257597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928695084797927, 0.2338119584573455, 0.8410321159752371, 0.0, -0.12575052771739645, -0.2450766126830368, -2.6083849522399776, -0.7150084945107471, -0.558067272264523, -1.1976645422434569, -2.875989934475641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5591806119876536, 0.7417669828489495, 1.3281815578917626, -1.181337083108363, -2.219347098584525, -0.5467876350123405, 1.3916637907816496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959750864783, -0.4403408649438677, 0.025359163293032172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.148646341928201e-05, 0.00025906615992544573, -5.6337771747108655e-05, 0.0, 0.00033107530379099525, 0.00011408170903712871, 8.774637939968811e-06, 0.0004013311078828809, 2.6865513162621074e-05, -0.00023459328637668916, -0.0001521005791680687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00893720456133019, 0.03745996857914207, -0.07368998737751273, -0.002526057186434127, 0.012984200642861312, 0.038128576087575396, 0.05597165567979601, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.032607281879432e-06, -1.9962139030758776e-07, -0.000277830275215461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928586632714155, 0.23382514213019298, 0.8410281279171928, 0.0, -0.1257337701212526, -0.245070380155813, -2.608384056205543, -0.7149880199197897, -0.5580663940860073, -1.1976764629807153, -2.875997503976249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5587346767482065, 0.7436035660074914, 1.3245602911608023, -1.1814631941859728, -2.218720221675862, -0.5449157679568635, 1.3944173987513842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196012518856, -0.4403408722934107, 0.02534500869895688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.169041675451192e-05, 0.0002636734569495852, -7.976116088462764e-05, 0.0, 0.000335151922876737, 0.00012465054447576959, 1.7920688690471714e-05, 0.0004094918191487047, 1.756357031465416e-05, -0.000238414745170206, -0.0001513900121642371, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008918704788940066, 0.036731663170838695, -0.07242533461920501, -0.0025222215521966854, 0.012537538173262038, 0.03743734110954007, 0.05507215939469092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.486475535157642e-07, -1.4699085936223667e-07, -0.0002830918815058249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928475816571282, 0.23383842289331924, 0.8410237772334282, 0.0, -0.12571693075540719, -0.24506380536438543, -2.6083828393500443, -0.7149673371095181, -0.5580658266392596, -1.1976884972615673, -2.876005033477747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5582855023094606, 0.7454223285409701, 1.320966063736913, -1.1815900579661462, -2.2181085407857957, -0.5430595762208513, 1.397153250655472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960396432749, -0.4403408777315123, 0.025330721100861507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2163228574663497e-05, 0.00026561526252498984, -8.701367529104261e-05, 0.0, 0.00033678731690860153, 0.00013149582855127422, 2.4337109971788726e-05, 0.0004136562054321969, 1.134893495327528e-05, -0.00024068561703942797, -0.00015059002995320076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008983488774919038, 0.03637525066957294, -0.07188454847778691, -0.002537275603468942, 0.012233617801327062, 0.03712383472024385, 0.05471703808175564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.424883800536471e-07, -1.0876203281328585e-07, -0.00028575196190749576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928361962021858, 0.233851671975343, 0.8410200329115725, 0.0, -0.12570014481308564, -0.24505718307812926, -2.608381384654628, -0.714946639975147, -0.5580654824178932, -1.19770057133443, -2.87601249037681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5578285987012843, 0.7472417640137283, 1.317362530804653, -1.1817186799421848, -2.217505315958886, -0.5412001596216567, 1.3998987606241629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960592890377, -0.4403408817798127, 0.025316430660225216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2770909884935263e-05, 0.00026498164047559765, -7.488643711521706e-05, 0.0, 0.0003357188464307567, 0.00013244572512316, 2.909390832013645e-05, 0.0004139426874227912, 6.884427328987225e-06, -0.0002414814572513849, -0.00014913798126398273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00913807216352482, 0.036388709455163676, -0.07207065864519666, -0.0025724395207737606, 0.012064496538201786, 0.037188331983892126, 0.054910199373815416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9291525549217034e-07, -8.096600676193637e-08, -0.0002858088127258603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928245108894183, 0.23386478804542368, 0.8410174650185066, 0.0, -0.125683527186835, -0.24505075403237622, -2.6083797446478076, -0.7149260860247941, -0.55806531127179, -1.1977126232930966, -2.876019838179076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.557359873636548, 0.7490775025074466, 1.31371866460612, -1.181849972036363, -2.216905181731572, -0.5393214456994128, 1.402677423283606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960735113084, -0.4403408848165188, 0.025302244240532755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3370625534722936e-05, 0.0002623214016136919, -5.135786131682776e-05, 0.0, 0.000332352525012723, 0.00012858091506071477, 3.280013641051642e-05, 0.0004110790070570588, 3.4229220628398828e-06, -0.000241039173333795, -0.0001469560453180969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00937450129472489, 0.03671476987436629, -0.07287732397065966, -0.0026258418835635637, 0.01200268454627503, 0.03757427844487955, 0.05557325318886109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.844454131390296e-07, -6.07341217716913e-08, -0.0002837283938491854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928125975254663, 0.2338777108130339, 0.8410158630732162, 0.0, -0.1256671439747314, -0.24504447219903447, -2.608377986471098, -0.7149057769458779, -0.5580652503388998, -1.1977246030067663, -2.876027063526532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5568762726491504, 0.7509401348519842, 1.3100131355736913, -1.181984612037136, -2.2163048343526506, -0.5374124503813171, 1.4055054932543025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196083799387, -0.44034088711628594, 0.02528823051558007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3826727904008558e-05, 0.0002584553522042788, -3.203890580907234e-05, 0.0, 0.000327664242072245, 0.00012563666683489575, 3.516353418872416e-05, 0.0004061815783248623, 1.2186578059567068e-06, -0.0002395942733952444, -0.00014450694912265818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009672019747952372, 0.03725264689075036, -0.07411058064857856, -0.002692800015456993, 0.012006947578431529, 0.0381799063619132, 0.056561399413934295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0576157060140677e-07, -4.5995343059355314e-08, -0.0002802744990537038]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928005822107565, 0.23389042542853103, 0.8410148861598132, 0.0, -0.1256510139598323, -0.24503832647630847, -2.608376152939475, -0.7148857485231586, -0.5580652620672273, -1.1977364858353845, -2.8760341665429783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5563762310020239, 0.7528339407988729, 1.3062369547787211, -1.182122942229882, -2.2157033441213, -0.535468624793998, 1.4083899574042051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960912332747, -0.4403408888790849, 0.02527441387595175]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4030629419687853e-05, 0.0002542923099423783, -1.953826805875379e-05, 0.0, 0.00032260029798148945, 0.00012291445452000235, 3.667063245698228e-05, 0.00040056845438629304, -2.3456654998743283e-07, -0.0002376565723656537, -0.00014206032892117383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010000832942529793, 0.037876118937773505, -0.07552361589940103, -0.002766603854918861, 0.012029804627013495, 0.038876511746381424, 0.057689282998053766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.486777525501345e-07, -3.525597893159262e-08, -0.00027633279256637983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927886130024168, 0.2339029581009885, 0.8410143843772253, 0.0, -0.12563511083264114, -0.2450323182141585, -2.6083742664359377, -0.7148659747237618, -0.5580653290243688, -1.1977482722593595, -2.876041161779588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558598237937736, 0.7547568426705952, 1.3023937086428552, -1.182264935247827, -2.21510201780957, -0.5334919482142477, 1.4113283165359392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960965966573, -0.4403408902509209, 0.025260777130170713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.393841667927272e-05, 0.0002506534491489933, -1.0035651758644546e-05, 0.0, 0.0003180625438231048, 0.00012016524299924724, 3.773007074423181e-05, 0.0003954759879352741, -1.339142829504216e-06, -0.0002357284794985124, -0.00013990473219042374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010328144165007061, 0.038458037434445515, -0.07686492271731701, -0.0028398603588998673, 0.012026526234592393, 0.039533531595005764, 0.05876718263468003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0726765329846376e-07, -2.7436719599043683e-08, -0.00027273491562077913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092776824624636, 0.23391536552185, 0.8410144391534922, 0.0, -0.12561937333641351, -0.24502644928800751, -2.608372332749249, -0.714846381459219, -0.5580654492593156, -1.197759983980225, -2.8760480752640456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5553285643804892, 0.7567016476649344, 1.2984972245575668, -1.182410240711934, -2.2145038309831597, -0.5314896916689004, 1.4143103114192785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961004586885, -0.440340891338681, 0.025247270725072626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3576755561743843e-05, 0.0002481484172302796, 1.0955253381353154e-06, 0.0, 0.00031474992455246607, 0.00011737852301981131, 3.8673733772419264e-05, 0.0003918652908572367, -2.4046989356143726e-06, -0.00023423441731272078, -0.00013826968915586324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010625188265690203, 0.03889609988678383, -0.07792968170576704, -0.002906109282138934, 0.011963736528207015, 0.040045130906946655, 0.05963989766678648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.724062164925631e-08, -2.175520169768459e-08, -0.00027012810196172857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927653107197078, 0.23392772070120912, 0.84101540580586, 0.0, -0.12560372148059526, -0.2450207360536313, -2.608370340249683, -0.7148268663770398, -0.5580656368309801, -1.1977716584644167, -2.8760549373458373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5547849118132201, 0.7586582290391126, 1.2945673283683066, -1.1825582987058603, -2.2139125863543287, -0.5294722015989911, 1.417321104001079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961032334704, -0.44034089222072975, 0.02523382607193861]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3027809855934757e-05, 0.0002471035871828815, 1.9333047355637315e-05, 0.0, 0.0003130371163650664, 0.00011426468752416804, 3.984999132486252e-05, 0.00039030164358217097, -3.751433291583298e-06, -0.00023348968383076396, -0.00013724163583012978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010873051345381439, 0.03913162748356494, -0.07859792378520314, -0.0029611598785264674, 0.011824892576616503, 0.04034980139818535, 0.06021585163600526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.5495637686507746e-08, -1.764097494381458e-08, -0.00026889306268031713]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927541131276883, 0.23394009802358995, 0.8410185932189661, 0.0, -0.12558808170539637, -0.24501536003159705, -2.6083682275172504, -0.7148073196989726, -0.5580659552445796, -1.1977833488101328, -2.8760617628774376, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5542316414209236, 0.7606159964722238, 1.2906249655285476, -1.182708483457291, -2.21333203892798, -0.5274503660158455, 1.4203449570214883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196105224699, -0.4403408929544426, 0.025220370236506463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2395184038915284e-05, 0.00024754644761651673, 6.374826212170298e-05, 0.0, 0.0003127955039780514, 0.00010752044068553737, 4.225464864792489e-05, 0.0003909335613460387, -6.368271990569878e-06, -0.00023380691432252473, -0.00013651063200414507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011065407845928948, 0.039155348662223484, -0.07884725679517919, -0.0030036950286129248, 0.011610948526976715, 0.04043671166291232, 0.06047706040818713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.982457199812676e-08, -1.4674257741168563e-08, -0.0002691167086428905]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092743215783537, 0.23395255998394907, 0.8410230051473843, 0.0, -0.1255723470215273, -0.24500948683706794, -2.6083661263330646, -0.7147876519622324, -0.5580662673833868, -1.1977950636282821, -2.8760686341751702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5536712534113452, 0.7625660031818171, 1.2866879830377118, -1.182860236787746, -2.2127652088517054, -0.5254334347642385, 1.4233684315272994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066363056, -0.4403408935819532, 0.025206839486613532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1794688302532136e-05, 0.0002492392071820842, 8.823856836351996e-05, 0.0, 0.00031469367738097055, 0.00011746389058215508, 4.202368371624377e-05, 0.0003933547348035006, -6.242776145484021e-06, -0.00023429636298597504, -0.000137425954647393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011207760191569353, 0.03900013419186768, -0.0787396498167154, -0.0030350666091020382, 0.011336601525492554, 0.04033862503213897, 0.06046949011622329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.823213433133761e-08, -1.2550211904220164e-08, -0.0002706149978586365]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927325796914456, 0.23396514844578484, 0.8410271275585507, 0.0, -0.1255564580338701, -0.24500311691316207, -2.6083640599432076, -0.7147677981657665, -0.5580665472338727, -1.1978068265208242, -2.876075583750252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.553105546653773, 0.7645022849839103, 1.2827683981542415, -1.1830131612272698, -2.2122139963352003, -0.5234276176635633, 1.426382469184317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119610762088, -0.44034089413375943, 0.025193188723775455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1272184183163444e-05, 0.00025176923671551226, 8.244822332876133e-05, 0.0, 0.0003177797531437408, 0.00012739847811768642, 4.132779714126504e-05, 0.0003970759293174542, -5.597009716998422e-06, -0.00023525785083845817, -0.00013899150163114093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011314135151442745, 0.03872563604186414, -0.07839169766940694, -0.0030584887904729547, 0.011024250330098417, 0.04011634201350546, 0.06028075314034978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9691486868662377e-08, -1.1036124096475251e-08, -0.00027301525676155737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927221430519952, 0.23397788059636185, 0.8410270716064849, 0.0, -0.12554039099261471, -0.24499642276078032, -2.608362020589197, -0.7147477276260098, -0.5580668007004707, -1.197818655240422, -2.8760826201722662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5525354056982379, 0.7664223422694074, 1.278871353095892, -1.1831670647227828, -2.2116791073875484, -0.5214355596259588, 1.4293832066465353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961082891086, -0.4403408946317607, 0.025179396447075814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0873278901138924e-05, 0.00025464301154047255, -1.119041316239696e-06, 0.0, 0.0003213408251079206, 0.00013388304763496832, 4.0787080209078265e-05, 0.0004014107951335775, -5.069331957641143e-06, -0.00023657439195773594, -0.00014072844028634236, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011402819110700887, 0.03840114570994267, -0.07794090116698955, -0.003078069910258842, 0.010697778953041907, 0.03984116075209075, 0.06001474924436734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3364573338846698e-08, -9.96002479206681e-09, -0.00027584553399285095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927118397610842, 0.23399075006007178, 0.8410239311303209, 0.0, -0.1255241513808587, -0.24498956199327032, -2.608359996228923, -0.7147274444229025, -0.5580670386222834, -1.1978305548826256, -2.8760897378995463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519607905134508, 0.7683268961315398, 1.2749955209541877, -1.1833219600052314, -2.2111602189092636, -0.5194565663562908, 1.4323716913338567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087239965, -0.44034089509134106, 0.025165464592248835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0606581822150228e-05, 0.00025738927419882105, -6.280952327926157e-05, 0.0, 0.00032479223511994534, 0.00013721535019996331, 4.048720548120468e-05, 0.0004056640621466314, -4.758436254420416e-06, -0.0002379928440712219, -0.00014235454560254028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492303695741828, 0.0380910772426483, -0.07751664283408612, -0.0030979056489716097, 0.010377769565691192, 0.03957986539335971, 0.05976969374642933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.697758470711222e-09, -9.191606961494153e-09, -0.0002786370965395946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927016114082483, 0.23400373210759065, 0.8410194512123002, 0.0, -0.12550776676360897, -0.24498264241683182, -2.6083579783408393, -0.7147069809039911, -0.558067269018674, -1.1978425179494117, -2.8760969224402344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5513808833672721, 0.770219150729859, 1.2711345184463556, -1.1834780299146201, -2.210656286818563, -0.5174873471763168, 1.4353528300773581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961089872947, -0.4403408955231401, 0.025151414134471806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0456705671853165e-05, 0.0002596409503772192, -8.959836041594101e-05, 0.0, 0.00032769234499486994, 0.00013839152876997973, 4.035776167439639e-05, 0.0004092703782273909, -4.607927813112079e-06, -0.00023926133572264456, -0.0001436908137622857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011598142923575108, 0.037845091966384706, -0.0772200501566399, -0.0031213981877756675, 0.010078641814011902, 0.03938438359947973, 0.05962277487002981, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.265964787306103e-09, -8.635980485045285e-09, -0.0002810091555406154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092691414881666, 0.23401679135898465, 0.8410150085045758, 0.0, -0.12549127854671643, -0.24497574505774763, -2.608355960179742, -0.7146863868814608, -0.5580674989080651, -1.1978545284643507, -2.8761041534961382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5507943371419204, 0.7721037991406221, 1.2672788624344777, -1.1836355715101474, -2.2101659072623985, -0.5155230332547469, 1.4383339177750694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091267843, -0.4403408959343855, 0.02513727793862914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0393053164340324e-05, 0.00026118502787984593, -8.885415448636424e-05, 0.0, 0.00032976433785099205, 0.00013794718168371885, 4.036322194714469e-05, 0.0004118804506054077, -4.597787821579858e-06, -0.00024021029877926975, -0.0001446211180774292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011730924507034505, 0.037692968215261316, -0.07711312023755544, -0.003150831910545682, 0.009807591123291796, 0.0392862784313995, 0.059621753954225365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7897920090490064e-09, -8.224908377818695e-09, -0.00028272391685331427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926812261786906, 0.23402988986582984, 0.8410113546364125, 0.0, -0.1254747319744555, -0.24496891110737837, -2.6083539390949957, -0.7146657179611566, -0.5580677317620203, -1.1978665659441785, -2.8761114100393854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5501995705682504, 0.7739859735345267, 1.2634180710725733, -1.1837949304919402, -2.209687661112676, -0.5135582639844605, 1.441323046386029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091769961, -0.44034089633000717, 0.025123092917831803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.037740595119924e-05, 0.00026197013690362075, -7.307736326522295e-05, 0.0, 0.0003309314452189297, 0.00013667900738548018, 4.042169492600479e-05, 0.000413378406083312, -4.657079103848079e-06, -0.00024074959655829772, -0.00014513086494717239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011895331473398937, 0.037643487878091735, -0.07721582723808787, -0.0031871796358551034, 0.009564922994449472, 0.039295385405728384, 0.05978257221919284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0042353279090035e-09, -7.91243332768826e-09, -0.00028370041594671626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209267104140628, 0.2340429943556656, 0.8410087467675743, 0.0, -0.12545816787715466, -0.24496215978482463, -2.6083519141469704, -0.7146450246015063, -0.5580679696948085, -1.1978786103348296, -2.8761186733775808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5495950616600683, 0.7758702989590087, 1.2595425870350851, -1.1839564366614876, -2.2092203933095136, -0.5115881754110759, 1.4443276391989144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091630049, -0.44034089671341636, 0.025108892724971923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0369544821449065e-05, 0.00026208979671518603, -5.215737676477587e-05, 0.0, 0.0003312819460165331, 0.0001350264510744388, 4.049896050569199e-05, 0.00041386719300691855, -4.75865576519643e-06, -0.00024088781302224356, -0.00014526676390855757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012090178163641576, 0.0376865084896394, -0.07750968074976214, -0.0032301233909471402, 0.009345356063242948, 0.039401771467691124, 0.060091856257709055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7982296091932287e-10, -7.668184058429974e-09, -0.00028400385719756733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926608744319491, 0.2340560813647748, 0.84100714592006, 0.0, -0.12544161653442082, -0.244955497567562, -2.6083498843726542, -0.7146243440160265, -0.558068214967887, -1.1978906458593799, -2.8761259294668036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5489795953441095, 0.7777601731303376, 1.2556452680292212, -1.1841203496511143, -2.2087633966761158, -0.50960916074856, 1.447353305741198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091030892, -0.4403408970870755, 0.025094702314994995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0333948661378775e-05, 0.00026174018218340985, -3.20169502866619e-05, 0.0, 0.0003310268546768269, 0.00013324434525306686, 4.059548631981508e-05, 0.0004136117095959833, -4.905461569446624e-06, -0.000240710491007444, -0.0001451217844593823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012309326319177109, 0.03779748342657835, -0.07794638011728017, -0.003278259792533467, 0.009139932667958336, 0.03958029325031823, 0.06051333084567211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1983133136278932e-09, -7.473183279607074e-09, -0.00028380819953853617]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926507518548892, 0.23406913975715812, 0.8410063972109484, 0.0, -0.1254250943916626, -0.24494892316027456, -2.608347847602481, -0.7146036957909659, -0.5580684709624298, -1.197902663376985, -2.8761331701051116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5483524295994947, 0.7796573562743375, 1.2517222633995697, -1.1842868227479875, -2.208316486536265, -0.5076193119658289, 1.450403158759081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961090106299, -0.4403408974528865, 0.025080534974728976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.024515411962932e-05, 0.00026116784766674965, -1.4974182231708038e-05, 0.0, 0.0003304428551644765, 0.00013148814574851165, 4.073540347224048e-05, 0.0004129645012103608, -5.11989085565838e-06, -0.00024035035209954281, -0.00014481276615678032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012543314892294048, 0.03794366287999797, -0.07846009259303048, -0.0033294619374617247, 0.008938202797012384, 0.039796975654622084, 0.06099706035765974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8491878388867557e-09, -7.316219767631447e-09, -0.00028334680532038955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092640706247312, 0.23408217066001355, 0.8410063526322429, 0.0, -0.12540860373294258, -0.2449424304491214, -2.60834579975472, -0.7145830813160546, -0.5580687427240117, -1.1979146611692344, -2.876140392932268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477133581084443, 0.7815619052704538, 1.2477731946150523, -1.184455889736394, -2.207879969820352, -0.5056185028546967, 1.4534776604086994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961088954982, -0.44034089781242836, 0.025066391894913224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.009121515419239e-05, 0.000260618057108365, -8.915741105720763e-07, 0.0, 0.00032981317440052325, 0.00012985422306327325, 4.095695521190876e-05, 0.0004122894982256085, -5.435231639094996e-06, -0.00023995584498924465, -0.00014445654312312013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012781429821006966, 0.03809097992232506, -0.07898137569034647, -0.0033813397681313325, 0.008730334318258284, 0.0400161822226447, 0.06149003299236816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3026331635870013e-09, -7.190836763878865e-09, -0.00028286159631504327]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926307691308385, 0.23409518526677917, 0.8410069402647227, 0.0, -0.1253921349031404, -0.24493601079447763, -2.6083437344912714, -0.7145624864817306, -0.5580690372130511, -1.1979266443344707, -2.8761476003795403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5470626671276048, 0.7834724248618756, 1.2438006829971782, -1.184627475277609, -2.207454529886821, -0.5036081384235395, 1.4565749690388725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087651023, -0.44034089816707767, 0.025052263927612763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.987423294722793e-05, 0.0002602921353122936, 1.1752649594739351e-05, 0.0, 0.00032937659604336363, 0.00012839309287525946, 4.1305268976469446e-05, 0.0004118966864805311, -5.889780787719116e-06, -0.00023966330472836243, -0.00014414894544540635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013013819616792176, 0.03821039182843783, -0.07945023235748334, -0.0034317108242994452, 0.008508798670629213, 0.04020728862314311, 0.061946172603460165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.6079186586223684e-09, -7.0929858090402915e-09, -0.0002825593460092203]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926209653450153, 0.23410820123521298, 0.8410082143246913, 0.0, -0.1253756709732818, -0.24492966907772523, -2.6083416402413238, -0.7145418865534288, -0.5580693663526989, -1.1979386237684981, -2.8761547968083865, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5464010059180497, 0.7853865487005857, 1.2398093933607142, -1.1848014244146543, -2.207041062165461, -0.5015906591196544, 1.4596916611728852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961086252894, -0.44034089851804437, 0.025038134870181875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9607571646466996e-05, 0.0002603193686763777, 2.5481199373799305e-05, 0.0, 0.00032927859717196993, 0.0001268343350481614, 4.188499894923267e-05, 0.00041199856603673615, -6.582792954605186e-06, -0.00023958868055025964, -0.0001439285769249745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013233224191099789, 0.038282476774199756, -0.0798257927292779, -0.003478982740907496, 0.008269354427197501, 0.04034958607770108, 0.06233384268025381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7962567570105424e-09, -7.0193344667182365e-09, -0.00028258114861774437]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926113099265617, 0.234121238526162, 0.8410105984550883, 0.0, -0.1253591947926548, -0.24492346106987012, -2.6083394906020354, -0.7145212518834684, -0.5580697569854639, -1.1979506160215903, -2.8761619827878184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5457292068060542, 0.7873015241020881, 1.2358048465440552, -1.184977542987103, -2.206640501330332, -0.49956893056404467, 1.4628236370430239, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961084815775, -0.4403408988663479, 0.025023985465707808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931083690758048e-05, 0.0002607458189806041, 4.768260794038333e-05, 0.0, 0.00032952361254006915, 0.00012416015710208913, 4.2992785767106124e-05, 0.0004126933992083718, -7.812655299679258e-06, -0.0002398450618418897, -0.0001437195886432252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01343598223991072, 0.03829950803004944, -0.08009093633318079, -0.0035223714489752, 0.008011216702579899, 0.0404345711121948, 0.06263951740277536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8742398780104438e-09, -6.966071248459883e-09, -0.0002829880894813476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926018097379936, 0.23413431550550415, 0.8410167207029203, 0.0, -0.12534271040293332, -0.2449177927150775, -2.608337171986235, -0.7145005514573702, -0.5580703255885383, -1.1979626566472965, -2.876169126106767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5450480973304483, 0.7892147697485378, 1.2317922688863037, -1.1851556392368676, -2.206253675763402, -0.4975456560147912, 1.4659670042325852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961083432173, -0.4403408992127139, 0.025009797299432257]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9000377136226644e-05, 0.0002615395868425685, 0.00012244495664020678, 0.0, 0.00032968779442995655, 0.00011336709585256783, 4.637231600443822e-05, 0.00041400852196258844, -1.1372061487813333e-05, -0.00024081251412407916, -0.00014286637897059832, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013622189512117975, 0.03826491292899262, -0.08025155315503234, -0.003561924995294374, 0.007736511338602989, 0.040465490985068735, 0.06286734379122626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7672025351042834e-09, -6.927319278877532e-09, -0.0002837633255110353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925924473431196, 0.23414744577279814, 0.8410295052634726, 0.0, -0.12532615413129616, -0.24491146594222257, -2.6083348858091493, -0.7144797706276045, -0.5580708638242928, -1.1979747109666614, -2.876176309298787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5443583420276428, 0.7911243028203149, 1.2277756938930156, -1.1853355594288222, -2.205881215621574, -0.49552292125638464, 1.4691187756999138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961081996834, -0.4403408995579558, 0.024995556101940583]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.872478974795834e-05, 0.0002626053458798795, 0.0002556912110465393, 0.0, 0.0003311254327433029, 0.00012653545709845852, 4.5723541721021796e-05, 0.0004156165953142211, -1.0764715090429236e-05, -0.00024108638729753126, -0.00014366384040922283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013795106056110737, 0.038190661435542575, -0.08033149986576091, -0.0035984038390933335, 0.007449202836556653, 0.04045469516813203, 0.06303542934656964, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.870679197150595e-09, -6.904837927637466e-09, -0.00028482394983349996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209258321812838, 0.23416063671814646, 0.8410437398870134, 0.0, -0.12530950693366413, -0.2449045021895959, -2.6083326703868854, -0.7144588979179173, -0.5580713315230594, -1.1979867766771146, -2.876183551344064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5436603401302411, 0.7930289777705635, 1.2237574461151752, -1.1855172087541164, -2.205523515013933, -0.4935019358093305, 1.4722772729752847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196108047214, -0.4403408999025876, 0.02498125341052859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8458429479456307e-05, 0.00026381890696620686, 0.00028469247081648613, 0.0, 0.00033294395264052857, 0.0001392750525336554, 4.430844527807723e-05, 0.0004174541937448723, -9.353975332314504e-06, -0.00024131420906434384, -0.00014484090553941895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013960037948034177, 0.03809349900497107, -0.08036495555680431, -0.003632986505881571, 0.007154012152821098, 0.04041970894108255, 0.06316994550741814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0493887787539148e-09, -6.892636135295253e-09, -0.00028605382823986507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925741079071422, 0.23417388915558981, 0.8410558513561877, 0.0, -0.1252927688848866, -0.24489716620190444, -2.608330514922322, -0.7144379299689384, -0.5580717393380537, -1.1979988583162735, -2.876190849474161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5429541857656108, 0.7949285340699397, 1.219738015378438, -1.1857005597806267, -2.20518074960298, -0.49148297443279904, 1.4754422337730737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961078852034, -0.44034090024685824, 0.02496688719657855]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.822044247553129e-05, 0.00026504874886679614, 0.00024222938348463573, 0.0, 0.00033476097555076287, 0.00014671975382885406, 4.3109291263184026e-05, 0.00041935897957802475, -8.15629988416167e-06, -0.00024163278317604285, -0.00014596260194143167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014123087292605495, 0.0379911259875245, -0.08038861473474176, -0.003667020530205452, 0.006855308219058671, 0.04037922753062938, 0.06329921595578203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.240211931340805e-09, -6.8854117509447195e-09, -0.0002873242790007967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925651016993824, 0.2341871982181353, 0.841064560189934, 0.0, -0.12527594904818817, -0.244889683732324, -2.6083283999322955, -0.7144168718483338, -0.5580721071402739, -1.1980109586672534, -2.8761981945080244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5422396885604397, 0.796823478601238, 1.2157162776406405, -1.1858856473286126, -2.204852931173053, -0.48946549449193955, 1.4786146509471971, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961077143157, -0.440340900590808, 0.024952461212057558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8012415519644415e-05, 0.0002661812509097066, 0.00017417667492830742, 0.0, 0.0003363967339687805, 0.00014964939160868815, 4.22998005336657e-05, 0.0004211624120919971, -7.356044404709993e-06, -0.00024200701959800386, -0.00014690067726872157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014289944103422625, 0.03789889062596692, -0.08043475475595119, -0.003701750959717785, 0.006556368598541364, 0.04034959881719022, 0.06344834348246732, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.417755392511266e-09, -6.878994897202412e-09, -0.0002885196904198138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925561871488957, 0.2342005551099568, 0.8410618129676085, 0.0, -0.12525905888066197, -0.24488214897121363, -2.6083263175041984, -0.7143957352424114, -0.5580724431370468, -1.1980230752117988, -2.876205579243565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5415164409760148, 0.7987148547729442, 1.2116899592973498, -1.1860725531242928, -2.204539981107109, -0.4874483756147806, 1.4817964206867469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196107529577, -0.4403409009345591, 0.024937983419938786]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7829100973510103e-05, 0.00026713783642982983, -5.494444651112204e-05, 0.0, 0.00033780335052389384, 0.00015069522220727264, 4.1648561942064236e-05, 0.00042273211844828475, -6.719935459193817e-06, -0.00024233089091155212, -0.0001476947108070534, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0144649516884974, 0.03782752343412516, -0.08052636686581613, -0.0037381159136050312, 0.006259001318883878, 0.04034237754317851, 0.063635394790993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.6947749940585474e-09, -6.875021760779324e-09, -0.00028955584237541106]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925473569686348, 0.23421394931927147, 0.8410514001986437, 0.0, -0.1252421128803267, -0.24487463982329583, -2.6083242575075474, -0.714374534897885, -0.5580727580383967, -1.1980352043068812, -2.876212994467474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5407839134953499, 0.8006039588567667, 1.207656221940558, -1.186261384604039, -2.2042418051162214, -0.48543021847138557, 1.484989893729473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961073308133, -0.4403409012779771, 0.024923463887919817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.766036052164086e-05, 0.0002678841862932682, -0.0002082553792966759, 0.0, 0.0003389200067054922, 0.00015018295835598537, 4.119993302519067e-05, 0.00042400689052663815, -6.298026998768619e-06, -0.00024258190164787988, -0.00014830447818341125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014650549613298546, 0.037782081676448954, -0.08067474713583679, -0.0037766295949263422, 0.005963519817753503, 0.04036314286790055, 0.06386946085452182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.975271951200736e-09, -6.868360176661031e-09, -0.00029039064037935573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092538608537945, 0.23422737072300479, 0.8410381966315522, 0.0, -0.12522512498451718, -0.24486719520491726, -2.6083222122520726, -0.7143532856264078, -0.558073060175217, -1.1980473414524133, -2.8762204318291222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5400415571601024, 0.802492060683494, 1.203612248263087, -1.1864522523033614, -2.203958355577257, -0.48340964194609903, 1.4881974215808351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961071196258, -0.4403409016208386, 0.024908912697799563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7496861379995055e-05, 0.0002684280746661161, -0.00026407134182844635, 0.0, 0.0003397579161902799, 0.00014889236757115187, 4.0905109493422496e-05, 0.0004249854295460771, -6.042736403583455e-06, -0.00024274291064534188, -0.00014874723296733107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014847126704950253, 0.03776203653454571, -0.08087947354941886, -0.0038173539864452552, 0.005668990779289269, 0.04041153050573016, 0.06415055702724443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.223748727891442e-09, -6.857230398915573e-09, -0.0002910238024050965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092529944076841, 0.23424081134161082, 0.8410256342076418, 0.0, -0.1252081083032503, -0.24485987423481367, -2.6083201681803243, -0.7143319993473054, -0.5580733639668903, -1.19805948425245, -2.876227881748336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5392888952123503, 0.8043801749776589, 1.199555730702428, -1.1866452498983047, -2.203689672700999, -0.4813855291015325, 1.4914209744135996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961069010158, -0.44034090196284364, 0.024894338130268572]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.73289222079557e-05, 0.0002688123721204562, -0.00025124847820875187, 0.0, 0.0003403336253374409, 0.0001464194020714956, 4.088143496894334e-05, 0.00042572558204703276, -6.075833466954572e-06, -0.00024285600073301045, -0.00014899838427806628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015053238955041206, 0.037762285883297685, -0.08113035121317991, -0.00385995189886731, 0.005373657525156167, 0.0404822568913309, 0.06447105665528777, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.372200407588851e-09, -6.840101178064515e-09, -0.00029149135061983824]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925213689002095, 0.2342542662563984, 0.8410156966170897, 0.0, -0.12519107192954645, -0.24485269584579836, -2.6083181143208978, -0.7143106838121357, -0.5580736811329241, -1.1980716312967383, -2.8762353371275893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5385255891694956, 0.8062689141714454, 1.1954851943908478, -1.1868404398340329, -2.2034359013919644, -0.47935718789178705, 1.4946618848676878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066785933, -0.44034090230379175, 0.024879745639150908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.715035326296363e-05, 0.00026909829575125156, -0.00019875181104035377, 0.0, 0.0003407274740771001, 0.00014356778030618733, 4.1077188530469014e-05, 0.0004263107033934446, -6.343320675583013e-06, -0.000242940885769391, -0.00014910758505718826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015266120857095179, 0.03777478387572981, -0.08141072623160639, -0.0039037987145622843, 0.00507542618069157, 0.04056682419490884, 0.06481820908176425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.448451342577258e-09, -6.818962556157126e-09, -0.0002918498223532651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925128903715878, 0.23426773395518843, 0.8410091822802671, 0.0, -0.1251740209093694, -0.24484566153708204, -2.608316039956505, -0.7142893418370708, -0.5580740230314425, -1.1980837830640352, -2.8762427927565875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5377514715302819, 0.8081584355938903, 1.191400123617303, -1.1870378465048221, -2.203197285560948, -0.47732441194759734, 1.4979207434700035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961064552824, -0.44034090264356734, 0.024865137375008096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6957057243526444e-05, 0.00026935397580074723, -0.0001302867364530094, 0.0, 0.00034102040354084764, 0.00014068617432632294, 4.1487287853933165e-05, 0.00042683950129745, -6.8379703677965584e-06, -0.00024303534593528628, -0.0001491125799654512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015482352784273262, 0.037790428448899266, -0.08170141547089317, -0.003948133415784107, 0.004772316620325626, 0.04065551888379408, 0.06517717204631435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4662181708756e-09, -6.795512158578875e-09, -0.00029216528285619614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925045163771558, 0.23428121600255097, 0.841006182580274, 0.0, -0.1251569578582527, -0.2448387886481049, -2.6083139287135433, -0.7142679714400227, -0.5580744067173158, -1.198095943175205, -2.8762502430157117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5369665434085289, 0.8100484778689586, 1.1873008984865836, -1.1872374571208901, -2.202974145462632, -0.47528744564920095, 1.5011974420998633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961062340045, -0.44034090298211515, 0.02485051238883319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.674798886404033e-05, 0.00026964094725063224, -5.999399986235081e-05, 0.0, 0.0003412610223343902, 0.0001374577795425186, 4.2224859239858586e-05, 0.0004274079409619088, -7.673717465437287e-06, -0.00024320222339622167, -0.00014900518248552445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015698562435060924, 0.03780084550136615, -0.08198450261439016, -0.003992212321361882, 0.00446280196632445, 0.04073932596792761, 0.06553397259719447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.425557552529118e-09, -6.770956109758903e-09, -0.000292499723498149]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092496254561651, 0.23429471621174008, 0.8410070818992268, 0.0, -0.12513988917033175, -0.24483220114101195, -2.6083117354932526, -0.7142465662167454, -0.5580748787203342, -1.1981081230145345, -2.876257672920959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5361709421772896, 0.8119384662083703, 1.1831885815751473, -1.1874392290545575, -2.2027668457589105, -0.47324687428874174, 1.5044913358973206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961060191408, -0.4403409033193899, 0.024835867359076832]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6523631009647197e-05, 0.00027000418378232623, 1.7986379055652413e-05, 0.0, 0.00034137375841914824, 0.0001317501418588057, 4.38644058126588e-05, 0.000428104465546681, -9.440060369282882e-06, -0.00024359678659280064, -0.00014859810494164313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01591202462478672, 0.03779976678823284, -0.082246338228728, -0.004035438673345594, 0.004145994074430361, 0.04081142720918442, 0.06587787594914715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.2972752186325556e-09, -6.745495156767535e-09, -0.0002929005951271798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924881037954635, 0.23430823941628123, 0.8410104805760512, 0.0, -0.12512278443502178, -0.24482522520652472, -2.6083095683298225, -0.7142251228420964, -0.5580753276019556, -1.1981203016818394, -2.876265125001612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5353648890732149, 0.8138276562638193, 1.1790646163154206, -1.1876431018294107, -2.2025757636634418, -0.47120347108002103, 1.507801477500176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961058005932, -0.4403409036557102, 0.02482119775785553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6301532375350888e-05, 0.00027046409082271354, 6.797353648898557e-05, 0.0, 0.00034209470619956105, 0.00013951868974477018, 4.334326859974839e-05, 0.0004288674929802702, -8.977632425557614e-06, -0.00024357334609904135, -0.00014904161305743515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016121062081492537, 0.037783801108978735, -0.08247930519453568, -0.004077455497066453, 0.0038216419093723523, 0.04086806417441358, 0.0662028320571086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.370951473633228e-09, -6.7264061167353235e-09, -0.00029339202442599564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924800703709684, 0.23432179057086786, 0.8410220134799768, 0.0, -0.1251056348788504, -0.24481791065265449, -2.608307439769383, -0.7142036343470946, -0.5580757402627518, -1.1981324793969663, -2.876272606590669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5345486301753641, 0.815715283537283, 1.174930509137666, -1.187849009680018, -2.202401260338183, -0.46915803691662905, 1.511126864406344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961055784995, -0.44034090399110765, 0.024806498730338414]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6066848990084677e-05, 0.000271023091732647, 0.0002306580785137615, 0.0, 0.0003429911234276098, 0.00014629107740476386, 4.2571208786319135e-05, 0.00042976990003583957, -8.253215924271817e-06, -0.00024355430253760203, -0.00014963178114351563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01632517795701424, 0.037752545469273785, -0.08268214355509021, -0.00411815701214592, 0.003490066505177751, 0.040908683267839405, 0.06650773812336223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.441875061750068e-09, -6.707948679834676e-09, -0.0002939805503423458]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924721542543817, 0.23433537370842256, 0.8410361863605892, 0.0, -0.12508843718601376, -0.24481039522159975, -2.608305342609468, -0.7141820942853051, -0.5580761239398435, -1.1981446603147465, -2.8762801172878922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5337223806981956, 0.8176006922550547, 1.1707875488863044, -1.1880568938312568, -2.202243664018041, -0.46711126031023903, 1.5144666613670423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961053527348, -0.4403409043256543, 0.024791766155124875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5832233173576852e-05, 0.0002716627510938502, 0.00028345761224643766, 0.0, 0.0003439538567329903, 0.0001503086210947443, 4.194319830212943e-05, 0.000430801235789004, -7.673541835312326e-06, -0.00024361835560364367, -0.00015021394446600118, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01652498954337114, 0.037708174355435345, -0.08285920502723475, -0.004157683024774714, 0.0031519264028380908, 0.040935532127800434, 0.06679593921396432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.515292675017828e-09, -6.690933603425866e-09, -0.00029465150427082805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924643533830425, 0.2343489912932732, 0.8410488218063917, 0.0, -0.12507119063353525, -0.2448027929086804, -2.6083032659665797, -0.7141604982942021, -0.558076489693346, -1.1981568485621175, -2.8762876545351124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5328862835321865, 0.8194834221540722, 1.1666366132028636, -1.1882667114267673, -2.2021032639672424, -0.4650636217414324, 1.5178203558558363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961051233105, -0.4403409046594021, 0.024776997345098726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5601742678380886e-05, 0.0002723516970125972, 0.0002527089160520015, 0.0, 0.00034493104957015075, 0.00015204625838715168, 4.153285776985821e-05, 0.000431919822058675, -7.315070048949514e-06, -0.0002437649474163956, -0.00015074494440707218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0167219433201824, 0.03765459798034946, -0.08301871366881823, -0.004196351910210223, 0.002808001015978366, 0.04095277137613264, 0.06707388977588098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.588484374229094e-09, -6.674955954323654e-09, -0.0002953762005229549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924566647408677, 0.2343626439628206, 0.8410582188776666, 0.0, -0.12505389614320422, -0.2447951709450306, -2.6083012010642563, -0.7141388447389879, -0.5580768464749206, -1.198169046739875, -2.876295215589466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5320403872014193, 0.8213632450124095, 1.1624780814579907, -1.1884784401226691, -2.2019803143826557, -0.46301535181210113, 1.5211878305426285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196104890307, -0.4403409049923652, 0.02476219137471044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5377284349828743e-05, 0.0002730533909486646, 0.00018794142549695913, 0.0, 0.0003458898066202609, 0.00015243927299610655, 4.129804646886761e-05, 0.0004330711042844184, -7.135631492355292e-06, -0.0002439635551490929, -0.00015122108707033406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016917926615343505, 0.03759645716674715, -0.08317063489745692, -0.004234573918034956, 0.002458991691729575, 0.04096539858662546, 0.0673494937358462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.660066937348196e-09, -6.659262154159706e-09, -0.00029611940776575553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924490848327904, 0.23437633061949292, 0.8410560835309228, 0.0, -0.12503655431277882, -0.24478752010214577, -2.6082991495782464, -0.7141171348764142, -0.5580771925424345, -1.1981812541074885, -2.8763028006481965, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5311846441002754, 0.8232401533797046, 1.1583118511849793, -1.1886920782222765, -2.201875045276336, -0.4609664411809146, 1.524569354157154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961046486924, -0.44034090532473663, 0.024747349055800713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.515981615443592e-05, 0.0002737331334461661, -4.2706934877010327e-05, 0.0, 0.0003468366085082563, 0.0001530168576964341, 4.102972019804011e-05, 0.0004341972514756301, -6.921350278078256e-06, -0.0002441473522719288, -0.0001517011746054956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017114862022878714, 0.037538167345899924, -0.08332460546022809, -0.004272761992147246, 0.0021053821263965393, 0.04097821262373043, 0.0676304722905131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.8322945298618424e-09, -6.647428706090912e-09, -0.00029684637819448666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924416111709013, 0.23439004885222628, 0.8410461448202162, 0.0, -0.12501916851060207, -0.24477986099661353, -2.608297108373726, -0.7140953718715477, -0.5580775311962143, -1.1981934700527117, -2.8763104073626153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5303189263193195, 0.8251143119355534, 1.1541374375979159, -1.1889076410571624, -2.2017876764519566, -0.458916691640201, 1.527965505878348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961043974682, -0.44034090565650524, 0.024732472576478384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.494732377830591e-05, 0.00027436465466719494, -0.0001987742141298727, 0.0, 0.00034771604353479976, 0.00015318211064475697, 4.082409040750608e-05, 0.0004352600973289408, -6.773075596842037e-06, -0.0002443189044638289, -0.0001521342883787291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017314355619117806, 0.03748317111697732, -0.0834882717412666, -0.004311256697716052, 0.0017473764875824422, 0.0409949908142728, 0.06792303442387358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.024482560456021e-09, -6.6353721321817925e-09, -0.0002975295864465577]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092434241898101, 0.23440379548519505, 0.8410332845986868, 0.0, -0.12500174317378177, -0.24477220846572847, -2.608295074172032, -0.7140735601679984, -0.5580778659557126, -1.1982056933796754, -2.876318032849949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5294430534430056, 0.8269859865684598, 1.1499541243889762, -1.189125154817421, -2.2017184311773126, -0.45686579217268836, 1.5313770578414172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961041372786, -0.4403409059875701, 0.024717564985329347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4738545600715052e-05, 0.0002749326593754455, -0.0002572044305889292, 0.0, 0.00034850673640610146, 0.0001530506177013048, 4.068403387558512e-05, 0.0004362340709858327, -6.695189967279231e-06, -0.00024446653927346663, -0.00015250974666713418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01751745752627855, 0.037433492658127586, -0.08366626417879379, -0.004350275205172314, 0.0013849054928832506, 0.04101798935025297, 0.0682310392613842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.20379147070437e-09, -6.6212970787305426e-09, -0.0002981518229807454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924269768571976, 0.23441756723256021, 0.8410211936055637, 0.0, -0.12498428656625127, -0.24476466142210812, -2.6082930282445553, -0.7140517040554214, -0.5580782163099339, -1.1982179260165966, -2.876325668360499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5285568258487621, 0.8288554673713606, 1.1457611312938534, -1.1893446493034172, -2.2016675466270863, -0.4548134026388708, 1.5348048426790608, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196103873076, -0.44034090631767464, 0.024702629546660564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4530081806884725e-05, 0.0002754349473032083, -0.00024181986246085216, 0.0, 0.0003491321506098486, 0.00015094087240714833, 4.091854953169874e-05, 0.00043712225154075634, -7.007084426564443e-06, -0.0002446527384237837, -0.00015271021099671814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017724551884869048, 0.03738961605801727, -0.08385986190245388, -0.004389889719921877, 0.0010176910045214236, 0.041047790676350795, 0.06855569675287329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.284054276865303e-09, -6.602091496072119e-09, -0.00029870877337561573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924198163869062, 0.2344313611202062, 0.8410122464977837, 0.0, -0.12496680663473403, -0.2447572764006, -2.608290952109812, -0.7140298075149323, -0.5580786015168077, -1.1982301698893667, -2.8763333053410314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5276600565197247, 0.8307230000548407, 1.141557766052324, -1.1895661509740727, -2.2016352798132326, -0.45275922901337, 1.5382496319416816, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961036089454, -0.44034090664660797, 0.024687669311053716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4320940582745845e-05, 0.00027587775291998173, -0.0001789421555994827, 0.0, 0.000349598630344771, 0.00014770043016274956, 4.152269486684434e-05, 0.0004379308097814693, -7.704137474671007e-06, -0.0002448774554009283, -0.00015273961065152483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017935386580748176, 0.03735065366960045, -0.08406730483058789, -0.004430033413108865, 0.0006453362770783385, 0.04108347251001572, 0.0688957852524162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.282608769722518e-09, -6.578666193878617e-09, -0.00029920471213696226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924127625602892, 0.2344451748886894, 0.8410079530709207, 0.0, -0.12494931498664277, -0.244750168298184, -2.6082888080760194, -0.7140078729634463, -0.5580790606308612, -1.1982424314263758, -2.8763409284529082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5267525963935548, 0.8325887363924743, 1.1373435371498235, -1.1897896775209689, -2.2016219084821045, -0.4507030786006588, 1.5417120444288943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961033496475, -0.4403409069741575, 0.02467268668987216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4107653234047511e-05, 0.00027627536966383934, -8.58685372608118e-05, 0.0, 0.00034983296182516905, 0.00014216204832000084, 4.288067585132707e-05, 0.0004386910297200211, -9.182281072144481e-06, -0.0002452307401810137, -0.0001524622375366768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018149202523398262, 0.0373147267526732, -0.08428457805000901, -0.004470530937921876, 0.00026742662256651394, 0.04112300825422484, 0.06924824974425506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.1859567260439755e-09, -6.5509905493119906e-09, -0.00029965242363114023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092405814221847, 0.23445900711925993, 0.8410076193949413, 0.0, -0.12493180308159409, -0.24474297271213807, -2.6082866415957042, -0.7139859042924999, -0.5580795469753796, -1.1982546995110912, -2.876348553631648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5258343494031532, 0.8344527092342277, 1.1331182132852262, -1.1900152349403026, -2.2016277287256725, -0.44864488862339164, 1.5451924969752042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961030939942, -0.440340907300321, 0.024657683298567584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3896676884206326e-05, 0.0002766446114107791, -6.67351958730456e-06, 0.0, 0.0003502381009738575, 0.0001439117209183849, 4.3329606299553536e-05, 0.00043937341892728914, -9.726890369524963e-06, -0.000245361694308613, -0.0001525035747982607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01836493980803164, 0.037279456835067414, -0.08450647729194553, -0.004511148386673094, -0.00011640487135941536, 0.04116379954534321, 0.06960905092619887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.113067642888294e-09, -6.523269362194304e-09, -0.0003000678260915194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923989737066429, 0.23447285729849482, 0.8410173949544465, 0.0, -0.12491426032710078, -0.2447354537589122, -2.608284502251769, -0.71396390406394, -0.5580800095622412, -1.198266962763555, -2.8763561988785353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5249052765248465, 0.8363148320871545, 1.1288818293044027, -1.1902428166137695, -2.201653048920596, -0.4465847280576006, 1.5486911968215638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961028376508, -0.44034090762510103, 0.024642659859163866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3681030408542761e-05, 0.00027700358469752445, 0.00019551119010394067, 0.0, 0.0003508550898663204, 0.00015037906451729831, 4.27868787103912e-05, 0.00044000457119782273, -9.251737232382818e-06, -0.00024526504927672977, -0.00015290493773938857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018581457566134493, 0.03724245705853732, -0.08472767961646975, -0.004551633469339973, -0.0005064038984640953, 0.041203211315821324, 0.06997399692719035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.126869319532842e-09, -6.495600528856092e-09, -0.0003004687880743624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092392244501384, 0.234486725664656, 0.8410311200160856, 0.0, -0.12489668545552522, -0.24472768583321533, -2.6082823951474987, -0.7139418722212836, -0.5580804432043482, -1.1982792199698034, -2.8763638661337536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5239653889266263, 0.8381749203751567, 1.1246346429876275, -1.1904724048381408, -2.201698183225296, -0.4445227753775335, 1.5522081740767828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961025786713, -0.4403409079485101, 0.024627616319695567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3458410517791e-05, 0.0002773673232235325, 0.00027450123278138414, 0.0, 0.0003514974315111833, 0.00015535851393738803, 4.214208540367673e-05, 0.00044063685312759504, -8.672842140828888e-06, -0.0002451441249686973, -0.00015334510436367145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018797751964405293, 0.037201765760044934, -0.08494372633550343, -0.004591764487425716, -0.0009026860940070896, 0.041239053601341294, 0.07033954510438059, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.179590171708666e-09, -6.4681820872776385e-09, -0.00030087078936595537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092385628245801, 0.23450061290819943, 0.841043974989202, 0.0, -0.12487907955192709, -0.24471978613250056, -2.6082803126668055, -0.7139198076214038, -0.5580808557941545, -1.1982914729840688, -2.87637155287179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5230147331040501, 0.840032726778139, 1.1203770586254933, -1.1907039742031829, -2.201763446439512, -0.44245928030608556, 1.555743342117177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961023164102, -0.4403409082705559, 0.024612552136522255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3232511166461702e-05, 0.0002777448708686309, 0.0002570994623296304, 0.0, 0.0003521180719626334, 0.00015799401429511677, 4.164961386793083e-05, 0.0004412919975958298, -8.251796124645198e-06, -0.0002450602853071114, -0.00015373476072257683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01901311645152213, 0.0371561280596449, -0.08515168724268607, -0.004631387300841511, -0.0013052642843153798, 0.04126990142895847, 0.07070336080788225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.245223065171383e-09, -6.440916079248447e-09, -0.000301283663466211]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923791258923294, 0.23451451984754135, 0.841053839335408, 0.0, -0.124861443738691, -0.24471183909284877, -2.6082782461560727, -0.7138977088744598, -0.5580812562752453, -1.198303724005304, -2.876379256266048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5220533722188224, 0.8418879814421235, 1.1161095379235029, -1.1909374956665297, -2.201849150615711, -0.4403945196928669, 1.5592965689997291, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196102050767, -0.44034090859124075, 0.024597466590461522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3004706942721193e-05, 0.0002781387868381211, 0.00019728692411996905, 0.0, 0.00035271626472192926, 0.00015894079303583724, 4.1330214656937515e-05, 0.00044197493888114875, -8.009621817293962e-06, -0.0002450204247059355, -0.00015406788515755283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019227217704553823, 0.03710509327968975, -0.0853504140398068, -0.004670429266939552, -0.0017140835239768332, 0.041295212264373216, 0.0710645376510457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.312866158655143e-09, -6.413697667347336e-09, -0.0003017109212146423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923727385304727, 0.2345284471820798, 0.8410522138073605, 0.0, -0.12484378254230989, -0.24470398536804427, -2.6082761725991963, -0.7138755742604499, -0.5580816683877518, -1.1983159783207948, -2.876386968121842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5210813675425818, 0.8437404292008875, 1.111832515911148, -1.191172940537945, -2.2019556038910966, -0.4383287562399933, 1.56286774570927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961017818023, -0.44034090891060784, 0.024582359033059612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2774723713286888e-05, 0.00027854669076925285, -3.251056095003856e-05, 0.0, 0.00035322392762227256, 0.00015707449608995283, 4.147113752742501e-05, 0.0004426922801981734, -8.242250128389216e-06, -0.0002450863098167964, -0.00015423711587763197, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01944009352481135, 0.03704895517528012, -0.08554044024709782, -0.004708897428303273, -0.002129065507710266, 0.04131526905747279, 0.07142353419081342, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.379290814927804e-09, -6.3873414308310886e-09, -0.000302151148038187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092366466504449, 0.2345423951962035, 0.8410434472930469, 0.0, -0.12482610237027067, -0.2446963384501182, -2.6082740628509478, -0.7138534024818921, -0.5580821222057958, -1.1983282422944421, -2.8763946777497114, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5200987630336469, 0.8455898577733169, 1.107546335549563, -1.1914102836995266, -2.2020831116149004, -0.4362622067468347, 1.566456840158064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961015123277, -0.44034090922857455, 0.024567229195095627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2544052047728873e-05, 0.0002789602824744588, -0.00017533028627138354, 0.0, 0.00035360344078455975, 0.000152938358521538, 4.2194964967829366e-05, 0.0004434355711551118, -9.0763608804408e-06, -0.000245279472945569, -0.00015419255739288778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019652090178698466, 0.03698857144858722, -0.08572360723169974, -0.004746863231634872, -0.002550154476074551, 0.04133098986317244, 0.07178188897588188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.389492783145938e-09, -6.359334203315072e-09, -0.0003025967592796801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923603119785542, 0.23455636366143515, 0.8410353019987932, 0.0, -0.1248084242584862, -0.24468923095470801, -2.6082718269296277, -0.713831191059617, -0.5580827105398091, -1.1983405351414187, -2.876402351621198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.519105575620468, 0.8474361134617115, 1.1032512099441503, -1.1916495054977405, -2.202231978612754, -0.4341950240570607, 1.5700639289912093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961012491604, -0.4403409095449165, 0.024552077293800822]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2309051789507755e-05, 0.00027936930463274916, -0.00016290588507396475, 0.0, 0.00035356223568931217, 0.00014214990820386725, 4.471842639831812e-05, 0.00044422844550102134, -1.1766680265442813e-05, -0.00024585693952967403, -0.00015347742973165416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019863748263576935, 0.03692511376789492, -0.08590251210825339, -0.004784435964277944, -0.0029773399570713964, 0.04134365379548046, 0.07214177666290271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.26334369806623e-09, -6.326839330366228e-09, -0.00030303802589605624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092354267738185, 0.2345703517593418, 0.841037086357163, 0.0, -0.12479072675782128, -0.24468196978950849, -2.608269562166431, -0.71380894456449, -0.5580833331616019, -1.1983528350359811, -2.87641002529331, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5181017919564832, 0.8492791034645827, 1.0989472139222365, -1.1918905930169712, -2.2024025140696923, -0.4321272937656738, 1.5736892075793183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961010055812, -0.4403409098589737, 0.02453690412215113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2088480738122096e-05, 0.0002797619581327564, 3.568716739713108e-05, 0.0, 0.0003539500132983976, 0.00014522330399074646, 4.529526392674975e-05, 0.0004449299025413268, -1.2452435856533942e-05, -0.00024599789125044413, -0.0001534734422348367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020075673279695384, 0.03685980005742207, -0.08607992043827516, -0.004821750384614016, -0.003410709138764685, 0.04135460582773689, 0.07250557176218154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.871585243622658e-09, -6.281143838603349e-09, -0.0003034634329938299]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923483351000108, 0.23458435821041387, 0.8410433690732536, 0.0, -0.1247729928187537, -0.24467419120495768, -2.6082673488459154, -0.7137866672064415, -0.5580839074054937, -1.198365123797158, -2.87641772791869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5170873720815716, 0.85111878546559, 1.0946343060215737, -1.192133538432852, -2.202595032702884, -0.43005904517215826, 1.5773329717200524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961007619495, -0.4403409101713919, 0.024521710933646846]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1865276348927471e-05, 0.0002801290214417316, 0.00012565432181280977, 0.0, 0.00035467878135150756, 0.0001555716910162052, 4.4266410315425116e-05, 0.0004455471609690459, -1.1484877837322644e-05, -0.00024577522353742175, -0.0001540525076079574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020288397498231026, 0.0367936400201483, -0.0862581580132528, -0.00485890831761699, -0.003850372663837832, 0.04136497187031095, 0.07287528281468234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.872635981013225e-09, -6.248363731130677e-09, -0.00030386377008570877]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923425164787207, 0.2345983814792764, 0.841050347506695, 0.0, -0.12475522292646406, -0.24466603816082416, -2.6082651926888545, -0.713764361211254, -0.5580844274851053, -1.1983773992061868, -2.876425460844925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5160622570306792, 0.8529551512103469, 1.09031236495632, -1.1923783374825825, -2.2028098565664673, -0.4279902694218642, 1.5809955887759293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961005111467, -0.4403409104823721, 0.02450649925825024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.163724258027144e-05, 0.0002804653772501444, 0.0001395686688296028, 0.0, 0.0003553978457929012, 0.0001630608826704875, 4.312314121554707e-05, 0.0004461199037493099, -1.0401592232705189e-05, -0.0002455081805767086, -0.00015465852470114935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02050230101784817, 0.03672731489513667, -0.08643882130507669, -0.004895980994609451, -0.004296477271664276, 0.041375515005881276, 0.073252341117538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.0160564280701034e-09, -6.219605362174422e-09, -0.0003042335079320552]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092336812073117, 0.23461241991371726, 0.8410561678621937, 0.0, -0.12473742219781848, -0.24465770728454195, -2.6082630802066746, -0.7137420285191424, -0.5580849074418099, -1.198389663027904, -2.8764332181693337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5150263785751835, 0.8547882069357311, 1.0859812336661037, -1.1926249875088784, -2.2030473162083246, -0.4259209411969448, 1.5846774624480346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961002514438, -0.44034091079192145, 0.024491270776937437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1408811207364125e-05, 0.0002807686888172977, 0.00011640710997282274, 0.0, 0.00035601457291151454, 0.00016661752564447262, 4.224964359557917e-05, 0.0004466538422316748, -9.599134091982837e-06, -0.0002452764343438294, -0.0001551464881691109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020717569109913524, 0.03666111450768433, -0.08662262580432678, -0.004933000525917938, -0.0047491928371491505, 0.041386564498387415, 0.07363747344210625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.194058572993528e-09, -6.190986860384029e-09, -0.00030456962625612414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092331222669531, 0.23462647193549757, 0.841052066079572, 0.0, -0.12471959924255467, -0.24464941954873765, -2.608260982624077, -0.713719670597397, -0.55808537708744, -1.1984019203027907, -2.8764409883123934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5139796698170055, 0.8566179539149585, 1.0816407643975692, -1.1928734852410094, -2.203307750057057, -0.4238510406151482, 1.5883789956931182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960999830891, -0.44034091110001405, 0.02447602713313368]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1178807172321633e-05, 0.00028104043560611415, -8.203565243488869e-05, 0.0, 0.00035645910527626145, 0.00016575471608629082, 4.195165195554541e-05, 0.00044715843490582383, -9.392912601900415e-06, -0.00024514549773298693, -0.00015540286119064626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02093417516356161, 0.03659493958454977, -0.08680938537068913, -0.004969954642621503, -0.005208676974652198, 0.04139801163593095, 0.07403066490167189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.367093402234195e-09, -6.1618522748371104e-09, -0.0003048728760751354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923257491223984, 0.23464053609047267, 0.8410419055366319, 0.0, -0.12470176364589647, -0.24464133781230815, -2.6082588665282125, -0.7136972887095854, -0.5580858710249742, -1.1984141770704049, -2.8764487579958957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5129220742543645, 0.8584443728070699, 1.077290855772315, -1.1931238248543903, -2.2035915028096063, -0.42178057102604194, 1.5921005596733184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960997096226, -0.440340911406489, 0.024460769881989263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0947094264936601e-05, 0.00028128309950176415, -0.0002032108588002307, 0.0, 0.00035671193316402056, 0.00016163472858988137, 4.232191728334855e-05, 0.0004476377562333042, -9.878750685222405e-06, -0.0002451353522834519, -0.00015539367005093068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021151911252818414, 0.03652837784222549, -0.08699817250508257, -0.005006792267617171, -0.005675055050982058, 0.04140939178212616, 0.07443127960400155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.469333852017078e-09, -6.129498761064716e-09, -0.00030514502288832664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923203945074248, 0.234654611139149, 0.8410329760044956, 0.0, -0.12468393783006151, -0.24463381737345521, -2.608256641870117, -0.7136748820675878, -0.5580864822372624, -1.1984264517189394, -2.876456493033111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5118535520675944, 0.86026741417937, 1.0729314763532303, -1.193375996563004, -2.2038989229339174, -0.4197095700785597, 1.59584247316251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960994386653, -0.4403409117110504, 0.024445500384940443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0709229947061336e-05, 0.0002815009735270556, -0.00017859064272867818, 0.0, 0.0003565163166989832, 0.00015040877705849477, 4.449316191303092e-05, 0.000448132839952295, -1.2224245764281534e-05, -0.00024549297069120405, -0.0001547007443032467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0213704437354033, 0.036460827446003485, -0.08718758838169695, -0.005043434172273638, -0.0061484024862227945, 0.041420018949645344, 0.07483826978383265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.41914580147142e-09, -6.091227530342086e-09, -0.00030538994097642047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923151539108384, 0.23466869601465398, 0.8410369603092293, 0.0, -0.12466610730241652, -0.24462629384666287, -2.6082543779253315, -0.7136524549442156, -0.5580871394853086, -1.1984387281294149, -2.876464218332244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5107740827551385, 0.8620869957374822, 1.0685626721506054, -1.1936299866938658, -2.2042303620937327, -0.41763811324967404, 1.5996049968703707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960991865436, -0.44034091201287073, 0.024430219834777226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0481193173066671e-05, 0.0002816975100991661, 7.968609467351684e-05, 0.0, 0.00035661055289996446, 0.00015047053584673302, 4.5278895708661466e-05, 0.0004485424674445845, -1.3144960923647588e-05, -0.0002455282095096486, -0.00015450598266201668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02158938624911852, 0.03639163116224268, -0.08737608405249829, -0.005079802617235855, -0.006628783196301097, 0.04142913657771301, 0.07525047415721449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.042432717502845e-09, -6.0364069223755525e-09, -0.0003056110032643384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923100283255752, 0.23468278982685334, 0.8410444950602779, 0.0, -0.12464825226265315, -0.24461829692062967, -2.6082521656327224, -0.713630011550289, -0.5580877491526708, -1.198450985861604, -2.8764719670998957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5096836649634202, 0.8639030045311199, 1.0641845631582998, -1.1938857771391707, -2.2045861721409685, -0.4155663116254859, 1.603388334133879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960989332096, -0.44034091231267136, 0.024414929235849793]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0251170526505469e-05, 0.00028187624398724346, 0.0001506950209727834, 0.0, 0.00035710079526729164, 0.00015993852066417723, 4.4245852182918864e-05, 0.0004488678785303976, -1.219334724283644e-05, -0.00024515464378050837, -0.0001549753530299669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021808355834365044, 0.03632017587275478, -0.08756217984611223, -0.005115808906095752, -0.007116200944715079, 0.041436032483762424, 0.07566674527016634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.066679126741525e-09, -5.996012086212419e-09, -0.00030581197854868307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923050216204658, 0.23469689186915452, 0.8410516616188889, 0.0, -0.12463037171473912, -0.24460994079275783, -2.6082500133720026, -0.7136075531239947, -0.5580883027034881, -1.1984632225123395, -2.8764797420544017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5085823128939614, 0.8657153051896176, 1.0597973256827151, -1.194143346163699, -2.2049667038536658, -0.4134943030747915, 1.6071926446615838, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196098671681, -0.44034091261067837, 0.024399629399881436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0013410218914426e-05, 0.00028204084602383465, 0.00014333117222068478, 0.0, 0.00035761095828053827, 0.00016712255743682876, 4.304521440058582e-05, 0.0004491685258869663, -1.1071016345658088e-05, -0.0002447330147117217, -0.00015549909012203795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022027041389176896, 0.03624601316995274, -0.08774474951169516, -0.0051513804905646155, -0.007610634253944473, 0.041440171013887465, 0.07608621055409705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.230571128178997e-09, -5.960140387646349e-09, -0.0003059967193671177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923001346662412, 0.23471100150640223, 0.8410570992865238, 0.0, -0.124612469576945, -0.24460141530682628, -2.6082479078840874, -0.7135850801968361, -0.5580888139089831, -1.1984754403653106, -2.876487537895516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5074700501760492, 0.867523751218759, 1.0554011660280609, -1.1944026698833945, -2.2053723078435907, -0.4114222395388834, 1.6110180667421843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960984004842, -0.440340912906907, 0.024384321059351226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.77390844932557e-06, 0.0002821927449540467, 0.000108753352697927, 0.0, 0.00035804275588250685, 0.00017050971863127144, 4.210975830491218e-05, 0.0004494585431732285, -1.0224109900509904e-05, -0.0002443570594232101, -0.0001559168222916129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022245254358245144, 0.036168920582829035, -0.08792319309308277, -0.005186474393909225, -0.008112079798501207, 0.04144127071816173, 0.07650844161200956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.423937811173064e-09, -5.924572664479066e-09, -0.0003061668106041999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092295368781185, 0.23472511812237018, 0.8410525567244167, 0.0, -0.12459455539927589, -0.24459298694859025, -2.608245811408167, -0.7135625925579099, -0.5580893217995248, -1.1984876469894246, -2.876495340225951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5063469036469429, 0.8693281958882545, 1.0509962948414044, -1.1946637235971365, -2.205803335645199, -0.40935027469185803, 1.6148647387961867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960981211883, -0.440340913201293, 0.024369004918805077]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.531770112582698e-06, 0.0002823323193592111, -9.085124214319048e-05, 0.0, 0.0003582835533821116, 0.00016856716472041987, 4.192951841072784e-05, 0.00044975277852422565, -1.0157810831525628e-05, -0.0002441324822768575, -0.00015604660869718368, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02246293058212572, 0.03608889338990902, -0.08809742373312995, -0.005221074274839436, -0.008620556032167825, 0.04143929694050713, 0.07693344108004997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.585919470088617e-09, -5.8877196347280575e-09, -0.00030632281092298554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922907254402637, 0.23473924097755533, 0.8410430468096177, 0.0, -0.12457664465750391, -0.24458494204825634, -2.6082436611804063, -0.7135400894695607, -0.558089891193906, -1.1984998552367652, -2.8765031252828543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5052128977614048, 0.871128501107967, 1.0465829055964682, -1.194926482883499, -2.2062601412752496, -0.4072785536904651, 1.6187328177432267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960978396832, -0.44034091349359755, 0.024353681801970777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.286681842308948e-06, 0.00028245710370275603, -0.00019019829597943813, 0.0, 0.00035821483543939294, 0.00016089800667815171, 4.3004555210236635e-05, 0.0004500617669834312, -1.1387887624443933e-05, -0.00024416494681227545, -0.00015570113806031218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022680117710762223, 0.03600610439425101, -0.08826778489872511, -0.005255185727246861, -0.009136112601008644, 0.04143442002785773, 0.07736157894079969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.630101619651346e-09, -5.8460912789013415e-09, -0.00030646233668602126]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092286203029788, 0.2347533691199173, 0.8410366097666756, 0.0, -0.12455873906782257, -0.24457712016806227, -2.608241455221437, -0.7135175725101464, -0.5580905242752763, -1.1985120646248903, -2.876510891702536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5040680507202013, 0.872924542990264, 1.042161160418863, -1.1951909245602055, -2.2067430834685604, -0.40520720662076, 1.6226224919949306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960975589218, -0.4403409137837116, 0.02433835273812638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.044820950828083e-06, 0.00028256284723898446, -0.00012874085884307046, 0.0, 0.00035811179362700286, 0.00015643760388143953, 4.411917938666845e-05, 0.0004503391882867604, -1.2661627407282987e-05, -0.00024418776250376096, -0.00015532839362946262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022896940824068145, 0.03592083764594023, -0.08843490355210347, -0.00528883353413279, -0.009658843866211879, 0.0414269413941024, 0.0777934850340786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6152266013673606e-09, -5.802281156345202e-09, -0.0003065812768879271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922817994548892, 0.23476750143913333, 0.8410317368181572, 0.0, -0.12454082133663524, -0.24456902851836237, -2.6082392747393492, -0.713495046101068, -0.5580911374821886, -1.1985242565890923, -2.87651866889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5029123732057359, 0.8747162132660619, 1.0377311860746754, -1.1954570270293148, -2.207252526997856, -0.40313634677010934, 1.6265339855381478, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960972813505, -0.4403409140713817, 0.024323018905498428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.807149797687654e-06, 0.0002826463843210159, -9.74589703665631e-05, 0.0, 0.0003583546237463803, 0.00016183299399782965, 4.360964175396415e-05, 0.00045052818156762596, -1.2264138246990007e-05, -0.0002438392840411457, -0.00015554380207734861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02311355028930857, 0.035833405515955936, -0.0885994868837508, -0.005322049382186002, -0.010188870585910479, 0.04141719701301333, 0.07822987086434155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5514245871595604e-09, -5.753402196005454e-09, -0.000306676652559026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922775208871658, 0.23478163673089025, 0.8410269189424823, 0.0, -0.12452290749927553, -0.2445610802733366, -2.60823705671734, -0.7134725099597611, -0.5580917959042532, -1.1985364438454809, -2.876526432828552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5017458688935809, 0.876503417771528, 1.0332930775127567, -1.1957247695296482, -2.2077888417223948, -0.4010660722071327, 1.6304675538598268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196097005762, -0.44034091435659856, 0.02430768157447591]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.557135447079631e-06, 0.00028270583513837535, -9.63575134987599e-05, 0.0, 0.00035827674719448194, 0.00015896490051578013, 4.4360440186066256e-05, 0.00045072282613815867, -1.3168441291317371e-05, -0.00024374512776992012, -0.00015527871823862847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023330086243100588, 0.03574409010932276, -0.08876217123837545, -0.005354850006668302, -0.010726294490778453, 0.041405491259532884, 0.07867136643357993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5117697080917796e-09, -5.704337183720439e-09, -0.00030674662045039944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092273364795529, 0.23479577360256368, 0.8410267217978544, 0.0, -0.12450499913756155, -0.2445531912725162, -2.6082348019596893, -0.7134499663025892, -0.5580924988772874, -1.1985486250627273, -2.876534182971404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5005685356159986, 0.8782860735546842, 1.0288469036469596, -1.1959941324338006, -2.2083524046662615, -0.3989964689225732, 1.6344234810585367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960967315432, -0.44034091463937164, 0.024292342210012866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.31218327346479e-06, 0.00028273743346835396, -3.942892555852602e-06, 0.0, 0.000358167234279383, 0.00015778001640777447, 4.50951530158411e-05, 0.0004508731434375434, -1.4059460683804483e-05, -0.00024362434492997581, -0.00015500285704769982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02354666555164614, 0.03565311566312634, -0.08892347731593916, -0.005387258083048048, -0.011271258877333048, 0.04139206569119055, 0.07911854397420086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4843783973253375e-09, -5.655461688257759e-09, -0.00030678728926084454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092269328669074, 0.2348099105758585, 0.8410328085718266, 0.0, -0.12448707681038215, -0.2445448705057502, -2.608232602889105, -0.7134274203571955, -0.5580931513025706, -1.1985607790395163, -2.876541952707773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4993803688712595, 0.880064103097541, 1.0243927211786348, -1.1962650965612587, -2.208943599389502, -0.3969276174649741, 1.6384020683100775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960964513507, -0.440340914919795, 0.02427700236992856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.072252910155402e-06, 0.00028273946589653745, 0.00012173547944455026, 0.0, 0.00035844654358794566, 0.0001664153353203612, 4.398141168845759e-05, 0.00045091890787210125, -1.3048505665113734e-05, -0.00024307953578067693, -0.00015539472737960248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023763334894781794, 0.03556059085713516, -0.08908364936649825, -0.005419282549162722, -0.011823894464809255, 0.04137702915198115, 0.07957174503081545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6038510622082095e-09, -5.608466697218602e-09, -0.00030679680168615704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922654166067067, 0.23482404617815011, 0.8410412273442239, 0.0, -0.12446914038951988, -0.24453622390550075, -2.608230468085501, -0.7134048745361499, -0.5580937444931828, -1.1985729027930856, -2.876549744394196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49818136574451966, 0.8818374283976583, 1.019930589651557, -1.1965376419472014, -2.2095628134221337, -0.3948595998606208, 1.6424036197278522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960961632773, -0.44034091519783325, 0.024261663614724982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.824124734902576e-06, 0.0002827120458322431, 0.0001683754479456738, 0.0, 0.0003587284172453867, 0.00017293200498848488, 4.2696072079051175e-05, 0.00045091642091311116, -1.1863812242775575e-05, -0.00024247507138728597, -0.00015583372845762609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023980062534796138, 0.035466506002346784, -0.08924263054155514, -0.00545090771885237, -0.012384280652634735, 0.04136035208706627, 0.08003102835549275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.761465067164659e-09, -5.5607647810329235e-09, -0.00030677510407153255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922616295505392, 0.23483817896123738, 0.8410490852513846, 0.0, -0.12445119489880907, -0.24452743829899679, -2.6082283837711637, -0.7133823305847966, -0.5580942928161348, -1.198584998145203, -2.8765575520800817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4969715275917248, 0.8836059669803608, 1.0154605812500674, -1.196811747499963, -2.2102104377362424, -0.39279250428916135, 1.6464284343560336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095867687, -0.44034091547339604, 0.024246327492719974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.574112335228865e-06, 0.0002826556617451584, 0.00015715814321276875, 0.0, 0.00035890981421632693, 0.00017571213007928167, 4.1686286744317405e-05, 0.0004508790270657108, -1.0966459037819545e-05, -0.00024190704235009058, -0.00015615371771426863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024196763055897286, 0.035370771654048096, -0.08940016802979006, -0.0054821110552363845, -0.012952486282172465, 0.04134191142918913, 0.0804962925636271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.911807805937267e-09, -5.5112561318106675e-09, -0.0003067224401001848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922579680585263, 0.23485230751964287, 0.8410551260082697, 0.0, -0.12443324572456714, -0.24451864694277212, -2.6082263344864067, -0.7133597902155533, -0.5580948123792668, -1.1985970672594228, -2.8765653691833957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49575086226104903, 0.8853696289438552, 1.0109827884664662, -1.1970873906083481, -2.2108868656457132, -0.39072642862796775, 1.65047679939993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960955656938, -0.4403409157463759, 0.024230995521878285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.322984026012576e-06, 0.0002825711681099264, 0.00012081513770211566, 0.0, 0.00035898348483850577, 0.00017582712449362893, 4.098569513964275e-05, 0.0004508073848668016, -1.0391262641673134e-05, -0.00024138228439390562, -0.0001563420662759655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02441330661351502, 0.035273239269888054, -0.0895558556720272, -0.005512862167700783, -0.013528558189413202, 0.04132151322387183, 0.08096730087792933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.039863141520829e-09, -5.459597199002481e-09, -0.00030663941683379875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922544348864547, 0.23486643055305054, 0.8410516600789181, 0.0, -0.12441531025423512, -0.24451022400760422, -2.608224252247095, -0.7133372533672377, -0.558095373430019, -1.198609123703882, -2.876573169694533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4945193854577599, 0.8871283156303824, 1.006497328144911, -1.1973645468070087, -2.2115924913823406, -0.388661482186963, 1.6545489860475655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095262447, -0.44034091601655695, 0.024215669123602613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.066344143356634e-06, 0.0002824606681536391, -6.931858703256564e-05, 0.0, 0.0003587094066402643, 0.00016845870335784188, 4.1644786232455846e-05, 0.00045073696631083623, -1.1221015042756142e-05, -0.00024112888918500513, -0.00015601022275316007, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02462953606578174, 0.035173733730543714, -0.08970920643110362, -0.00554312397321154, -0.014112514732550215, 0.041298928820095435, 0.0814437329527083, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0649334679944005e-09, -5.403621012739874e-09, -0.00030652796551343983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922510287796178, 0.23488054673289557, 0.8410453123797789, 0.0, -0.12439739345231203, -0.24450208979585292, -2.608222123215735, -0.7133147218632591, -0.5580959904178329, -1.198621169241677, -2.876580947616735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4932771206221174, 0.8888819200328602, 1.002004340587019, -1.1976431899810067, -2.2123277102860492, -0.38659778527636235, 1.658645250560513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196094961182, -0.44034091628382155, 0.02420034975651545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.812213673893282e-06, 0.00028232359690059553, -0.00012695398278336715, 0.0, 0.00035833603846176075, 0.00016268423502602524, 4.2580627199534485e-05, 0.00045063007957435767, -1.2339756277197146e-05, -0.00024091075590005698, -0.00015555844404097243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02484529671285001, 0.035072088049553814, -0.08985975115784277, -0.005572863479960354, -0.014704378074173489, 0.04127393821201264, 0.08192529025895022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0252987988901175e-09, -5.345292444117205e-09, -0.0003063873417432767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922477524753944, 0.23489465477246935, 0.8410452074994145, 0.0, -0.12437950954869476, -0.24449439493203598, -2.6082198931027345, -0.7132921961287746, -0.5580967194820536, -1.1986332144417962, -2.87658868200518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4920240985108147, 0.8906303281832448, 0.997503986963954, -1.1979232922787466, -2.2130929177335372, -0.38453546777582476, 1.6627658355278006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960946663445, -0.44034091654796714, 0.02418503883586631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.55260844684948e-06, 0.00028216079147531595, -2.0976072879545196e-06, 0.0, 0.0003576780723454631, 0.00015389727633898903, 4.460226001287e-05, 0.00045051468968865444, -1.4581284414749146e-05, -0.00024090400238012088, -0.00015468776889814983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025060442226055177, 0.03496816300769299, -0.0900070724612974, -0.005602045954796174, -0.015304148949760347, 0.0412463500107513, 0.08241169934575161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.896747979429786e-09, -5.282911832871913e-09, -0.0003062184129828008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922445995118852, 0.23490875335282946, 0.8410484974848362, 0.0, -0.12436162721644259, -0.2444862530313363, -2.6082177053556697, -0.7132696829483258, -0.5580974129435289, -1.1986452270616588, -2.876596425174763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49076035572194887, 0.8923734214703991, 0.9929964432129866, -1.198204825000671, -2.213888511169073, -0.38247466647819256, 1.6669109766511037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960943694733, -0.4403409168091144, 0.024169737799255797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.305927018371171e-06, 0.00028197160720243975, 6.57997084341371e-05, 0.0, 0.00035764664504322043, 0.00016283801399335354, 4.3754941293355606e-05, 0.00045026360897635297, -1.3869229504038548e-05, -0.0002402523972538747, -0.00015486339166848937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025274855777316755, 0.03486186574308656, -0.09015087501934801, -0.005630654438487442, -0.015911868710717047, 0.04121602595264391, 0.0829028224660603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.937423846599186e-09, -5.22294577457969e-09, -0.00030602073221025353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922415758091562, 0.2349228411724104, 0.8410526983818923, 0.0, -0.12434374248924537, -0.24447768873916056, -2.60821558440803, -0.7132471849890912, -0.5580980457685073, -1.19865720078781, -2.8766041854502538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4894859337370256, 0.8941110786251171, 0.9884818963113168, -1.1984877579817428, -2.214714887686934, -0.38041552288820757, 1.6710809034491936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960940678644, -0.4403409170672489, 0.02415444805994494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.047405458144199e-06, 0.0002817563916189022, 8.401794112132126e-05, 0.0, 0.0003576945439442653, 0.00017128584351477422, 4.241895279880636e-05, 0.0004499591846913434, -1.2656499568355628e-05, -0.00023947452302428265, -0.00015520550981206458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025488439698465194, 0.034753143094359555, -0.09029093803339643, -0.005658659621436673, -0.016527530357216394, 0.04118287179970025, 0.08339853596179836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.03217883464038e-09, -5.1626905210071585e-09, -0.00030579478621716805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922386825645328, 0.23493691690624557, 0.8410564512649941, 0.0, -0.1243258594111105, -0.24446889925952728, -2.6082135201018084, -0.7132247038994421, -0.5580986285853954, -1.1986691367474456, -2.8766119583016656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48820087632289133, 0.8958431793631576, 0.983960534776307, -1.1987720604255176, -2.2155724461756536, -0.3783581789414705, 1.6752758485502535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960937612354, -0.4403409173222983, 0.024139171052652106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786489246427161e-06, 0.0002815146767031294, 7.505766203420739e-05, 0.0, 0.00035766156269743726, 0.00017578959266584843, 4.1286124428578224e-05, 0.0004496217929827031, -1.1656337761063967e-05, -0.00023871919271227572, -0.00015545702823389334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025701148282685583, 0.03464201476081067, -0.09042723070019727, -0.005686048875495764, -0.017151169774387676, 0.04114687893474189, 0.08389890202119733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.132577920404379e-09, -5.1009871084421215e-09, -0.00030554014585668624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092235922605165, 0.23495097923899583, 0.8410519427358509, 0.0, -0.12430799797295512, -0.24446039171558423, -2.6082114331239783, -0.7132022392024135, -0.5580992433130904, -1.1986810509852375, -2.8766197135440503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4869052277139634, 0.8975696069788188, 0.9794325421284801, -1.1990577012557722, -2.2164615881936442, -0.37630277396989964, 1.679496053466264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960934548712, -0.4403409175740272, 0.024123908203004432]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.519918735469442e-06, 0.0002812466550050523, -9.017058286262138e-05, 0.0, 0.0003572287631076722, 0.00017015087886112826, 4.173955660569902e-05, 0.00044929394057188977, -1.2294553899290337e-05, -0.00023828475583984556, -0.00015510484769303776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025912972178559337, 0.034528552313223757, -0.09055985295653808, -0.005712816605088591, -0.017782840359812042, 0.04110809943141729, 0.08440409832021027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.127284994485085e-09, -5.034578465706776e-09, -0.0003052569929535026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922332950507752, 0.23496502672304753, 0.841047783413629, 0.0, -0.12429016966556214, -0.24445225590891467, -2.60820928186934, -0.7131797919809006, -0.5580999330293639, -1.1986929512033815, -2.8766274348355845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48559903131642573, 0.8992902496173529, 0.9748980930181969, -1.199344649530385, -2.2173827195828784, -0.3742494430608768, 1.6837417729196484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196093153261, -0.44034091782227236, 0.02410866107571083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.2551087796667704e-06, 0.0002809496810341711, -8.318644443892944e-05, 0.0, 0.00035656614785969763, 0.0001627161333910628, 4.3025092769582105e-05, 0.0004489444302589652, -1.3794325470608606e-05, -0.0002380043628809906, -0.000154425830679982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02612392795075296, 0.03441285277068236, -0.09068898220566399, -0.005738965492258566, -0.018422627784678763, 0.04106661818045598, 0.08491438906769068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0322003801230195e-09, -4.964903312858732e-09, -0.0003049425458720436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922307991070202, 0.23497905786820408, 0.8410556573019119, 0.0, -0.12427237387831729, -0.2444442940500671, -2.608207077567316, -0.7131573652116887, -0.5581006863642975, -1.1987048335720254, -2.8766351253435607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4842823300878567, 0.9010049998697255, 0.9703573543408388, -1.1996328745291291, -2.2183362506259474, -0.3721983176407974, 1.6880132741548193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960928754658, -0.44034091806592374, 0.024093431277851397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.991887509777812e-06, 0.0002806229031311392, 0.00015747776565822725, 0.0, 0.0003559157448970038, 0.00015923717695157525, 4.408604048309066e-05, 0.00044853538423953636, -1.5066698673928943e-05, -0.00023764737287945692, -0.00015381015952641166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026334024571381103, 0.0342950050474507, -0.09081477354716017, -0.005764499974883995, -0.01907062086137703, 0.041022508401587915, 0.08543002470341639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.555908666280711e-09, -4.8730279323739366e-09, -0.00030459595718869284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922284323115387, 0.23499307108162593, 0.8410620224473074, 0.0, -0.12425458744531685, -0.24443588510526554, -2.608204929517324, -0.7131349647765528, -0.5581013908433606, -1.1987166731633414, -2.8766428246415074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48295516731288507, 0.9027137532260882, 0.9658104886496258, -1.1999223453926828, -2.219322595734824, -0.37014952706588417, 1.6923108338763249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960925990926, -0.4403409183058999, 0.024078220512936645]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.7335909628940805e-06, 0.00028026426843671655, 0.00012730290790996507, 0.0, 0.00035572866000864066, 0.00016817889603117935, 4.296099983475214e-05, 0.00044800870271772164, -1.408958126273807e-05, -0.0002367918263207148, -0.00015398595893936561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02654325549943236, 0.034175067127253114, -0.09093731382426007, -0.005789417271074297, -0.019726902177531216, 0.040975811498265485, 0.08595119443011036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527463615746055e-09, -4.799523095846143e-09, -0.0003042152982949902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922261997224498, 0.2350070647912494, 0.8410577045336366, 0.0, -0.12423681243828566, -0.24442719122016499, -2.6082028373758583, -0.7131125929317202, -0.5581020469926288, -1.1987284688445206, -2.876650531726507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48161758806816896, 0.904416406601707, 0.9612576589459293, -1.2002130305739471, -2.2203421712282, -0.36810320061496893, 1.696634732660511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196092317279, -0.44034091854252083, 0.024063030469186026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.465178177833702e-06, 0.00027987419246927657, -8.635827341689408e-05, 0.0, 0.00035550014062387086, 0.00017387770201113094, 4.184282931522522e-05, 0.000447436896650261, -1.3122985361760713e-05, -0.0002359136235845094, -0.0001541416999878178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026751584894322514, 0.034053067512376585, -0.09105659407393087, -0.005813703625287087, -0.020391509867517234, 0.04092652901830437, 0.08647797568372015, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.636273932491716e-09, -4.732419414340443e-09, -0.00030380087501240055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922241016812146, 0.23502103740905048, 0.8410463694385787, 0.0, -0.12421905333043677, -0.24441836995158422, -2.608200790619741, -0.7130902517633231, -0.5581026658436722, -1.198740221602538, -2.8766582417647193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48026963952599694, 0.9061128577303539, 0.9566990298493572, -1.20050489804106, -2.221395396086243, -0.36605946817557733, 1.700985254766309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960920279746, -0.44034091877582304, 0.024047862863995576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.1960824706491225e-06, 0.0002794523560217615, -0.0002267019011576197, 0.0, 0.00035518215697770964, 0.00017642537161540508, 4.0935122353427696e-05, 0.0004468233679431487, -1.2377020867531316e-05, -0.00023505516034913785, -0.00015420076425019393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026958970843440316, 0.03392902257293763, -0.09117258193144308, -0.005837349342256303, -0.02106449716086064, 0.04087464878783213, 0.08701044211595904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786086760284027e-09, -4.666044771786301e-09, -0.00030335210380902497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922221440887018, 0.23503498739762702, 0.841036886455467, 0.0, -0.1242013481825966, -0.24441026653189415, -2.608198632835657, -0.7130679387372286, -0.5581034088108263, -1.1987519639596742, -2.876665895865233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4789113717793767, 0.9078030043511358, 0.9521347702517232, -1.200797914844916, -2.222482690370258, -0.3640184612869564, 1.7053626847014656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196091741422, -0.4403409190052954, 0.024032719370823248]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.915185025717901e-06, 0.0002789997715310093, -0.0001896596622333224, 0.0, 0.00035410295680355535, 0.0001620683938012719, 4.315568167552039e-05, 0.0004462605218899997, -1.4859343083454556e-05, -0.0002348471427225327, -0.00015308201027994006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027165354932404285, 0.03380293241563895, -0.09128519195267903, -0.005860336077119565, -0.021745885680302154, 0.04082013777241842, 0.08754859870313353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.731050726891179e-09, -4.58944610775106e-09, -0.0003028698634465459]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922203164538525, 0.23504891307276912, 0.841032541842507, 0.0, -0.12418366740896726, -0.24440192084839657, -2.6081965020990285, -0.7130456612191032, -0.5581041338020172, -1.1987636644722774, -2.876673544051086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4775428382354116, 0.9094867432162603, 0.9475650547121593, -1.2010920480404839, -2.223604478160592, -0.3619803142765615, 1.7097673090060426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960914598313, -0.4403409192310516, 0.02401760180827296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.655269698775106e-06, 0.00027851350284206105, -8.689225920218913e-05, 0.0, 0.00035361547258678437, 0.00016691366995180907, 4.2614732565614394e-05, 0.00044555036250906017, -1.4499823817667592e-05, -0.00023401025206547227, -0.0001529637170595984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027370670879302096, 0.033674777302491084, -0.09139431079127737, -0.005882663911359049, -0.022435755806672526, 0.04076294020789779, 0.08809248609153901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.631816940030336e-09, -4.515125428379149e-09, -0.0003023512510057976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218624636338, 0.23506281281421168, 0.8410356756575126, 0.0, -0.12416600432264169, -0.24439321694763538, -2.608194436426376, -0.7130234228233399, -0.5581048018148895, -1.1987753136380845, -2.876681199480581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47616409798292436, 0.9111639678647261, 0.9429900709564467, -1.2013872631601683, -2.224761182138141, -0.3599451670496676, 1.7141994056720824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960911738547, -0.44034091945324066, 0.024002511926413173]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383635029025387e-06, 0.00027799482885125325, 6.26763001119526e-05, 0.0, 0.00035326172651137423, 0.0001740780152235415, 4.131345304538199e-05, 0.00044476791526665467, -1.3360257447749238e-05, -0.00023298331614080524, -0.0001531085898994188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027574805049744477, 0.03354449296931504, -0.09149967511425215, -0.005904302393688978, -0.023134079550981332, 0.04070294453787818, 0.08864193332079673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.719530654727784e-09, -4.443781211465503e-09, -0.0003017976371957132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922170704203732, 0.23507668502075083, 0.8410423074849374, 0.0, -0.1241483623155468, -0.244384310557527, -2.6081924300125126, -0.7130012257667365, -0.5581054190160493, -1.1987869114340584, -2.876688859076571, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47477521540227136, 0.9128345692861699, 0.9384100182269607, -1.20168352459866, -2.225953224315494, -0.35791316440846443, 1.7186592461985255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960908809377, -0.44034091967180033, 0.02398745145288188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1084319293768643e-06, 0.00027744413078277237, 0.0001326365484943806, 0.0, 0.00035284014189772793, 0.00017812780216790056, 4.01282772728635e-05, 0.00044394113206605953, -1.2344023195454017e-05, -0.00023195591947688265, -0.00015319191979646822, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02777765161305974, 0.033412028428875376, -0.09160105458971957, -0.0059252287698322425, -0.02384084354705729, 0.04064005282406402, 0.08919681052886042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.858339466261557e-09, -4.371193406864528e-09, -0.00030120947062583256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922156543450052, 0.23509052810004516, 0.8410492694389827, 0.0, -0.12413074689682618, -0.24437535618911002, -2.6081904678915984, -0.712979072046481, -0.5581060010212636, -1.1987984597786585, -2.8766965163409224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47337625952659734, 0.9144984368578705, 0.9338251048857156, -1.2019807958468574, -2.2271810265116145, -0.3558844549669417, 1.7231470978947316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960905813695, -0.44034091988659374, 0.023972422108249798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8321507362843026e-06, 0.00027686158588654494, 0.00013923908090758875, 0.0, 0.00035230837441229307, 0.00017908736833938907, 3.9242418287363135e-05, 0.0004430744051094812, -1.1640104287746735e-05, -0.00023096689200289316, -0.00015314528703072957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02797911751348016, 0.03327735143401081, -0.09169826682490159, -0.00594542496394866, -0.024556043922417028, 0.0405741888304541, 0.08975703392412263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.99136182881903e-09, -4.295868409399808e-09, -0.00030058689264164613]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092214376950768, 0.2351043404631002, 0.841055000947925, 0.0, -0.12411316316685755, -0.24436644803037927, -2.6081885369185116, -0.7129569637734708, -0.5581065615745155, -1.1988099601669355, -2.8767041654304397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4719673035386995, 0.916155459116594, 0.9292355465253229, -1.2022790396236822, -2.228445010501852, -0.3538591902620027, 1.7276632254874882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196090276409, -0.44034092009746506, 0.023957425614455224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.554788474152601e-06, 0.00027624726110047753, 0.00011463017884518368, 0.0, 0.0003516745993725979, 0.000178163174614961, 3.861946173756925e-05, 0.0004421654602037304, -1.1211065038467111e-05, -0.00023000776553994804, -0.0001529817903483625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02817911975795758, 0.033140445174471, -0.09179116720785228, -0.005964875536498757, -0.025279679804751456, 0.04050529409878031, 0.0903225518551289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.099211472283008e-09, -4.217426245952425e-09, -0.00029992987589149664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132402106286, 0.23511812054038544, 0.8410520894025295, 0.0, -0.12409562383109912, -0.2443578314158735, -2.608186590890484, -0.712934902017406, -0.5581071484951111, -1.1988214212369817, -2.8767117882556934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47054842423382764, 0.9178055245993192, 0.9246415639932796, -1.202578217928743, -2.229745597925077, -0.3518375237867856, 1.7322078925422681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196089970556, -0.4403409203040926, 0.023942463678312494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2734802787669106e-06, 0.00027560154570521126, -5.8230907909955594e-05, 0.0, 0.000350786715168619, 0.0001723322901152663, 3.892056055380001e-05, 0.00044123512129748107, -1.1738411910820731e-05, -0.0002292214009220766, -0.0001524565050773675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028377586097436923, 0.033001309654503014, -0.09187965064086771, -0.0059835661012142315, -0.02601174846449523, 0.0404333295043409, 0.09089334109560107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.1170619527525975e-09, -4.1325504136064795e-09, -0.00029923872285463716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922122434115142, 0.23513186671753447, 0.8410480627601596, 0.0, -0.12407813314545002, -0.24434945545829273, -2.608184620574443, -0.7129128891496048, -0.5581077715045112, -1.198832843569758, -2.8767193803773026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4691197012732411, 0.9194485226447213, 0.9200433810360168, -1.2028782923185342, -2.2310832111884804, -0.34981960999287814, 1.7367813640484877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960896649155, -0.44034092050638907, 0.02392753805860094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.993598228687448e-06, 0.0002749235429804493, -8.053284739664491e-05, 0.0, 0.00034981371298213994, 0.00016751915161527365, 3.9406320815882495e-05, 0.0004402573560225493, -1.2460188001387484e-05, -0.00022844665552575148, -0.00015184243218659447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028574459211730487, 0.032859960908041684, -0.09196365914525552, -0.006001487795825586, -0.026752265268074542, 0.04035827587814968, 0.09146943012439056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.112808490593471e-09, -4.045929541332256e-09, -0.00029851239423111863]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211389827854, 0.23514557736365363, 0.8410578585477725, 0.0, -0.12406070988152301, -0.24434158934098602, -2.608182553769859, -0.7128909254979008, -0.5581085052234442, -1.1988442413850604, -2.8767269140492373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4676812169158026, 0.9210843438719359, 0.9154412233761499, -1.2031792237209296, -2.2324582726969604, -0.3478056037279826, 1.741383906369289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960893591872, -0.44034092070432945, 0.023912650529372945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7071673205114855e-06, 0.00027421292238309636, 0.00019591575225744434, 0.0, 0.00034846527854018143, 0.000157322346134472, 4.133609168080293e-05, 0.0004392730340808338, -1.4674378662152341e-05, -0.00022795630604805403, -0.00015067343869631415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02876968714876997, 0.032716424544291745, -0.09204315319733973, -0.006018628047907992, -0.027501230169602837, 0.0402801252979109, 0.09205084641602652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.114568185997018e-09, -3.958807443717854e-09, -0.0002977505845598786]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210672469882, 0.23515925083401482, 0.8410652320488057, 0.0, -0.12404332566823896, -0.24433336627992613, -2.608180522997439, -0.7128690180598636, -0.5581092132659031, -1.1988555845615416, -2.876734437299029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46623305579286745, 0.9227128804080058, 0.9108353175470177, -1.2034809732727259, -2.2338712072731286, -0.3457956600814619, 1.7460157904635891, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960890519567, -0.44034092089783095, 0.02389780286694324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4347159446389079e-06, 0.00027346940722347367, 0.00014747002066334785, 0.0, 0.0003476842656809194, 0.00016446122119761613, 4.0615448397339356e-05, 0.0004381487607450033, -1.4160849177094524e-05, -0.00022686352962361731, -0.00015046499583523993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896322245870369, 0.03257073072139712, -0.09211811658264313, -0.00603499103592687, -0.028258691523363376, 0.04019887293041388, 0.09263768188600079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.144607672069865e-09, -3.870029836860596e-09, -0.0002969532485941604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210100400509, 0.23517288551398433, 0.8410664138041404, 0.0, -0.1240259996089749, -0.24432528532443024, -2.608178454395147, -0.7128471669546982, -0.5581099719448497, -1.198866887773201, -2.8767419218274246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4647753056448859, 0.9243340253193703, 0.9062258936717704, -1.2037835010299036, -2.235322437674143, -0.3437899350125588, 1.750677285561212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960887517417, -0.44034092108648143, 0.023882996819733292]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1441387459766836e-06, 0.0002726935993901465, 2.3635106694689962e-05, 0.0, 0.00034652118528124735, 0.0001616191099181937, 4.1372045842379415e-05, 0.0004370221033072508, -1.5173578930017302e-05, -0.0002260642331865976, -0.00014969056791598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029155002959631346, 0.03242289822728867, -0.09218847750494656, -0.006050555143554061, -0.029024608020289562, 0.04011450137806245, 0.09322990195245989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.004299680337448e-09, -3.7730098884789655e-09, -0.0002961209441989173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092209669726632, 0.23518647970489048, 0.8410609226416369, 0.0, -0.12400872906868333, -0.24431719191532206, -2.608176369004111, -0.7128253755692321, -0.5581107597717642, -1.1988781450453656, -2.876749374387809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4633080561386832, 0.9259476735196431, 0.9016131818317626, -1.2040867669585253, -2.236812388228808, -0.34178858417897373, 1.7553686651971052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960884538656, -0.44034092127040986, 0.023868234227515342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.613477534914119e-07, 0.00027188381812338203, -0.00010982325006922625, 0.0, 0.000345410805831185, 0.00016186818216330927, 4.170782071484811e-05, 0.0004358277093212305, -1.575653829063398e-05, -0.00022514544329536624, -0.0001490512076832327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029344990124054126, 0.03227296400545834, -0.09225423680015506, -0.006065318572435898, -0.02979901109329317, 0.0400270166717004, 0.09382759271786134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.957524940023932e-09, -3.6785690750768175e-09, -0.0002952518443589767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093822929072, 0.2352000317341201, 0.8410524181684602, 0.0, -0.12399151746904731, -0.24430910863530028, -2.608174261444083, -0.7128036463850764, -0.5581115824848359, -1.1988893561534155, -2.876756791973215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46183139963036696, 0.9275537212519152, 0.8969974141792522, -1.2043907305783736, -2.238341482998964, -0.3397917636906221, 1.7600902039997306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960881578726, -0.4403409214495698, 0.0238535169087839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.748674497860114e-07, 0.0002710405845922016, -0.00017008946353326963, 0.0, 0.0003442319927206149, 0.0001616656004355191, 4.215120056168994e-05, 0.00043458368311318613, -1.645426143494226e-05, -0.0002242221609999945, -0.00014835170811919904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029533130166324435, 0.03212095464544021, -0.09231535305020915, -0.006079272396967082, -0.030581895403125385, 0.039936409767033054, 0.09443077605250862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.91986084688446e-09, -3.5831994274456708e-09, -0.0002943463746288033]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373323128, 0.23521353992827793, 0.8410438725266971, 0.0, -0.12397436044111262, -0.244300887496518, -2.6081721601693726, -0.7127819829808627, -0.558112410947662, -1.1989005135506143, -2.876764184099484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4603454313905481, 0.9291520657795702, 0.8923788256592536, -1.204695351075815, -2.239910145922031, -0.33779963049762673, 1.7648421773105925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960878624786, -0.4403409216239188, 0.023838846682848473]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8992118888876934e-07, 0.0002701638831565353, -0.00017091283526128758, 0.0, 0.0003431405586938345, 0.00016442277564585636, 4.202549420018781e-05, 0.00043326808427352663, -1.6569256520598532e-05, -0.00022314794397777974, -0.0001478425253884784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029719364796376244, 0.03196689055310157, -0.09237177039997145, -0.006092409948825406, -0.031373258461334215, 0.03984266385990679, 0.09503946621723514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907879199330411e-09, -3.486980077253522e-09, -0.00029340451870856404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373722798, 0.23522700262504698, 0.8410374403757168, 0.0, -0.12395726578111037, -0.24429269050492022, -2.6081700407288655, -0.7127603871926259, -0.5581132705496118, -1.1989116211622244, -2.8767715407119447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.458850249996433, 0.9307426050694383, 0.8877576552539141, -1.2050005870186693, -2.2415187994729133, -0.3358123427934258, 1.7696248590278236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196087569427, -0.4403409217933179, 0.023824225354744655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.993361838705048e-11, 0.0002692539353811438, -0.00012864301960679008, 0.0, 0.0003418932000452387, 0.00016393983195510124, 4.2388810139131095e-05, 0.0004319157647347982, -1.719203899706572e-05, -0.00022215223220196987, -0.00014713224921229104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029903627882302698, 0.03181078579736128, -0.09242340810678894, -0.006104718857087361, -0.03217307101764898, 0.039745754084018536, 0.09565363434462144, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.861033564134219e-09, -3.387982440439172e-09, -0.0002924265620763873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093803793915, 0.23524041814845156, 0.8410374906842297, 0.0, -0.12394022730095001, -0.2442843307062041, -2.6081679394647272, -0.712738862857545, -0.558114124022187, -1.198922669739127, -2.8767788742441045, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4573459573374052, 0.9323252377254454, 0.8831341459157536, -1.2053063966618953, -2.2431678654292573, -0.33383006012496247, 1.7744385224039096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960872769383, -0.4403409219577329, 0.02380965473961995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.860142235474362e-07, 0.0002683104680918212, 1.0061702575075656e-06, 0.0, 0.0003407696032069348, 0.00016719597432282023, 4.202528276281991e-05, 0.00043048670161862127, -1.706945150298024e-05, -0.0002209715380559683, -0.0001466706431985636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03008585318055555, 0.031652653120141615, -0.09247018676321055, -0.00611619286451865, -0.032981319126879634, 0.039645653369266835, 0.09627326752172037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.849774123333481e-09, -3.2882997372638714e-09, -0.0002914123024940956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922096657396688, 0.2352537848481625, 0.8410424879608319, 0.0, -0.12392323099804707, -0.24427550322994218, -2.608165926451545, -0.7127174147928246, -0.5581148993177725, -1.1989336427949417, -2.876786209655038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4558326592403161, 0.9338998624960788, 0.8785085463058647, -1.2056127377883856, -2.2448577636846556, -0.3318529440691488, 1.7792834377311177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960869837198, -0.44034092211708964, 0.023795136622358486]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.707205544453632e-07, 0.00026733399421898104, 9.99455320436035e-05, 0.0, 0.00033992605805876916, 0.00017654952523818242, 4.026026364787405e-05, 0.00042896129440782137, -1.550591171088359e-05, -0.0002194611162937864, -0.000146708218664564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030265961941782726, 0.03149249541266861, -0.09251199219777764, -0.0061268225298059045, -0.03379796510796265, 0.039542321116274225, 0.09689830654416252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.86437310864071e-09, -3.187134913313221e-09, -0.00029036234522933065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922100965552448, 0.23526710107514773, 0.8410490640684287, 0.0, -0.12390627994451152, -0.2442664026430487, -2.60816399756591, -0.7126960453592284, -0.5581156008578939, -1.198944539937928, -2.8767935444610173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4543104655338203, 0.9354663782831726, 0.8738811111354717, -1.2059195673919778, -2.246588910859805, -0.3298811581868147, 1.7841598707715598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960866898349, -0.4403409222713018, 0.023780672785392188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.616311522513805e-07, 0.0002663245397044324, 0.0001315221519361624, 0.0, 0.000339021070711086, 0.0001820117378696219, 3.857771269517252e-05, 0.0004273886719234314, -1.4030802428831007e-05, -0.00021794285972423394, -0.0001466961195899939, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030443874129915626, 0.031330315741874865, -0.09254870340785973, -0.006136592071843622, -0.03462294350299033, 0.039435717646682064, 0.09752866080883925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.877696582075045e-09, -3.0842428966251893e-09, -0.00028927673932593894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210673237465, 0.235280365187046, 0.8410550975979828, 0.0, -0.12388938100491373, -0.24425724891563522, -2.608162132255566, -0.7126747564615128, -0.5581162500032212, -1.1989553642943187, -2.8768008700700447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4527794894455337, 0.9370246848142204, 0.8692520991614596, -1.2062268420164741, -2.2483617212788136, -0.3279148672301889, 1.7890680851332526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960863958802, -0.4403409224202819, 0.023766265007226756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1533644406949973e-06, 0.00026528223796546833, 0.00012067059108091881, 0.0, 0.00033797879195573256, 0.00018307454826957186, 3.73062068809094e-05, 0.00042577795431106595, -1.2982906544877191e-05, -0.0002164871278149365, -0.00014651218054448473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030619521765731874, 0.031166130620956245, -0.09258023948024134, -0.006145492489924126, -0.03545620838017727, 0.03932581913251551, 0.09816428723385391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.879091789393594e-09, -2.979601671892309e-09, -0.0002881555633086335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211398984335, 0.2352935755878579, 0.8410555050831465, 0.0, -0.12387255996124569, -0.24424862974986714, -2.6081602276898908, -0.7126535474193972, -0.5581169529252559, -1.198966136758033, -2.8768081474179703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4512398472649066, 0.9385746831577152, 0.8646217720329866, -1.20653451772497, -2.2501766065511055, -0.32595423653796046, 1.7940083427031794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960861098235, -0.4403409225636437, 0.023751915023692883]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.451493739797756e-06, 0.0002642080162376779, 8.149703274743813e-06, 0.0, 0.0003364208733607873, 0.00017238331536136223, 3.809131350543452e-05, 0.00042418084231146783, -1.4058440694780964e-05, -0.00021544927428580668, -0.00014554695851592048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03079284361254177, 0.030999966869896325, -0.0926065425694596, -0.00615351416991691, -0.036297705445837984, 0.03921261384456869, 0.09880515139853736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.721133778020836e-09, -2.8672360332484574e-09, -0.00028699967067747945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221227393265, 0.23530673061450377, 0.8410565945129704, 0.0, -0.12385584263010913, -0.24424086611527335, -2.608158181332645, -0.7126324177743517, -0.5581178155082985, -1.1989768780505843, -2.8768153374764402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4496916576505383, 0.9401162761748174, 0.8599903925518251, -1.2068425503342475, -2.252033976608772, -0.3239994313693354, 1.798980905793647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960858334568, -0.4403409227013466, 0.02373762464347082]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.749896630280465e-06, 0.0002631005329173592, 2.1788596477419196e-05, 0.0, 0.00033434662273115046, 0.00015527269187593876, 4.092714491516038e-05, 0.0004225929009102559, -1.7251660853081745e-05, -0.0002148258510234415, -0.00014380116939687583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030963792287366225, 0.03083186034204511, -0.09262758962322996, -0.006160652185548577, -0.037147401153326536, 0.0390961033725009, 0.09945126180934931, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527332100915927e-09, -2.7540586281405656e-09, -0.0002858076044412479]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132919391548, 0.23531982864719386, 0.841063223931719, 0.0, -0.1238392122362804, -0.24423321920061875, -2.6081560758377376, -0.7126113735463446, -0.5581187527877131, -1.1989875685837716, -2.8768224695965015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44813504236501883, 0.941649368224787, 0.8553582259425409, -1.2071508962014381, -2.2539342407502954, -0.3220506177501416, 1.8039860375006576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196085635504, -0.44034092283093423, 0.023723395630806134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.03601300906797e-06, 0.0002619606538019357, 0.0001325883749712573, 0.0, 0.0003326078765743858, 0.000152938293091898, 4.210989814999217e-05, 0.0004208845601416009, -1.8745588290554045e-05, -0.00021381066374907771, -0.00014264240122127474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031132305710390124, 0.030661840999390497, -0.09264333218568391, -0.006166917343814103, -0.03800528283046801, 0.038976272383875785, 0.10010263414021117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.959053397238659e-09, -2.5917525910362977e-09, -0.00028458025329374653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922144519139135, 0.2353328680869434, 0.8410676669346647, 0.0, -0.12382263726512502, -0.24422491913739267, -2.6081540567514145, -0.7125904214700881, -0.5581196148820815, -1.1989981758353803, -2.8768295968508615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4465701270552781, 0.9431738636921824, 0.8507255432224222, -1.207459510790999, -2.2558778039573784, -0.3201079635102819, 1.8090239953968683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960854533182, -0.4403409229545072, 0.023709229726479042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199495176391782e-06, 0.00026078879499084965, 8.886005891627416e-05, 0.0, 0.0003314994231077098, 0.00016600126452181964, 4.038172646392046e-05, 0.00041904152513015484, -1.7241887368174105e-05, -0.0002121450321726098, -0.00014254508720348415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03129830619481516, 0.030489909347908482, -0.09265365440237223, -0.006172291791215753, -0.03887126414166291, 0.038853084797193384, 0.1007591579242136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.643715639193411e-09, -2.4714595723696988e-09, -0.00028331808654188023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922157604694372, 0.23534584736592495, 0.8410668504909772, 0.0, -0.12380612670554354, -0.24421636926187285, -2.6081520936769205, -0.7125695627130906, -0.5581204332535905, -1.1990087053101475, -2.8768367071660017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4449970414885467, 0.94468966757663, 0.8460926213960657, -1.2077683487512805, -2.2578650650041974, -0.3181716381099931, 1.8140950299117282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960852664008, -0.44034092307275113, 0.023695128639661108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6171110473867365e-06, 0.0002595855796310719, -1.6328873750977248e-05, 0.0, 0.0003302111916294966, 0.00017099751039630092, 3.9261489880747366e-05, 0.0004171751399507709, -1.636743018040559e-05, -0.0002105894953461487, -0.00014220630280115963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146171133462829, 0.030316077688951552, -0.09265843652713089, -0.006176759205631756, -0.0397452209363828, 0.038726508005776, 0.1014206902972002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.738346712078653e-09, -2.3648780842152937e-09, -0.00028202173635868386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922172187093444, 0.235358764914175, 0.8410654898822433, 0.0, -0.12378970357889556, -0.24420812020919186, -2.608150095496031, -0.7125487967681349, -0.5581213019711135, -1.1990191755044783, -2.8768437658949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4434159178476597, 0.9461966869587102, 0.8414597384723083, -1.2080773645313565, -2.2598964193485593, -0.31624181071038876, 1.8191993904816701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960850686543, -0.4403409231858745, 0.023681094082104545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.916479814417497e-06, 0.00025835096500088103, -2.721217467799101e-05, 0.0, 0.0003284625329597579, 0.00016498105361986836, 3.996361778996376e-05, 0.00041531889911317413, -1.7374350460272283e-05, -0.00020940388661766464, -0.00014117457796544163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03162247281773904, 0.03014038764160504, -0.09265765847514915, -0.006180315601519984, -0.040627086887241, 0.038596547992087005, 0.10208721139883624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.954931207271424e-09, -2.2624669460461017e-09, -0.00028069115113125986]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218820509567, 0.2353716191701673, 0.8410633476626547, 0.0, -0.1237733545919424, -0.24419974024874178, -2.6081481290056185, -0.7125281285220432, -0.5581221523588407, -1.1990295706059233, -2.8768507967261296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44182689050891993, 0.9476948312002192, 0.8368271724979245, -1.2083865130951508, -2.2619722611590123, -0.31431865007858156, 1.824337328212959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960848777775, -0.44034092329331354, 0.02366712775352238]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2036004456094876e-06, 0.0002570851198458028, -4.28443917725028e-05, 0.0, 0.00032697973906325436, 0.00016759920900176153, 3.932980824228668e-05, 0.000413364921835116, -1.7007754542764683e-05, -0.00020790202889795674, -0.0001406166245909901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03178054677479595, 0.02996288483018038, -0.09265131948767472, -0.006182971275886583, -0.04151683620905522, 0.038463212636144044, 0.10275875462577573, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.817535953222311e-09, -2.1487807233846523e-09, -0.00027932657164330354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221916360722, 0.23538440877937317, 0.84113623431204, 0.0, -0.12375716825404547, -0.24419305877140782, -2.608145824566453, -0.7125075583188882, -0.5581233419857754, -1.1990400234739393, -2.87685766726029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44024420765108996, 0.9491709563510456, 0.832235792593017, -1.208693270166394, -2.2640751584080365, -0.31229657903902314, 1.829464531952495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960847210564, -0.4403409233974491, 0.023653231142714507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.861953054122794e-07, 0.000255792184117114, 0.0014577329877055664, 0.0, 0.00032372675793870207, 0.00013362954667919574, 4.6088783318532606e-05, 0.0004114040630983184, -2.3792538695589267e-05, -0.0002090573603190461, -0.0001374106832015365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03165365715659935, 0.02952250301652904, -0.0918275980981496, -0.006135141424863823, -0.04205794498048291, 0.04044142079116874, 0.10254407479071907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1344232765148914e-09, -2.0827119200966643e-09, -0.00027793221615745386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922201868250198, 0.23539634306990492, 0.8412314006554471, 0.0, -0.12374207508064684, -0.24418789206263306, -2.6081432812967753, -0.7124882530489969, -0.5581248514787112, -1.1990499100341336, -2.8768639699113385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43850370439191116, 0.9507742115167876, 0.8272174784440234, -1.209027128457125, -2.266421303994671, -0.30998379134964577, 1.8351043704068524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846727415, -0.44034092351037646, 0.02364019598329647]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0464356000538463e-06, 0.00023868581063525855, 0.0019033268681426727, 0.0, 0.00030186346797247786, 0.00010333417549517549, 5.0865393554811415e-05, 0.0003861053978273925, -3.0189858715893594e-05, -0.00019773120388399588, -0.00012605302097634758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.034810065183576266, 0.03206510331484076, -0.10036628297987271, -0.006677165814621422, -0.0469229117326932, 0.04625575378754693, 0.11279676908714747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.66298946820811e-10, -2.2585461717950393e-09, -0.0002607031883607115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922216437310262, 0.2354080849464401, 0.8413213449530466, 0.0, -0.12372725721475548, -0.24418254640448694, -2.6081406111655814, -0.7124692442472988, -0.5581265156307138, -1.1990596621045952, -2.8768701100452763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43673363940883975, 0.9523871568461224, 0.8221391334650482, -1.2093648423795467, -2.26884706203803, -0.30766750998431247, 1.840851733829424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846677342, -0.44034092362250954, 0.023627366179124365]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.913812013021153e-06, 0.00023483753070400228, 0.00179888595198974, 0.0, 0.0002963573178272846, 0.00010691316292219053, 5.340262387741816e-05, 0.0003801760339596849, -3.328304005376323e-05, -0.00019504140923134718, -0.00012280267875417538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03540129966142834, 0.03225890658669601, -0.10156689957950295, -0.006754278448434319, -0.0485151608671812, 0.046325627306666436, 0.11494726845142962, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0014635555554529e-10, -2.242661711052622e-09, -0.00025659608344215124]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922230828349167, 0.23542179120280785, 0.8413961196175765, 0.0, -0.1237101320622456, -0.2441748125719034, -2.608137768907168, -0.7124473589817228, -0.5581281884138987, -1.1990708510518875, -2.8768772695111755, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4350979902425157, 0.9538648375688505, 0.8174609802263084, -1.2096783122332178, -2.271137094484585, -0.305621782567045, 1.846191036079717, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960845977244, -0.4403409237343511, 0.02361258903531463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8782077809993562e-06, 0.0002741251273545041, 0.0014954932906001, 0.0, 0.00034250305019766023, 0.0001546766516706125, 5.684516826768007e-05, 0.0004377053115208709, -3.3455663696616285e-05, -0.00022377894584475218, -0.0001431893179887565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03271298332648065, 0.029553614454562817, -0.09356306477479633, -0.006269397073421333, -0.04580064893110514, 0.04091454834535009, 0.10678604500586072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4001961193872394e-09, -2.236830667351529e-09, -0.0002955428761946808]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922243783393282, 0.23543903852997633, 0.8414513434500096, 0.0, -0.12368880508011355, -0.24416378984995993, -2.60813464483527, -0.7124202454252593, -0.5581298364460988, -1.1990846663697565, -2.876886296613515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4336623984435202, 0.9551532708001835, 0.8133606711026311, -1.209957272600563, -2.273199334011333, -0.3039200237919479, 1.850916595958042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196084406267, -0.44034092384720275, 0.023594268486829852]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.591008822977664e-06, 0.0003449465433696476, 0.001104476648661621, 0.0, 0.0004265396426407557, 0.00022045443886932763, 6.248143796103482e-05, 0.0005422711292714019, -3.296064400230728e-05, -0.0002763063573822093, -0.00018054204678421757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02871183597991043, 0.02576866462665916, -0.08200618247354668, -0.00557920734690619, -0.041244790534955666, 0.034035175501941975, 0.09451119756650121, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8291438123780864e-09, -2.2570332791828863e-09, -0.00036641096969553655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922255106794738, 0.23546013123742882, 0.8414867720698173, 0.0, -0.12366286242224352, -0.24414972837577267, -2.6081311939056873, -0.7123873802711952, -0.558131470146458, -1.1991013861642983, -2.876897373484767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43242675695397453, 0.9562573128632461, 0.8098307629874593, -1.2102024622712715, -2.2750240339463406, -0.30252510162345925, 1.8550265512441675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960840910455, -0.44034092395784474, 0.023572049757173866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.26468029088339e-06, 0.0004218541490494525, 0.0007085723961537018, 0.0, 0.0005188531574006369, 0.00028122948374484466, 6.901859164659148e-05, 0.0006573030812827114, -3.267400718439803e-05, -0.0003343958908373568, -0.00022153742504650204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02471282979091402, 0.022080841261251077, -0.07059816230343761, -0.004903793414171123, -0.036493998700152935, 0.027898443369773075, 0.0821991057225074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.304433286892409e-09, -2.2128403986714446e-09, -0.000444374593119745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922265159170025, 0.23548434886488395, 0.8415061255847035, 0.0, -0.1236330840946502, -0.24413351552177873, -2.608127454022146, -0.7123497254554765, -0.5581331059967973, -1.19912053705499, -2.8769101520880205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43135851539591985, 0.9572093754222624, 0.8067750353053372, -1.2104195732844663, -2.276643595151556, -0.3013598281014676, 1.8586187114510089, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960836810974, -0.44034092406159986, 0.023546586131306835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.010475057647412e-06, 0.0004843525491029461, 0.00038707029772529206, 0.0, 0.0005955665518662969, 0.0003242570798786655, 7.479767081710877e-05, 0.0007530963143733585, -3.2717006786872644e-05, -0.00038301781383230676, -0.00025557206506673664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021364831161093535, 0.01904125118032559, -0.06111455364244099, -0.00434222026389549, -0.032391224104307406, 0.023305470439832707, 0.07184320413682947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.19896031598218e-09, -2.0751025149419598e-09, -0.000509272517340654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922274555400075, 0.23551049919664788, 0.8415149219583403, 0.0, -0.12360081504552632, -0.24411619699799172, -2.6081235111311813, -0.712308950582451, -0.5581347560571188, -1.1991412817206182, -2.876924034508455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4304134333681977, 0.9580505897866057, 0.8040671225441811, -1.2106158703853926, -2.2781080914157794, -0.30034361325339415, 1.861827325592487, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960832140596, -0.44034092415520626, 0.023519010503724798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8792460097681025e-06, 0.0005230066352782863, 0.00017592747273691278, 0.0, 0.000645380982477355, 0.00034637047574014696, 7.885781929856352e-05, 0.0008154974605094604, -3.3001206429091666e-05, -0.00041489331256218425, -0.0002776484086882363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018901640554443433, 0.016824287286867967, -0.05415825522312133, -0.003925942018529482, -0.029289925284466382, 0.020324296961469136, 0.06417228282956303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.340756875042724e-09, -1.8721281955298883e-09, -0.0005515125516407263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922283902802277, 0.23553740499180734, 0.8415182253375447, 0.0, -0.12356741262006192, -0.244098656648433, -2.6081194585706613, -0.7122667452605677, -0.5581364278203959, -1.1991627663390112, -2.876938417438849, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295475700577736, 0.9588204602625764, 0.8015834397600468, -1.2107984291261271, -2.2794706522647883, -0.2994086858988451, 1.8647869579812928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960827229942, -0.4403409242374828, 0.02349046859225637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8694804402221444e-06, 0.0005381159031892923, 6.606758408896761e-05, 0.0, 0.000668048509288048, 0.00035080699117424197, 8.105121039951375e-05, 0.0008441064376684413, -3.3435265540814266e-05, -0.0004296923678604655, -0.000287658607876933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01731726620848244, 0.015397409519414065, -0.04967365568268607, -0.003651174814689638, -0.027251216980177163, 0.01869854709098071, 0.059192647776113216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.821306158070047e-09, -1.6455303699486633e-09, -0.0005708382293685547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092229362213521, 0.23556419214109076, 0.8415193673058253, 0.0, -0.12353391477712479, -0.24408145874473222, -2.608115372253596, -0.7122244048578634, -0.5581381237752528, -1.1991843319310758, -2.8769528395699946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42872445430342665, 0.9595510565704616, 0.7992223359452336, -1.2109731199137916, -2.280777720365814, -0.2985065236544123, 1.8676104953770492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196082231266, -0.4403409243088011, 0.02346183822581013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9438665863407815e-06, 0.0005357429856686259, 2.283936561278392e-05, 0.0, 0.0006699568587426542, 0.0003439580740157031, 8.17263413041995e-05, 0.000846808054083768, -3.39190971396814e-05, -0.0004313118412897082, -0.000288442622914387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01646231508693933, 0.01461192615770454, -0.04722207629626339, -0.003493815753291094, -0.026141362020514175, 0.018043244888655965, 0.056470747915129293, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.83456558593435e-09, -1.426367202242299e-09, -0.000572607328924798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922303880110799, 0.23559038168015178, 0.8415199852882396, 0.0, -0.1235009259124147, -0.24406483268837104, -2.6081113018315367, -0.7121826869037292, -0.5581398408669545, -1.1992055894462346, -2.876967032815702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42791895589001544, 0.9602641198930109, 0.7969141609822934, -1.2111440345584141, -2.2820628385253374, -0.2976091306509349, 1.8703766996585587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960817519064, -0.4403409243703063, 0.02343363234899367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0515951175859435e-06, 0.0005237907812203649, 1.2359648284266457e-05, 0.0, 0.0006597772942017476, 0.000332521127223907, 8.140844119091067e-05, 0.0008343590826838142, -3.4341834033013567e-05, -0.0004251503031771353, -0.00028386491415034406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016109968268223928, 0.014261266450985874, -0.04616349925880549, -0.0034182928924479396, -0.02570236319046215, 0.017947860069547936, 0.055324085630191866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.587193975638144e-09, -1.2301036995276342e-09, -0.00056411753632922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922314643975465, 0.23561584225978577, 0.8415206281416071, 0.0, -0.12346865914893124, -0.24404875443383964, -2.6081072718949243, -0.7121418622418272, -0.5581415717556476, -1.1992263960601717, -2.8769809036549896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4271176920472807, 0.9609710640627841, 0.7946219475397546, -1.2113134147462656, -2.2833449298152786, -0.29670604552711033, 1.8731283167796038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960812893364, -0.44034092442329237, 0.023406033978459983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152772933227082e-06, 0.0005092115926796831, 1.2857067350550212e-05, 0.0, 0.0006453352696690721, 0.0003215650906277757, 8.059873225149452e-05, 0.0008164932380410139, -3.461777386295665e-05, -0.00041613227874423325, -0.0002774167857476666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016025276854695188, 0.014138883395464165, -0.045844268850776165, -0.0033876037570306798, -0.025641825798819465, 0.018061702476492185, 0.05503234242090225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.251399377513169e-09, -1.0597212265636223e-09, -0.0005519674106737503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092232580107623, 0.23564067171667163, 0.8415212349419124, 0.0, -0.1234370605731956, -0.24403306406223987, -2.608103288474411, -0.7121018685308353, -0.5581433072688579, -1.1992467787880954, -2.87699447765998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42631633281947695, 0.9616754935931877, 0.792333738387956, -1.2114820654238903, -2.2846310717664897, -0.29579816557776584, 1.8758799956162546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960808423015, -0.4403409244688435, 0.023379000395382613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2314201529564266e-06, 0.0004965891377175496, 1.2136006107188386e-05, 0.0, 0.0006319715147126685, 0.0003138074319952333, 7.966841026668133e-05, 0.000799874219836588, -3.4710264206142476e-05, -0.0004076545584751738, -0.0002714800998085875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016027184556074832, 0.014088590608071366, -0.045764183035973204, -0.003373013552493929, -0.025722839024224495, 0.01815759898688995, 0.055033576733016905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.940694945966608e-09, -9.110227440188435e-10, -0.000540671661547411]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209223372539627, 0.23566506806782841, 0.8415217812975562, 0.0, -0.12340594956291107, -0.24401758090343914, -2.6080993451677648, -0.7120624836986472, -0.5581450407705657, -1.1992668474692554, -2.8770078362267806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42551557505713944, 0.9623767297213253, 0.7900514091170274, -1.2116499838904833, -2.2859214864877115, -0.29489107317242, 1.8786305914415817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960804069877, -0.44034092450770895, 0.023352380809571575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2905772941065556e-06, 0.00048792702313550185, 1.0927112874049084e-05, 0.0, 0.0006222202056907677, 0.00030966317601457835, 7.88661329248291e-05, 0.0007876966437629345, -3.4670034157743676e-05, -0.0004013736231996911, -0.00026717133601586484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01601515524674981, 0.014024722562751344, -0.045646585418570494, -0.003358369331861143, -0.0258082944244407, 0.018141848106916394, 0.055011916506542455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.706274311049773e-09, -7.773093037112224e-10, -0.0005323917162207316]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922348953618178, 0.23568922979927492, 0.8415222566785925, 0.0, -0.123375129465284, -0.24400216448610904, -2.608095430822606, -0.712023463875547, -0.5581467688719711, -1.1992867246130448, -2.8770210672879366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42471767050002407, 0.9630727822489621, 0.7877811163116816, -1.2118169029211905, -2.28721408021122, -0.29399025899148507, 1.8813739028142424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960799793762, -0.4403409245403216, 0.023326009828649293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3399310956571104e-06, 0.00048323462893022737, 9.507620725404603e-06, 0.0, 0.0006164019525410937, 0.00030832834660205323, 7.828690317029863e-05, 0.000780396462003816, -3.456202810875578e-05, -0.0003975428757877269, -0.00026462122312433816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015958091142307503, 0.013921050552737518, -0.045405856106917414, -0.003338380614145172, -0.02585187447017159, 0.018016283618698822, 0.05486622745321367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.552228758823872e-09, -6.522531359252474e-10, -0.000527419618445673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092236089442465, 0.2357133007651516, 0.8415226672037902, 0.0, -0.12334445117290906, -0.24398673651659994, -2.6080915348528966, -0.7119846230807773, -0.5581484910085028, -1.199306504474441, -2.877034237148521, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42392436326708854, 0.9637620898156535, 0.785527656721029, -1.2119826123190947, -2.2885072294691815, -0.29309891318302905, 1.8841050985136476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196079556518, -0.4403409245668912, 0.023299761418517764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.388161294365743e-06, 0.0004814193175336523, 8.210503954310316e-06, 0.0, 0.0006135658474991242, 0.00030855939018207835, 7.791939418756594e-05, 0.0007768158953953921, -3.4442730633713985e-05, -0.0003955972279284372, -0.00026339721168615413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015866144658710776, 0.013786151333827379, -0.045069191813052134, -0.003314187958082865, -0.02586298515922863, 0.01782691616911975, 0.054623913988103075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.457162595218221e-09, -5.313923472491648e-10, -0.0005249682026306076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922373096431715, 0.2357373554602591, 0.8415230305637231, 0.0, -0.12331383313096314, -0.24397127446279795, -2.6080876499174175, -0.71194585879409, -0.5581502083641651, -1.1993262395279525, -2.8770473817984348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4231361474736072, 0.9644441377747965, 0.7832924464386829, -1.2121470755077381, -2.2898008375515504, -0.292217667083622, 1.8868230698752826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960791368715, -0.44034092458751367, 0.023273566174345575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4404014132461273e-06, 0.00048109390215006183, 7.267198659375373e-06, 0.0, 0.0006123608389183291, 0.00030924107603955115, 7.769870958462718e-05, 0.0007752857337444723, -3.4347113243743554e-05, -0.00039470107022578484, -0.0002628929982758232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015764315869626497, 0.013640959182861963, -0.04470420564692132, -0.003289263772868496, -0.025872161647381108, 0.017624921988140904, 0.05435942723269867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.392931709869209e-09, -4.124487802740948e-10, -0.0005239048834437878]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092238558825656, 0.23576141053205174, 0.8415233686300534, 0.0, -0.12328325243654976, -0.2439557920151657, -2.6080837724010726, -0.7119071414159466, -0.5581519227870049, -1.199345945387338, -2.8770605110628282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4223523698543891, 0.9651193702015691, 0.7810737984948897, -1.2123104169868437, -2.2910962516623736, -0.29134533396449097, 1.8895301632215622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960787200638, -0.4403409246022554, 0.023247404124884127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4983649688536877e-06, 0.0004811014358528989, 6.761326606055589e-06, 0.0, 0.0006116138882675735, 0.00030964895264502747, 7.755032689620944e-05, 0.0007743475628682688, -3.4288456795332206e-05, -0.00039411718771227295, -0.0002625852878715163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015675552384362555, 0.013504648535452373, -0.04437295887586491, -0.0032668295821129466, -0.02590828221646176, 0.017446662382620555, 0.054141866925591864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.336152004959027e-09, -2.9483383204032195e-10, -0.0005232409892289644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922398394839423, 0.23578544723407127, 0.8415237008592102, 0.0, -0.12325272323726047, -0.2439403182548261, -2.608079901591061, -0.7118684876951991, -0.5581536360211438, -1.1993656140432984, -2.8770736183330112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42157170330215116, 0.9657887980086253, 0.7788682009049951, -1.2124728538313292, -2.292395659042311, -0.2904799007452496, 1.8922307511121659, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960783064311, -0.44034092461119667, 0.023221286690121322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5613165727152883e-06, 0.00048073404039043435, 6.644583136598058e-06, 0.0, 0.0006105839857859857, 0.0003094752067921484, 7.741620023622234e-05, 0.0007730744149506638, -3.426468277858962e-05, -0.00039337311920644867, -0.00026214540366160043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01561333104475981, 0.013388556141123548, -0.04411195179789197, -0.003248736889710461, -0.025988147598741438, 0.01730866438482799, 0.054011757812075435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.272654326006525e-09, -1.788258857433844e-10, -0.0005223486952560803]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092241153103414, 0.23580943343363525, 0.8415240404833962, 0.0, -0.1232222746465587, -0.24392488207649005, -2.608076038413205, -0.7118299333489168, -0.5581553493164322, -1.1993852276726218, -2.8770866904437438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42079265955417344, 0.9664535785191612, 0.7766716961082093, -1.212634621195772, -2.293701407394966, -0.2896193457177761, 1.8949296662867212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960778965756, -0.440340924614439, 0.02319523811198458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.627238943820995e-06, 0.000479723991279697, 6.792483720689729e-06, 0.0, 0.0006089718140354803, 0.0003087235667211426, 7.726355711621118e-05, 0.000771086925645637, -3.426590576893101e-05, -0.00039227258646606824, -0.0002614422146470036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015580874959554462, 0.013295610210719745, -0.04393009593571532, -0.003235347288853942, -0.02611496705310561, 0.017211100549470552, 0.05397830349110793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.197111136692185e-09, -6.484728093278991e-11, -0.0005209715627347895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092242500054431, 0.23583333917995253, 0.8415243937262556, 0.0, -0.12319193475318685, -0.24390950385004634, -2.6080721843085497, -0.7117915131284361, -0.5581570633418861, -1.1994047687729104, -2.8770997147905937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4200139636292416, 0.9671147104640737, 0.7744808856812928, -1.2127959181453245, -2.295015497776658, -0.28876212112143645, 1.8976310505495397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960774910598, -0.4403409246120918, 0.02316928194668761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6939020335182154e-06, 0.00047811492634575376, 7.064857187734985e-06, 0.0, 0.0006067978674369437, 0.00030756452887392905, 7.70820931088602e-05, 0.0007684044096126242, -3.428050907739793e-05, -0.0003908220057691243, -0.0002604869369985441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015573918498637348, 0.013222638898248726, -0.043816208538330355, -0.00322593899105221, -0.026281807633830957, 0.017144491926792838, 0.05402768525636815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.110315293499276e-09, 4.6944804177953823e-11, -0.0005191233059394407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922438798573534, 0.2358571444272394, 0.8415247611308359, 0.0, -0.12316172246009313, -0.24389419335789833, -2.608068340507095, -0.7117532505645536, -0.558158778287458, -1.199424225430224, -2.8771126829367297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41923473532055916, 0.9677728866796532, 0.7722934161990574, -1.212956881883158, -2.2963393354168686, -0.2879073096273501, 1.9003377944197228, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960770902595, -0.4403409246042542, 0.023143434124516634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7596058447164707e-06, 0.000476104945737298, 7.348091605041611e-06, 0.0, 0.0006042458618744598, 0.00030620984296020646, 7.687602909510037e-05, 0.0007652512776494267, -3.429891143800084e-05, -0.0003891331462746232, -0.00025936292271699256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0155845661736487, 0.013163524311589642, -0.04374938964470688, -0.0032192747566692206, -0.02647675280421163, 0.017096229881726443, 0.054134877403664294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.01600633038393e-09, 1.5675137198967494e-10, -0.0005169564434195082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922452916000858, 0.2358808403621116, 0.8415251397821107, 0.0, -0.12313164583970654, -0.24387895172115687, -2.6080645077163536, -0.711715155813482, -0.5581604940444943, -1.1994435924773454, -2.87712559131105, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41845450336903484, 0.9684284818251855, 0.7701080173027351, -1.2131175865810657, -2.2976737120383386, -0.2870545511453888, 1.9030514941192362, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196076694342, -0.4403409245910031, 0.02311770150108781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8234854651376114e-06, 0.0004739186974440934, 7.573025496729262e-06, 0.0, 0.0006015324077317446, 0.00030483273482931615, 7.66558148236624e-05, 0.0007618950214334908, -3.4315140727767546e-05, -0.0003873409424277983, -0.0002581674864028675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015604639030486773, 0.01311190291064501, -0.043707977926445755, -0.0032140939581541406, -0.026687532429398322, 0.01705516963922575, 0.054273993990267506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.918348766056197e-09, 2.650229335057428e-10, -0.000514652468576475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922467343183218, 0.2359044269142091, 0.8415255254644389, 0.0, -0.12310170444313419, -0.24386377493927877, -2.608060686115852, -0.7116772284471309, -0.5581622103830651, -1.1994628701224501, -2.8771384401500866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4176731159377752, 0.9690816227511331, 0.7679242635833511, -1.2132780573832522, -2.299018936029712, -0.28620385908414797, 1.9057727319204802, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960763033183, -0.440340924572389, 0.023092083757146897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8854364718654023e-06, 0.0004717310419500043, 7.713646564592234e-06, 0.0, 0.0005988279314469956, 0.00030353563756180154, 7.643201002834777e-05, 0.0007585473270231177, -3.4326771416632615e-05, -0.00038555290209570716, -0.00025697678073433646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015627748625193033, 0.013062818518951868, -0.043675074387681916, -0.003209416043731131, -0.02690447982746789, 0.017013841224816428, 0.05442475602487812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.820471259658485e-09, 3.7228274721579084e-10, -0.0005123548788182946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922482072344842, 0.2359279089154134, 0.841525914222004, 0.0, -0.1230718930598605, -0.24384865728966337, -2.608056875514007, -0.7116394620836728, -0.55816392708018, -1.1994820616189485, -2.8771512318041363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4168906142633456, 0.9697322875982185, 0.7657422392854535, -1.2134382896662679, -2.3003750177240807, -0.28535542471059344, 1.90850147292552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960759171188, -0.4403409245484401, 0.023066576541881698]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9458323249921477e-06, 0.00046964002408588835, 7.775151300331361e-06, 0.0, 0.000596227665474031, 0.00030235299230778275, 7.621203690126238e-05, 0.0007553272691621398, -3.433394229827986e-05, -0.0003838299299675208, -0.0002558330809954987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015650033488590995, 0.01301329694170914, -0.043640485957952946, -0.003204645660315158, -0.027121633887366898, 0.016968687471091107, 0.05457482010079753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.723991917998616e-09, 4.789779770359519e-10, -0.0005101443053039941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922487188422875, 0.2359512926173417, 0.8414798981621372, 0.0, -0.12304217007769358, -0.2438328025892432, -2.608053233455713, -0.7116018612972712, -0.5581654649798811, -1.1995011740929382, -2.87716403092832, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41622679897001835, 0.9702865401809379, 0.763883358433907, -1.2135778829397672, -2.3015461478541615, -0.284671909354924, 1.9108411860728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075585609, -0.44034092452713464, 0.023041174375794907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0232156067228836e-06, 0.0004676740385663791, -0.0009203211973347449, 0.0, 0.0005944596433383856, 0.0003170940084034714, 7.284116588084856e-05, 0.0007520157280314512, -3.0757994020575036e-05, -0.0003822494797954897, -0.000255982483672668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013276305866545001, 0.011085051654385976, -0.03717761703092988, -0.002791865469985349, -0.023422602601618707, 0.013670307113389343, 0.04679426294614361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.630193781554256e-09, 4.2610865232925507e-10, -0.0005080433217358516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092248984882419, 0.235974268389336, 0.8414506529541362, 0.0, -0.1230129407403171, -0.24381756337189522, -2.6080496259565082, -0.7115648801886544, -0.5581669870332563, -1.199520018068767, -2.87717661581652, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4157054495725053, 0.970726134875539, 0.7624113404522476, -1.2136924119698704, -2.302488665425653, -0.28416729112142136, 1.9127088918606323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960753270093, -0.44034092451105267, 0.02301618802811448]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.320802629738785e-07, 0.00045951543988579204, -0.0005849041600194818, 0.0, 0.0005845867475296946, 0.00030478434695945265, 7.214998409164552e-05, 0.0007396221723374655, -3.044106750547131e-05, -0.00037687951657553657, -0.00025169776400109383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010426987950260405, 0.00879189389202301, -0.02944035963318739, -0.00229058060206577, -0.018850351429836387, 0.010092364670052284, 0.03735411575610158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.171997670780403e-09, 3.216397380081335e-10, -0.0004997269536085335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922491494170983, 0.23599624983988501, 0.8414483496448353, 0.0, -0.122984921306867, -0.24380364302824198, -2.608046030740962, -0.7115293881312232, -0.5581685710940243, -1.1995381647932162, -2.8771886485782794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4153133445449481, 0.9710617032434499, 0.7612911261863405, -1.2137835548633018, -2.303218483848184, -0.2838093796255577, 1.9141429507514227, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751444154, -0.4403409245013862, 0.022992208098654425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2906935816892777e-07, 0.00043962901098051926, -4.606618601843708e-05, 0.0, 0.0005603886690020853, 0.0002784068730651544, 7.19043109229564e-05, 0.0007098411486224862, -3.1681215360431484e-05, -0.0003629344889806832, -0.00024065523518950488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007842100551144033, 0.006711367358216193, -0.022404285318141592, -0.0018228578686265181, -0.014596368450615259, 0.007158229917273065, 0.02868117781580587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.651877703104973e-09, 1.933301689856042e-10, -0.00047959858920105706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492437373727, 0.23601658623147476, 0.8414590466242347, 0.0, -0.12295889779171289, -0.2437913255747105, -2.608042497371656, -0.7114963632547027, -0.5581702289630247, -1.1995551136100802, -2.8771997770817075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41502627397516445, 0.9713122651738108, 0.760458530364623, -1.2138548491255416, -2.303770441791338, -0.2835593787138501, 1.9152187220931172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119607504069, -0.44034092450048995, 0.02296989711802654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8864054873582224e-07, 0.000406727831794947, 0.0002139395879865806, 0.0, 0.0005204703030823638, 0.00024634907062953237, 7.066738611790935e-05, 0.0006604975304108868, -3.315738000833834e-05, -0.0003389763372812621, -0.0002225700685628714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005741411395673626, 0.005011238607218407, -0.016651916434352116, -0.0014258852447985985, -0.011039158863079185, 0.005000018234151651, 0.02151542683389112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0745040033420788e-09, 1.7924738970382162e-11, -0.00044621961255772425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492933419876, 0.23603475577432742, 0.8414750227616592, 0.0, -0.1229355231945582, -0.2437809814534243, -2.6080390312703785, -0.7114666078848317, -0.5581720073977583, -1.1995704589743537, -2.877209698784248, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4148198000911033, 0.9714968972861152, 0.7598487496944001, -1.2139100078181488, -2.304181407589278, -0.2833847366983969, 1.9160138213012863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960750336107, -0.4403409245145704, 0.02294979900678752]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.920922989975184e-08, 0.00036339085705321047, 0.00031952274849119864, 0.0, 0.00046749194309373803, 0.0002068824257242287, 6.932202555167622e-05, 0.000595107397419589, -3.5568694672535596e-05, -0.00030690728546846455, -0.00019843405081240186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004129477681223238, 0.0036926422460890037, -0.012195613404458027, -0.0011031738521428088, -0.008219315958802705, 0.003492840309064276, 0.015901984163380244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4158986410701592e-10, -2.8160915053321025e-10, -0.0004019622247804496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493099129635, 0.23605046525805473, 0.8414448279092318, 0.0, -0.12291510482198442, -0.2437709778967978, -2.608035990795053, -0.7114406115277784, -0.5581735692497372, -1.1995838798835885, -2.877218364229198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4146730376185007, 0.9716318981989475, 0.7594062208513683, -1.2139523496896159, -2.304484103164397, -0.28326203612539763, 1.916595816208237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751141298, -0.44034092454431645, 0.022932238233061203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.314195200306826e-08, 0.00031418967454627315, -0.0006038970485487139, 0.0, 0.0004083674514753187, 0.0002000711325302667, 6.0809506508185485e-05, 0.0005199271410681618, -3.123703957631058e-05, -0.000268418184694739, -0.0001733088989992726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002935249452052032, 0.0027000182566449277, -0.008850576860634755, -0.0008468374293380021, -0.006053911502375485, 0.0024540114599855816, 0.011639898139017498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6103848084768415e-09, -5.949203318875397e-10, -0.0003512154745262834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493104040848, 0.23606365717311636, 0.8413724547795586, 0.0, -0.12289772275178933, -0.2437611459551833, -2.6080335107422443, -0.711418514534015, -0.5581747862028298, -1.199595274141099, -2.8772257708797935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41456955499475034, 0.9717301605493174, 0.7590869279578832, -1.213984645147714, -2.3047052786869795, -0.2831748818362176, 1.9170190087748016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075219521, -0.4403409245856499, 0.022917307953974907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0" - }, - "execution_count": 33, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999943677873273, 0.036489651127809095, -0.34861191507695366, 0.0, -1.0029954720697876, 0.48869320376572917, -0.9525215184807941, -1.3886278121725906, -2.334452544500386, -0.4558788900739724, 0.11051798980155325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424639103, 0.01537723122151193, 1.7420423753144298, -2.031187242709937, -1.4888851823925482, -0.10085496898309822, 0.2189845498620707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529550045, -0.0006253905029041468, -0.0006249999999543101]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011264425345431811, -0.10782259036973244, 0.24007968118780842, 0.0, 0.03470669267139551, 0.02650595782943679, -0.0749999999999986, 0.07499999999999744, -0.06632406743743047, -0.02018751168584966, -0.07499999999999926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999737, 0.074999999999998, 0.07499999999999606, -0.012777139263307391, -0.04774843784840461, -2.521049782918791e-13, -0.04371418946734415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059100089, -0.012507810058082935, -0.012499999999997631]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998925805181444, 0.0267630596697571, -0.3278931585753566, 0.0, -1.0000224659428705, 0.49049653362158574, -0.9619301047404497, -1.379593523733744, -2.3410342122554755, -0.4572018850649818, 0.10116315485063393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8674174204432588, 0.025183583202972704, 1.751384115653074, -2.0317932410205013, -1.493464451596551, -0.10085496898310194, 0.21493079853658995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024960475280989564, -0.0025039454747618935, -0.0018977869579240155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00010219471025693422, -0.1945318291610399, 0.4143751300319408, 0.0, 0.05946012253834131, 0.03606659711713095, -0.1881717251931117, 0.18068576877693243, -0.13163335510178822, -0.026459899820186556, -0.18709669901838655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.17671844041302845, 0.19612703962921552, 0.18683480677288364, -0.012119966211281892, -0.09158538408005376, -7.442134995683418e-14, -0.0810750265096152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742876550287904, -0.037571099437154934, -0.025455739159394107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998493688783553, 0.014583839048681577, -0.30283958239639125, 0.0, -0.9965298716413223, 0.4921355227464133, -0.9760200982822472, -1.36680060810211, -2.349875174327609, -0.45803239691922115, 0.08685564365031923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8549868214394558, 0.03999234575967991, 1.7648047375765166, -2.0314752473307713, -1.4992752177285162, -0.10085496898347529, 0.20999822574163152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005922552841754735, -0.005952405107086799, -0.003193360879578438]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.642327957848494e-05, -0.2435844124215104, 0.5010715235793077, 0.0, 0.06985188603096355, 0.03277978249655097, -0.2817998708359508, 0.25585831263267966, -0.17681924144267328, -0.016610237084787073, -0.2861502240062941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24861198007606106, 0.2961752511341441, 0.26841243846885016, 0.006359873794598259, -0.11621532263930487, -7.467089435582319e-12, -0.09865145589916838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853010627311555, -0.06896919264649809, -0.025911478433088442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999809068351237, 0.0014335378704646243, -0.2761944917194697, 0.0, -0.9929074957979815, 0.49347927487126664, -0.9934337460668297, -1.3521735729677822, -2.3599662038298526, -0.457824273575296, 0.06884865106772532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8406534822932354, 0.058139594719090186, 1.7805125395519898, -2.029647170337682, -1.505313962569741, -0.10102857327294908, 0.20517189543805536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010643678979208298, -0.010710374037979753, -0.0038867220396985465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.06010542364428e-05, -0.26300602356433905, 0.5329018135384308, 0.0, 0.07244751686681615, 0.02687504249706601, -0.34827295569164807, 0.29254070268655696, -0.2018205900448637, 0.004162466878503277, -0.3601398516518781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2866667829244086, 0.3629449791882055, 0.31415603950946397, 0.0365615398617862, -0.12077489682449417, -0.0034720857894756426, -0.09652660607152291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09442252274907126, -0.09515937861785909, -0.013867223202402175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997690652879782, -0.011702002331867939, -0.24928874587665734, 0.0, -0.989246276057703, 0.49468681123771097, -1.0130856680342577, -1.3371594841759553, -2.370582763613108, -0.45628347991271506, 0.04830253205125776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8255901082630048, 0.07823517963514391, 1.7972253898468225, -2.026066250201851, -1.510779505665099, -0.10158468126685208, 0.20121590048948146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01641292307501113, -0.01652437680067441, -0.0038640671749981628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.000612651748077e-05, -0.26271080404665126, 0.5381149168562469, 0.0, 0.0732243948055711, 0.024150727328886127, -0.39303843934856075, 0.3002817758365387, -0.21233119566511, 0.030815873251618307, -0.41092238032935124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30126748060461117, 0.40191169832107443, 0.3342570058966499, 0.07161840271662138, -0.10931086190716179, -0.01112215987806014, -0.07911989897147827, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11538488191605661, -0.1162800552538931, 0.00045309729400767884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997283474068714, -0.02422006317593057, -0.22265032601038354, 0.0, -0.9854888087372059, 0.4959988791581555, -1.0342328168154162, -1.3226446897264197, -2.381293431749223, -0.45328812762035114, 0.026100264362257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8104723735088248, 0.09932762778084879, 1.8141873846479377, -2.020712517349157, -1.5151246688409317, -0.10266626822918933, 0.1986374242225254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023024727213398023, -0.023179169679737342, -0.003240362997743023]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.143576221380755e-05, -0.2503612168812526, 0.532768397325476, 0.0, 0.07514934640994225, 0.026241358408890046, -0.42294297562316907, 0.2902958889907117, -0.21421336272229458, 0.05990704584727803, -0.4440453537800151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3023546950835998, 0.42184896291409757, 0.3392398960223039, 0.10707465705388071, -0.08690326351665349, -0.021631739246744976, -0.05156952533912154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13223608276773788, -0.13309585758125864, 0.0124740835451028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996865980793582, -0.03577252767613231, -0.19642956701394904, 0.0, -0.9815406337022685, 0.4976208882400833, -1.056396033113364, -1.3090816174212576, -2.3918853969091396, -0.4488199833015818, 0.0028533308283817463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7956428661300832, 0.12084202839815208, 1.831009251468635, -2.013679421858163, -1.5180326510469635, -0.10435473103804188, 0.19771778927297087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030315445650636933, -0.03050174984173772, -0.002180320475781348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.349865502641323e-05, -0.2310492900040347, 0.5244151799286898, 0.0, 0.07896350069874844, 0.032440181638556685, -0.44326432595895465, 0.271261446103241, -0.21183930319833585, 0.08936288637538736, -0.4649386706775051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.29659014757483493, 0.43028801234606573, 0.3364373364139436, 0.14066190981987875, -0.058159644120635956, -0.03376925617705119, -0.018392698991090466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1458143687447782, -0.14645160324000756, 0.02120085043923349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996442330373115, -0.04616995896947086, -0.17062210968011732, 0.0, -0.9773194217804638, 0.49955824438821456, -1.07920000541233, -1.2966864109287906, -2.402273896109887, -0.44290888219037877, -0.021025607826192387, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7812463341514053, 0.1424741886154075, 1.8475146134884695, -2.0051054194168927, -1.519369528373308, -0.10669360940779955, 0.1985627728675731, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03815425881537758, -0.03835359792954218, -0.0008307438256598999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.473008409361587e-05, -0.20794862586677107, 0.5161491466766346, 0.0, 0.08442423843609374, 0.03874712296262459, -0.45607944597932065, 0.24790412984934107, -0.20776998401494684, 0.11822202222406095, -0.47757877309148267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2879306395735574, 0.4326432043451085, 0.3301072403966928, 0.17148004882540202, -0.02673754652688798, -0.04677756739515352, 0.016899671892044166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1567762632948129, -0.15703696175608922, 0.026991533002428958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996040725524014, -0.055314282637708795, -0.14516865212623695, 0.0, -0.9727456966265481, 0.5009982242991801, -1.1019427606501693, -1.2858660976682268, -2.412379732756123, -0.4355618582535085, -0.04519470760038505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.767324519208989, 0.1640966399781355, 1.8636348863947714, -1.9951358832689376, -1.5191345486479253, -0.10970712890896582, 0.20115281807469315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04643623664364146, -0.046624149490955655, 0.0006903032687336236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.0320969820218e-05, -0.1828864733647586, 0.5090691510776074, 0.0, 0.0914745030783143, 0.028799598219310777, -0.4548551047567852, 0.216406265211273, -0.202116732924724, 0.14694047873740462, -0.48338199548385324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2784362988483254, 0.43244902725455975, 0.3224054581260395, 0.19939072295909918, 0.004699594507654364, -0.060270390023325224, 0.05180090414240096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656395565652775, -0.1654110312282694, 0.03042094188787047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995656080170937, -0.06315356264304221, -0.1199941524971841, 0.0, -0.9677747180971222, 0.5012873611605031, -1.1241369183257128, -1.2768487140584996, -2.422146155899913, -0.42689116470085037, -0.06940616153652623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753877220547299, 0.18568829153512362, 1.8793483881907975, -1.983904792192392, -1.517416586876193, -0.11341034879709012, 0.20538601171981455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.055076911032641694, -0.05522545682713539, 0.002283205327204916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.692907061534153e-05, -0.15678560010666837, 0.5034899925810568, 0.0, 0.09941957058851723, 0.005782737226461488, -0.44388315351087204, 0.18034767219454395, -0.19532846287580571, 0.1734138710531634, -0.4842290787228237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26894597323380076, 0.43183303113976196, 0.3142700359205242, 0.22462182153091065, 0.03435923543464532, -0.07406439776248616, 0.08466387290242797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17281348778000474, -0.17202614672359462, 0.03185804116942584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995281641503582, -0.06966866451748287, -0.09502117513016206, 0.0, -0.9624003387814247, 0.500116271030617, -1.1455779972015496, -1.269654870766623, -2.431548357049536, -0.4170777138025503, -0.09350309815341745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7408879145352454, 0.2072870992331846, 1.8946485238828072, -1.9715281295513343, -1.5143590200051038, -0.11781302443341707, 0.21111215767328254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06400807277254862, -0.0640877832741035, 0.003868547243061622]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.488773347092766e-05, -0.13030203748881303, 0.4994595473404408, 0.0, 0.10748758631395008, -0.023421802597722835, -0.42882157751673766, 0.14387686583753134, -0.1880440229924549, 0.1962690179660015, -0.4819387323378244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2597861202410735, 0.43197615396121986, 0.3060027138401966, 0.24753325282115302, 0.06115133742178465, -0.08805351272653884, 0.11452291906935952, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17862323479813863, -0.17724652893936235, 0.03170683831713413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994913107957552, -0.07486978452803561, -0.07017347678394761, 0.0, -0.9566474214950237, 0.4974535442189808, -1.1662723818940892, -1.2641571779351852, -2.4405939888037196, -0.406312552106569, -0.11740332790066152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7283317732074577, 0.22895947583181858, 1.9095291082817134, -1.9581026453043, -1.5101332014272366, -0.12292019476310419, 0.21815816901528123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07317453423226578, -0.07315595397288652, 0.005390281978841689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.370670920623152e-05, -0.1040224002110549, 0.4969539669242888, 0.0, 0.11505834572802173, -0.0532545362327229, -0.4138876938507903, 0.10995385662875751, -0.1809126350836694, 0.2153032339196265, -0.4780045949448813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25112282655575346, 0.43344753197267905, 0.29761168797812365, 0.2685096849406872, 0.08451637155734373, -0.10214340659374235, 0.1409202268399741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18332922919434316, -0.18136341397566022, 0.030434694715601344]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999454778588323, -0.0787932511944504, -0.04537638636620607, 0.0, -0.9505610930258132, 0.4934320662590068, -1.186347623731432, -1.2601449452411397, -2.4493170870303422, -0.394757933766431, -0.1410787049015602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7161772892543037, 0.2507809650795023, 1.9239788941423313, -1.9437069608164215, -1.504919569294214, -0.1287315809038877, 0.22634589764778879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08253162230411247, -0.0823863518059898, 0.006815783357143117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.306441486449107e-05, -0.07846933332829581, 0.49594180835483076, 0.0, 0.12172656938421006, -0.08042955919948017, -0.401504836746858, 0.08024465388091005, -0.1744619645324521, 0.23109236680276088, -0.4735075400179733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24308967906307802, 0.4364297849536748, 0.28899571721235584, 0.2879136897575728, 0.10427264266044811, -0.11622772281567015, 0.1637545726501511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18714176143693387, -0.1846079566620657, 0.028510027566028558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999418401004553, -0.08149615548172884, -0.020556340685526725, 0.0, -0.9441966043754932, 0.4882542696256191, -1.205982998975845, -1.2573734263664906, -2.457768988172567, -0.3825317687870865, -0.16453548044579352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7043869252787127, 0.27282430441754935, 1.9379806416962566, -1.9284037276933006, -1.4988950104392036, -0.13524091820649173, 0.2355038109280024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09204320725190959, -0.09174447697766148, 0.008132419216196427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.275516754014441e-05, -0.054058085745568765, 0.49640091361358685, 0.0, 0.12728977300639832, -0.10355593266775534, -0.39270750488825773, 0.05543037749298321, -0.16903802284449532, 0.24452329958688943, -0.4691355108846665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23580727951181774, 0.44086678676094054, 0.28003495107850934, 0.30606466246241537, 0.12049117710021234, -0.13018674605208075, 0.18315826560427226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19023169895594233, -0.1871625034334337, 0.026332717181066216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993820843096527, -0.08304951929192882, 0.004359732278485691, 0.0, -0.9376112471486444, 0.48212994460053066, -1.2253658774053524, -1.2555963712456997, -2.466009239976215, -0.36970820743538035, -0.18779826770983304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6929184906149766, 0.2951523694979101, 1.9515121768008965, -1.9122422732104816, -1.4922250618411221, -0.14243568346670238, 0.24547391998940069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10168012295086909, -0.10120299526375542, 0.009342140285319461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.263338980055095e-05, -0.031067276203999572, 0.4983214592802483, 0.0, 0.13170714453697593, -0.12248650050176803, -0.3876575685901491, 0.035541102415818024, -0.16480503607295707, 0.256471227034123, -0.4652557452807905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22936869327472115, 0.4465613016072156, 0.27063070209279794, 0.32322908965637986, 0.13339897196162795, -0.1438953052042129, 0.19940218122796569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19273831397919, -0.18917036572187879, 0.024194421382460668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999345787218696, -0.08353142067439112, 0.029445008079205522, 0.0, -0.9308586256850422, 0.47524219487126584, -1.244668886932497, -1.2545853835584841, -2.4740982777286065, -0.35632634252206563, -0.21089833098617597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6817271814852262, 0.31781441248440706, 1.9645481115374919, -1.8952614045937972, -1.4850596725245517, -0.15029731022491274, 0.2561152164303628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1114188792209438, -0.11074019912926589, 0.010455772812928171]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.259418191355444e-05, -0.009638027649246223, 0.5017055160143966, 0.0, 0.1350524292720445, -0.13775499458529636, -0.38606019054289176, 0.0202197537443123, -0.16178075504782638, 0.2676372982662945, -0.4620012655268586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22382618259500872, 0.4532408597299385, 0.26071869473190895, 0.33961737233368844, 0.14330778633140898, -0.1572325351642074, 0.2128259288192421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1947751254014942, -0.1907440773102094, 0.02227265055217421]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999310607111454, -0.08302938996233994, 0.05477321513919481, 0.0, -0.923991414112252, 0.46773330417573744, -1.2640402128919723, -1.2541392907820497, -2.482092733130743, -0.34240177658041, -0.23386587648540366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.670773099558801, 0.3407370161374479, 1.9768575873766403, -1.877623985725392, -1.4775504600158724, -0.1588547607254304, 0.2672813611253824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12124067996820441, -0.12033872601129876, 0.011496409058730188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.036021448414886e-05, 0.010040614241023614, 0.5065641411997858, 0.0, 0.13734423145580163, -0.1501778139105684, -0.38742651918950577, 0.00892185552869019, -0.15988910804273, 0.2784913188331126, -0.459350909984554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21908163852850127, 0.4584520730608169, 0.24618951678296816, 0.3527483773681055, 0.1501842501735842, -0.17114901001035326, 0.2233228939003923, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19643601494521215, -0.19197053764065736, 0.020812724916040352]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992804213393903, -0.08165764022566474, 0.08041948891832457, 0.0, -0.9170770735508773, 0.45970313497894394, -1.283601065526524, -1.254086813416885, -2.490043326135137, -0.3279381466345287, -0.2567255882798957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6600365308914813, 0.3634496468522489, 1.9875244374976193, -1.859987029478487, -1.4699013151136944, -0.1682919919079088, 0.2787573864212014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13113083499134293, -0.12998432922857048, 0.012517509370653924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0371544126995355e-05, 0.027434994733504064, 0.512925475582595, 0.0, 0.13828681122749548, -0.16060338393586998, -0.3912170526910351, 0.0010495473032916588, -0.15901186008788104, 0.28927259891762647, -0.4571942358898413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21473137334639292, 0.45425261429602043, 0.21333700241957979, 0.35273912493810033, 0.15298289804356144, -0.1887446236495683, 0.2295205059163795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1978031004627706, -0.19291206434543448, 0.020422006238474722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992545743305098, -0.0795159245272511, 0.10646074018709453, 0.0, -0.9101708458552307, 0.45121181250340664, -1.3034525260914236, -1.254290785018126, -2.4979930325894326, -0.31293292071170853, -0.2794942992600252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6494984100499197, 0.38552614818554565, 1.995875388686491, -1.842962512642937, -1.4623139445105957, -0.1786552829958554, 0.2903352443415077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14107795986408048, -0.13966523005111176, 0.013562634334371814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.169401776087522e-05, 0.04283431396827265, 0.5208250253753994, 0.0, 0.13812455391293332, -0.16982644951074582, -0.39702921129799257, -0.004079432024817522, -0.15899412908591287, 0.30010451845640373, -0.45537421960259006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2107624168312294, 0.44153002666593455, 0.16701902377743577, 0.340490336711002, 0.15174741206197195, -0.20726582175893182, 0.23155715840612628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19894249745475076, -0.19361801645082535, 0.02090249927435781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992322813680996, -0.07670867382958221, 0.1329763188290542, 0.0, -0.9032348264408785, 0.44214690901905485, -1.323493252842749, -1.254855348925615, -2.5059698634130587, -0.2980366560047832, -0.3021668847623032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.639108140516877, 0.40669613074814553, 2.001651537455167, -1.8269615651281002, -1.4549582247240107, -0.18982475365300422, 0.30184944505258826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15107350323247298, -0.14937142693135094, 0.014685286317639549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4585924820379004e-05, 0.05614501395337779, 0.5303115728391934, 0.0, 0.13872038828704258, -0.18129806968703563, -0.40081453502650954, -0.0112912781497776, -0.15953661647252596, 0.2979252941385066, -0.45345171004555895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20780539066085135, 0.42339965125199724, 0.11552297537352055, 0.32001895029673716, 0.1471143957317011, -0.22338941314297658, 0.23028401422161135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991086736785002, -0.19412393760478375, 0.02245303966535469]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992130626790985, -0.07340491572848924, 0.15994061314862004, 0.0, -0.8962724789649682, 0.4324964947242017, -1.3438263294093244, -1.2556221171898703, -2.514013184406461, -0.2835484250369043, -0.3247341376957751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6288354085764698, 0.42682450613392386, 2.0049347917272113, -1.8121833806064307, -1.4479642065666531, -0.20157012497956966, 0.31318554591657793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16111059208723302, -0.15909494212136988, 0.01586729616881353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8437378001899175e-05, 0.06607516202185941, 0.5392858863913167, 0.0, 0.13924694951820532, -0.19300828589706293, -0.4066615313315085, -0.015335365285106062, -0.1608664198680467, 0.28976461935757797, -0.4513450586694377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20545463880814627, 0.40256750771556626, 0.06566508544089172, 0.2955636904333909, 0.1398803631471516, -0.23490742653130897, 0.22672201727979394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007417770952007, -0.19447030380037839, 0.023640197023479626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991966840970793, -0.06977970537894607, 0.18726994136662176, 0.0, -0.8892701283554084, 0.42224521192470754, -1.3645891160146304, -1.256394921929232, -2.5221558967836404, -0.2696095747926342, -0.3471787210740257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6186465895692452, 0.4458749683982276, 2.0060105202825427, -1.7986622006434627, -1.4414223202292344, -0.21361339867696572, 0.32427683434982835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1711835067910226, -0.1688296131239169, 0.017074813798622437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.275716403852687e-05, 0.07250420699086339, 0.5465865643600344, 0.0, 0.14004701219119592, -0.20502565598988312, -0.4152557321061212, -0.015456094787236955, -0.16285424754359026, 0.27877700488540236, -0.44889166756501203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20377638014449317, 0.3810092452860746, 0.021514571106627384, 0.2704235992593596, 0.13083772674837285, -0.240865473947921, 0.22182576866500847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2014582940757915, -0.19469342005094056, 0.024150352596178155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991829704491304, -0.06595164889716351, 0.21486738391251042, 0.0, -0.8821869876742153, 0.4113580694793555, -1.3858915903241376, -1.2570265264617904, -2.5304170095375724, -0.25627574742973624, -0.36947639220324785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6085015888525278, 0.46387136236181853, 2.005249868742743, -1.7863216674809272, -1.4353896885281745, -0.22567821158055126, 0.3350945463214575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18128738829199612, -0.17857079626743272, 0.01827446757476247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.742729589774109e-05, 0.07656112963565102, 0.5519488509177736, 0.0, 0.14166281362386218, -0.21774284890704082, -0.4260494861901423, -0.012632090651166567, -0.165222255078642, 0.26667654725795925, -0.44595342258444315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.202900014334348, 0.3599278792718181, -0.015213030795990373, 0.24681066325070852, 0.12065263402119997, -0.24129625807171087, 0.21635423943258303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20207763001947027, -0.19482366287031647, 0.02399307552280062]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999171936687081, -0.06200489325961712, 0.24262760650810797, 0.0, -0.8749077381951124, 0.3997031550632148, -1.4076775335683605, -1.25758594128843, -2.5387972096710043, -0.24417857712991742, -0.391590489618162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.598342974240442, 0.48087099638066244, 2.003027721377976, -1.7750238484235246, -1.4298975236623708, -0.2375200347171883, 0.34563704259039363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19141825256944675, -0.1883148717070868, 0.019458676694438536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2067524098460056e-05, 0.07893511275092788, 0.555204451911951, 0.0, 0.1455849895820586, -0.23309828832281398, -0.43571886488445577, -0.011188296532793842, -0.16760400266863723, 0.24194340599637676, -0.4422819482982835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20317229224171607, 0.33999268037687863, -0.044442947295344856, 0.22595638114805344, 0.10984329731607509, -0.23683646273274064, 0.2108499253787216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20261728554901254, -0.19488150879308166, 0.023684182393521297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991632893154915, -0.057955381131714064, 0.27043383512585756, 0.0, -0.867367996397315, 0.3872512299726996, -1.429980287645491, -1.2580481042981049, -2.5472886953391627, -0.23334210046732623, -0.4134925815781258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.588134021490493, 0.49694044611680416, 1.9996814247534958, -1.7646048459974841, -1.4249597077185387, -0.24894317319441417, 0.3559190350014655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20157257289412323, -0.1980592924005522, 0.020596362724224826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7294743179113573e-05, 0.0809902425580611, 0.5561245723549918, 0.0, 0.1507948359559485, -0.24903850181030343, -0.4460550815426122, -0.009243260193495056, -0.16982971336316888, 0.21672953325182365, -0.43804183919927536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2041790549989801, 0.321388994722834, -0.06692593248960249, 0.20838004852081085, 0.09875631887663844, -0.2284627695445175, 0.2056398482214377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20308640649352938, -0.1948884138693078, 0.022753720595725828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991570323469426, -0.053798476309639034, 0.29815606018178514, 0.0, -0.8595176351390179, 0.37399993210151256, -1.4528474884205413, -1.2583752085214903, -2.5558745158296525, -0.22360631004274767, -0.43515990202702315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5778455511123288, 0.5121486757206983, 1.9954893594833063, -1.7549029483419794, -1.4205778231805546, -0.2598038304006368, 0.36596427551383576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21174720324770274, -0.20780235697116883, 0.0216640683540259]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2513937097453594e-05, 0.08313809644150058, 0.5544445011185514, 0.0, 0.1570072251659406, -0.2650259574237416, -0.4573440155010057, -0.006542084467708544, -0.17171640980979766, 0.19471580849157094, -0.4333464089779465, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2057694075632873, 0.30416459207788243, -0.08384130540378956, 0.19403795311009459, 0.08763769075968289, -0.2172131441244532, 0.2009048102474056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2034926070715904, -0.1948612914123327, 0.021354112596021484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991532140068302, -0.0495261124340122, 0.32565129367259676, 0.0, -0.8513100937361373, 0.3599504123409985, -1.4763174109024948, -1.2585407040120304, -2.564530809104911, -0.21478922970344114, -0.4565740300787786, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5674527919006813, 0.5265628008053821, 1.9906665842974844, -1.7457735158233119, -1.4167452974479746, -0.27000673079348886, 0.375800257381472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22193937709696854, -0.21754296453507113, 0.02265058158026335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.636680224744883e-06, 0.08544727751253674, 0.5499046698162328, 0.0, 0.16415082805761122, -0.28099039521028146, -0.4693984496390691, -0.0033099098108013477, -0.17312586550517142, 0.17634160678613053, -0.42828256103510925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20785518423294885, 0.288282501693675, -0.09645550371643657, 0.1825886503733485, 0.07665051465159964, -0.2040580078570406, 0.1967196373527248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20384347698531594, -0.19481215127804613, 0.019730264524749012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991519586375045, -0.04514634070765176, 0.3514006435865091, 0.0, -0.8426592115557481, 0.3450548782274425, -1.5003302905499343, -1.2586417207195475, -2.5732270149977454, -0.2073179997627597, -0.4777153494071629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569252279431307, 0.5402475213617974, 1.9853689104517105, -1.737095556272282, -1.41345007180058, -0.279497516553597, 0.3854550071751034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23214684001108826, -0.2272802767874083, 0.023568252139719102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.510738651493572e-06, 0.08759543452720886, 0.5149869982782466, 0.0, 0.1730176436077857, -0.2979106822711192, -0.4802575929487916, -0.002020334150341435, -0.17392411785668363, 0.1494245988136289, -0.42282638656768645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.210551279151014, 0.27369441112830695, -0.10595347691547766, 0.17355919102059403, 0.06590451294789099, -0.18981571520216345, 0.1930949958726276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2041492582823945, -0.19474624504674332, 0.018353411189115012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991531433682683, -0.040652203443944004, 0.3734640331474745, 0.0, -0.8335255223283966, 0.32932626206854554, -1.5248929540006286, -1.2586880015078965, -2.581930858881691, -0.20105999855085718, -0.498573411877532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5462492593169215, 0.5532608933159537, 1.9797051056484585, -1.7287711810021689, -1.4106774840942202, -0.28825605805658827, 0.3949547180241143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24236763948430182, -0.23701378075307267, 0.02441571502677804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.369461527810091e-06, 0.08988274527415509, 0.4412677912193081, 0.0, 0.18267378454702882, -0.3145723231779398, -0.4912532690138861, -0.0009256157669812709, -0.1740768776789138, 0.12516002423805006, -0.4171612494073814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2135193725241847, 0.26026743908312594, -0.11327609606504076, 0.16648750540226392, 0.055451754127197606, -0.17517083005982564, 0.18999421698021818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20441598946427111, -0.19467007931328703, 0.016949257741178766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991568038104338, -0.03604378387140768, 0.39102189623055855, 0.0, -0.8238822059508757, 0.3127923029678555, -1.5500276807358593, -1.2586642221456124, -2.5906074666517895, -0.19576593852907737, -0.5191436384328104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5354166890823266, 0.5656565402075744, 1.9737468833513334, -1.7207250504230756, -1.4084109998532808, -0.29628753156221943, 0.4043231753796419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25260010035560265, -0.24674318402336615, 0.02519559589684357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.320884331225334e-06, 0.09216839145072646, 0.35115726166168076, 0.0, 0.1928663275504183, -0.33067918201380153, -0.502694534704615, 0.0004755872456812329, -0.17353215540196934, 0.10588120043559658, -0.4114045311055688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21665140469189534, 0.2479129378324135, -0.11916444594250003, 0.16092261158186555, 0.045329684818788706, -0.1606294701126236, 0.1873691471105526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20464921742601713, -0.1945880654058694, 0.015597617401310607]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991629762965907, -0.0313301511200436, 0.4042356347770096, 0.0, -0.8137036635729823, 0.2954815505203647, -1.5757550714762791, -1.2585520824471372, -2.599220977602953, -0.19121333064802526, -0.539425331861611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5244213501439687, 0.5774842648355991, 1.9675384844805521, -1.7129005387961165, -1.4066329340866166, -0.30361497808066934, 0.41358166513866096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26284282183271745, -0.25646830713754026, 0.025915311458413366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2344972314041837e-05, 0.0942726550272815, 0.26427477092902024, 0.0, 0.2035708475578688, -0.3462150489498161, -0.5145478148083986, 0.0022427939695019595, -0.17227021902327067, 0.09105215762104218, -0.4056338685760125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21990677876715797, 0.2365544925604943, -0.12416797741562423, 0.15649023253918076, 0.03556131533328266, -0.14654893036899808, 0.18516979518038082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20485442954229588, -0.19450246228348259, 0.014394311231395939]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991716731154052, -0.026525558340783968, 0.41380240247527866, 0.0, -0.8029623156404427, 0.2774207428798835, -1.6020897913705852, -1.2583369909018103, -2.607736646785377, -0.1872381734880999, -0.5594203751179667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5132583434356306, 0.5887901948276059, 1.9611049586567002, -1.7052552910862158, -1.405324980846817, -0.3102732739851018, 0.42274918911505466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.273094660675004, -0.2661890497572536, 0.026584619763713735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.739363762884511e-05, 0.09609185558519262, 0.19133535396538198, 0.0, 0.21482695865079082, -0.36121615280962405, -0.5266943978861184, 0.0043018309065368885, -0.17031338364847823, 0.0795031431985073, -0.3999008651271129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2232601341667642, 0.22611859984013546, -0.12867051647703923, 0.15290495419801506, 0.026159064795992434, -0.13316591808864933, 0.1833504795278738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20503677684573077, -0.19441485239426728, 0.013386166106007354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991828863620853, -0.021645009132675964, 0.4205907108636889, 0.0, -0.791628159543138, 0.258635880996209, -1.6290408846014002, -1.2580090366093195, -2.6161224405769827, -0.18372994186970218, -0.5791323817827055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5019239113415281, 0.5996168454478135, 1.9544588074527132, -1.6977572570550705, -1.404468556059473, -0.31630444289788495, 0.4318428320375456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28335470022604436, -0.27590532282194086, 0.027213481376127325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.242649336002097e-05, 0.09761098416216009, 0.13576616776820377, 0.0, 0.22668312194609339, -0.3756972376734905, -0.5390218646163004, 0.006559085849813688, -0.16771587583211528, 0.07016463236795442, -0.39424013329477636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22668864188205057, 0.21653301240415293, -0.1329230240797412, 0.1499606806229051, 0.01712849574688053, -0.12062337825566287, 0.18187285844981813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2052007910208073, -0.19432546129374453, 0.01257723224827178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991965916541216, -0.016701056200382057, 0.4254225939679053, 0.0, -0.7796690759648334, 0.23915418238325292, -1.6566134421122871, -1.25756206611305, -2.624349893978199, -0.18061804771119994, -0.5985661845110753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904153737741563, 0.6100031613137556, 1.947604948074933, -1.6903814793287308, -1.404045026353251, -0.32175417684037083, 0.44087815263000113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29362221457316656, -0.285617048995376, 0.027810817361409907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7410584072310096e-05, 0.0988790586458781, 0.09663766208432883, 0.0, 0.23918167156609368, -0.3896339722591212, -0.5514511502177396, 0.008939409925390817, -0.16454906802433, 0.062237883170044736, -0.3886760545673955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23017075134743417, 0.20772631731884392, -0.1370771875556067, 0.1475155545267934, 0.008470594124443212, -0.10899467884971732, 0.18070641184911032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20535028694244367, -0.1942345234687028, 0.011946719705651644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992127501286358, -0.011702208613917686, 0.4289739422232274, 0.0, -0.7670512784878643, 0.21900591760066124, -1.684810411942989, -1.2569922982686135, -2.632394354661889, -0.17785914352096863, -0.617727581249097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787309925001368, 0.6199845755451108, 1.9405442054172986, -1.683107685070384, -1.4040358776467259, -0.3266693798282774, 0.44986952770788047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30389663225850994, -0.2953241545968568, 0.028383949432997407]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2316949028507026e-05, 0.09997695172928742, 0.0710269651064412, 0.0, 0.25235594953938256, -0.4029652956518339, -0.563939396614037, 0.011395356888729244, -0.1608892136737929, 0.0551780838046262, -0.3832279347604332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23368762548039063, 0.19962828462710325, -0.14121485315268698, 0.14547588516693374, 0.0001829741305017802, -0.09830405975813139, 0.17982750155758723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548835370686713, -0.1941421120296164, 0.01146264143174999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992313101318812, -0.006652692565644477, 0.4317498358492036, 0.0, -0.7537397487466786, 0.19822584140021687, -1.7136341431009776, -1.2562970072993924, -2.6402348296879428, -0.17542754335129496, -0.6366232662843543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4668697844299083, 0.6295930893252552, 1.933275611045951, -1.6759185806028578, -1.404422861464175, -0.33109652878027634, 0.458830413805529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31417750276953854, -0.30502657383305176, 0.02893846063414057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.712000649054735e-05, 0.10099032096546418, 0.05551787251952504, 0.0, 0.2662305948237139, -0.4156015240088871, -0.5764746231597715, 0.01390581938442012, -0.15680950052107492, 0.04863200339347323, -0.37791370070514646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2372241614045679, 0.19217027560288796, -0.1453718874269521, 0.14378208935052617, -0.00773967634898096, -0.08854297903997929, 0.1792177219529715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056174102205722, -0.1940483847238996, 0.011090224022863238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999252208256924, -0.0015530650799208427, 0.43409950235886813, 0.0, -0.7396986511357861, 0.17685419495564528, -1.7430875667126164, -1.255473436518051, -2.6478536261191183, -0.1733086480035227, -0.6552608821508061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4548313208956247, 0.638857379542875, 1.9257978066239203, -1.6687987189318956, -1.4051881357602882, -0.3350806539796887, 0.46777352030281205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32446446710359783, -0.3147242513390845, 0.02947827750528296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.179625008542345e-05, 0.10199254971447269, 0.04699333019329052, 0.0, 0.2808219522178488, -0.4274329288914317, -0.5890684722327764, 0.01647141562682765, -0.1523759286235147, 0.04237790695544556, -0.37275231732903635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24076927068567405, 0.1852858043523969, -0.14955608844061632, 0.14239723341924326, -0.015305485922267837, -0.07968250398824721, 0.17886212994566003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20573928668118585, -0.19395355012065485, 0.010796337422847802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992753700588597, 0.003598798511559146, 0.43624739217648045, 0.0, -0.724891741690841, 0.15493734916362287, -1.77317503344434, -1.2545179696671447, -2.65523591858819, -0.17149465918198545, -0.6736491402359694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4426155419967504, 0.6478029342278301, 1.9181098129680592, -1.6617337984280063, -1.4063144055645729, -0.33866476616335506, 0.4767109036375887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3347572324029258, -0.3244171475426142, 0.030005856709231834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6323603871767203e-05, 0.10303727182959976, 0.04295779635224643, 0.0, 0.2961381888989033, -0.43833691584044815, -0.6017493346344696, 0.01910933701812804, -0.1476458493814388, 0.036279776430745134, -0.36776516170326684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24431557797748968, 0.17891109369910227, -0.15375987311722422, 0.14129841007778507, -0.0225253960856932, -0.07168224367332676, 0.17874766669553313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20585530598655982, -0.19385792407059352, 0.010551584078977523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999300727479941, 0.008804094513933344, 0.43832674680155004, 0.0, -0.7092734812854777, 0.1325250230096199, -1.8038896617668416, -1.2534467156304505, -2.662369107290451, -0.170136386354041, -0.6917974923403458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4302206397529396, 0.656452392197265, 1.91021119496771, -1.654710318457212, -1.4077850093685291, -0.3418894014845274, 0.48565401651967277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34505557801701003, -0.3341052161568823, 0.03052500721608979]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.071484216269138e-05, 0.10410592004748395, 0.041587092501391226, 0.0, 0.3123652081072662, -0.4482465230800592, -0.6142925664500328, 0.02142508073388495, -0.14266377404522404, 0.02716545655888939, -0.3629670420875271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.247898044876214, 0.1729891593886999, -0.15797236000698112, 0.1404695994158832, -0.029412076079125125, -0.06449270642344677, 0.17886225764168148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596691228168415, -0.1937613722853621, 0.01038301013715913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993281607735924, 0.014069201764168223, 0.440554074676966, 0.0, -0.6928109809552064, 0.10967925831495132, -1.8352409943354022, -1.2522513346602826, -2.6692418402322686, -0.16918147937709843, -0.7097178193704274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4176478262465135, 0.6648252180781782, 1.9021025352490581, -1.6477151275537387, -1.4095841982762256, -0.3447930230988332, 0.4946136536266191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35535929515115294, -0.3437884526041532, 0.031034178355589064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.4866587303167144e-05, 0.10530214500469758, 0.044546557508319394, 0.0, 0.329250006605426, -0.4569152938933719, -0.627026651371214, 0.023907619403360444, -0.1374546588363505, 0.0190981395388514, -0.3584065406016334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2514562701285214, 0.1674565176182633, -0.16217319437304076, 0.13990381806946717, -0.035983778153928975, -0.05807243228611571, 0.17919274213892625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20607434268285799, -0.19366472894541778, 0.010183422789985429]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993575682648196, 0.019400616468993246, 0.44289768829019843, 0.0, -0.6754744605295335, 0.08646953830834081, -1.8672451722132992, -1.2509139006384626, -2.6758434597702183, -0.1685470814504019, -0.7274240181573949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4048984576701506, 0.6729382830732726, 1.8937852932352317, -1.640735717797071, -1.4116971315210167, -0.3474117904117522, 0.5035999569603018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3656681770246601, -0.3534668961450138, 0.031531318896992885]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.8814982454298406e-05, 0.10662829409650044, 0.04687227226464876, 0.0, 0.3467304085134582, -0.46419440013220997, -0.6400835575579383, 0.02674868043639765, -0.1320323907589963, 0.012687958533930593, -0.3541239757393488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2549873715272559, 0.16226129990188878, -0.16634484027652924, 0.1395881951333539, -0.04225866489582044, -0.05237534625838001, 0.17972606667365373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617763747014317, -0.1935688708172126, 0.009942810828076472]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993888393816484, 0.0248040893394555, 0.44529375356535134, 0.0, -0.657234770570855, 0.06297094490393922, -1.8999212050323753, -1.249412458692867, -2.682164551083141, -0.16816676905990524, -0.7449317767870256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3919731590322595, 0.6808061382983573, 1.8852615233704535, -1.6337601318767279, -1.4141099807966149, -0.3497796362304216, 0.5126224001403346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37598173324735323, -0.36314035844652015, 0.03201440817113183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.254223365770543e-05, 0.10806945740924509, 0.04792130550305777, 0.0, 0.3647937991735709, -0.4699718680880319, -0.6535206563815221, 0.03002883891191481, -0.12642182625846027, 0.007606247809932947, -0.35015517259261514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2585059727578234, 0.15735710450169496, -0.17047539729556585, 0.1395117184068595, -0.048256985511962884, -0.04735691637338743, 0.18044886360065446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20627112445386322, -0.19346924603012725, 0.00966178548277895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994218755304446, 0.03028111445937137, 0.4476983151298864, 0.0, -0.638051332776127, 0.03926257745153229, -1.9332743876008847, -1.2477508441344103, -2.688197452370262, -0.16810928445998144, -0.7622579496811501, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3788697670593844, 0.6884412863522363, 1.8765336079476393, -1.6267770578307548, -1.4168099483184164, -0.35192815298540625, 0.521689746529341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38629983835555937, -0.3728089685767702, 0.03248476983167084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.607229759236975e-05, 0.10954050239831736, 0.04809123129070107, 0.0, 0.3836687558945604, -0.4741673490481384, -0.6670636513701855, 0.03323229116913221, -0.12065802574241588, 0.001149691998475956, -0.3465234578824916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2620678394575032, 0.15270296107757883, -0.17455830845628348, 0.13966148091946143, -0.053999350436031546, -0.04297033509969325, 0.1813469277801277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063621021641231, -0.19337220260500151, 0.009407233210780217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994565462695438, 0.035833492498871876, 0.4500905981744083, 0.0, -0.6178842585120434, 0.015431057167064749, -1.9673061459951764, -1.2459416831053933, -2.6939362728567957, -0.16848615907127737, -0.7794214344100959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3655861790610817, 0.695854000809875, 1.8676041606193066, -1.6197754582617239, -1.4197854587358523, -0.35388704398114024, 0.5308099776510703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3966223687317779, -0.382472854002744, 0.03294257592190131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.934147819820369e-05, 0.11104756079001019, 0.04784566089043712, 0.0, 0.40334148528167124, -0.47663040568935083, -0.6806351678858344, 0.03618322058034058, -0.11477640973067882, -0.007537492225918648, -0.3432696945789163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26567175996605197, 0.1482542891527731, -0.1785889465666572, 0.14003199138061714, -0.05951020834871641, -0.03917781991467974, 0.18240462243458555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064506075243705, -0.1932777085194761, 0.009156121804609322]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994927114146885, 0.04146423281254037, 0.4524652423308594, 0.0, -0.5967002839762974, -0.008428315810264247, -2.002019540532723, -1.2439956941687156, -2.6993758339653144, -0.16940299491767172, -0.7964438610998594, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3521212162123777, 0.7030525069188116, 1.8584760797939717, -1.6127446918799009, -1.4230261952653138, -0.35568434019006, 0.539990275195647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4069491874556222, -0.3921321596665384, 0.0333861414163522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.233029028954226e-05, 0.1126148062733699, 0.04749288312902246, 0.0, 0.42367949071492217, -0.4771874595465799, -0.694267890750924, 0.038919778733553526, -0.10879122217037608, -0.018336716927886926, -0.3404485337952699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2692992569740784, 0.14397012217873117, -0.18256161650669792, 0.14061532763645895, -0.0648147305892294, -0.035945924178395046, 0.1836059508915353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20653637447688533, -0.19318611327588817, 0.008871309889017753]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995302292547737, 0.04717719163981723, 0.45482467173455715, 0.0, -0.5744743481247945, -0.03221191560342329, -2.0374207516577627, -1.2419173313528997, -2.704510349690118, -0.17094461988618306, -0.8133500607854194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.338474363592058, 0.710043323425046, 1.849152611281147, -1.6056747744240032, -1.4265230589240911, -0.3573465118464638, 0.5492370613052514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4172801236089696, -0.40178706148223914, 0.03381250417578785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.50356801704552e-05, 0.1142591765455371, 0.0471885880739552, 0.0, 0.4445187170300572, -0.47567199586318076, -0.7080242225007946, 0.041567256316315505, -0.10269031449607864, -0.030832499370226814, -0.3381239937112001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27293705240639565, 0.13981633012468742, -0.18646937025649496, 0.14139834911795557, -0.06993727317554597, -0.03324343312807645, 0.18493572219208787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2066187230669484, -0.1930980363140145, 0.008527255188713103]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995689562569696, 0.0529764013584553, 0.4571740315963459, 0.0, -0.5511892882837658, -0.05580878834381451, -2.0735186015691505, -1.2397038596385224, -2.70933229877117, -0.17317392474171134, -0.8301683189783522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3246456650861915, 0.716831383794669, 1.8396373038523934, -1.5985564082349324, -1.4302681534635762, -0.3588985346995499, 0.558555999158406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42761497664776876, -0.4114377704488579, 0.03421828106622663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.745400439178555e-05, 0.1159841943727615, 0.046987197235774894, 0.0, 0.4657011968205729, -0.4719374548078243, -0.7219569982277539, 0.04426943428754573, -0.09643898162103368, -0.044586097110565416, -0.33636516385865606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2765739701173271, 0.1357612073924629, -0.19030614857507142, 0.1423673237814152, -0.07490189078970134, -0.03104045706172176, 0.18637875706309256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20669706077598285, -0.1930141793323752, 0.008115537808775676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996089890845417, 0.05888883692989693, 0.4595184800629568, 0.0, -0.526901883015525, -0.07893182781676603, -2.110092321432455, -1.2373198520905968, -2.7134998146319544, -0.17613304333447521, -0.8465907922731724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.310653127481421, 0.7234196128227636, 1.8299352386537378, -1.5913806634700793, -1.4342550396317781, -0.36036587707562534, 0.5679520932180644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4379532912986751, -0.421084771078369, 0.03457703990224904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.006565514422405e-05, 0.11824871142883255, 0.046888969332218, 0.0, 0.485748105364817, -0.4624607894590302, -0.7314743972660956, 0.047680150958511774, -0.08335031721568739, -0.05918237185527777, -0.32844946589640434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27985075209540916, 0.13176458056189136, -0.19404130397311342, 0.14351489529706157, -0.07973772336403934, -0.029346847521508145, 0.18792188119316772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20676629301812666, -0.1929400125902228, 0.007175176720448172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999650598841945, 0.06497439219545284, 0.4618620525147836, 0.0, -0.5017975861345425, -0.10103100307083646, -2.1465184654326808, -1.234674623861658, -2.7161027121378716, -0.17985000619381897, -0.8617340947443358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2965438552155464, 0.7298096042905275, 1.8200545056691093, -1.5841400898195637, -1.4384785532693973, -0.36177571462075087, 0.5774299590274339, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4482940391134155, -0.43072916432052577, 0.034829289387686035]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.3219514806687e-05, 0.12171110531111831, 0.046871449036536506, 0.0, 0.5020859376196491, -0.4419835050814085, -0.7285228800045104, 0.05290456457877694, -0.052057950118340725, -0.07433925718687479, -0.30286604942326895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28218544531749395, 0.1277998293552787, -0.1976146596925673, 0.14481147301031166, -0.0844702727523845, -0.028196750902510892, 0.18955731618739077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2068149562948069, -0.19288786484313503, 0.0050449897087399016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996936354723793, 0.07126622309335441, 0.4642074181845505, 0.0, -0.4760551418039262, -0.12167984801784872, -2.1822476332991476, -1.2316783456747256, -2.716361757472941, -0.18434645519981743, -0.8748556332219445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.282349992373356, 0.7360038559743707, 1.8100036805633035, -1.5768306365002767, -1.4429338617451328, -0.36315222153362153, 0.5869939497017014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4586358746761437, -0.44037239127138705, 0.0349420811878866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.607326086861515e-05, 0.12583661795803136, 0.046907313395338227, 0.0, 0.5148488866123256, -0.4129768989402451, -0.7145833573293369, 0.05992556373864878, -0.005180906701383242, -0.08992898011996939, -0.26243076955217426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28387725684381143, 0.12388503367686289, -0.20101650211611713, 0.14618906638573945, -0.08910616951470839, -0.027530138257413045, 0.1912798134853488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683671125456485, -0.19286453901722592, 0.0022558360040113136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997379143001764, 0.07776899639084262, 0.46655600538470354, 0.0, -0.4498147428041323, -0.1406513385680828, -2.2169279753438587, -1.228267958933324, -2.7138063538676853, -0.18962681856315414, -0.8855349017778712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2680810973387941, 0.7420045623063706, 1.7997893976568422, -1.5694488605442787, -1.4476169525708655, -0.36451601216623863, 0.5966479672555021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46897740788126946, -0.4500159440950995, 0.03491072156614704]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.855765559401911e-05, 0.13005546594976414, 0.046971744003060124, 0.0, 0.5248079799958779, -0.3794298110046814, -0.6936068408942236, 0.0682077348280285, 0.05110807210511245, -0.1056072672667343, -0.21358537111853512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2853779006912345, 0.12001412663999692, -0.20428565812922733, 0.1476355191199587, -0.09366181651465605, -0.02727581265234201, 0.19308035107601457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683066410251555, -0.1928710564742491, -0.00062719243479135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997859488869993, 0.08449411927742755, 0.46890829058041245, 0.0, -0.423228987139392, -0.15802175540469443, -2.249987385598714, -1.2241457216270608, -2.7084187345750443, -0.1957180323196668, -0.893782711064083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.253748187745712, 0.7478123549353348, 1.7894169406863398, -1.5619896511407834, -1.4525252844554515, -0.36588689044702444, 0.6063954373352898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4793171384805335, -0.4596614333567058, 0.03472380389854716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.606917364578337e-05, 0.1345024577316986, 0.047045703914178304, 0.0, 0.5317151132948059, -0.3474083367322327, -0.6611882050971059, 0.08244474612526588, 0.10775238585281527, -0.12182427513025361, -0.1649561857242356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.286658191861644, 0.11615585257928451, -0.20744913941004678, 0.14918418806990458, -0.09816663769171755, -0.027417565615715768, 0.19494940159575466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2067946119852808, -0.19290978523212576, -0.0037383533519975355]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998346517918872, 0.09141406724463508, 0.4712641065329575, 0.0, -0.3963772718905486, -0.17371562945071847, -2.2814760175244753, -1.219360925440738, -2.7002327508410016, -0.20256769550311668, -0.8997134077907735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.239329617790521, 0.7534266524824335, 1.7788887401772873, -1.5544474328996274, -1.4576573351045903, -0.3672799495537857, 0.6162389829320788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48965387642560615, -0.4693104482638417, 0.03440900117209651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.740580977579372e-05, 0.13839895934415067, 0.047116319050902106, 0.0, 0.5370343049768674, -0.31387748092048084, -0.629772638515227, 0.0956959237264568, 0.16371967468085852, -0.13699326366899722, -0.11861393453380784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28837139910381737, 0.11228595094197273, -0.21056401018104937, 0.15084436482312133, -0.1026410129827759, -0.027861182135225065, 0.19687091193577935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20673475890145315, -0.19298029814271903, -0.006296054529012879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998837262983027, 0.0984876371474542, 0.4736228512128817, 0.0, -0.36931688053387773, -0.18773598357623295, -2.3116213955634004, -1.2140251347964188, -2.6893801310269607, -0.21009366952295444, -0.903551021511901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2247864723311725, 0.7588446208607488, 1.7682046484249256, -1.5468142979099502, -1.463013101024749, -0.3687074540384244, 0.6261802995106079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49998676525617464, -0.47896382469304655, 0.03400803337286887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.814901283098824e-05, 0.14147139805638256, 0.04717489359848419, 0.0, 0.5412078271334178, -0.2804070825102892, -0.6029075607785047, 0.1067158128863861, 0.21705239628081968, -0.15051948039675508, -0.07675227442255034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2908629091869693, 0.10835936756630725, -0.21368183504723234, 0.1526626997935423, -0.1071153184031709, -0.028550089692774814, 0.1988263315705836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20665777661136933, -0.19306752858409676, -0.008019355984552914]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999333034850686, 0.105673669795564, 0.4759836606629676, 0.0, -0.3420989319308359, -0.2001784404608327, -2.3406676079286513, -1.2082366255708006, -2.676068847338364, -0.2181991233110978, -0.9055950446480462, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.210074347685301, 0.7640609965663732, 1.7573630303574068, -1.53907990480734, -1.4685941695923914, -0.3701801278166298, 0.636220089338161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5103153663581976, -0.4886219727508629, 0.03356302377694085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.915437353183409e-05, 0.14372065296219605, 0.047216189001717875, 0.0, 0.5443589720608369, -0.2488491376919947, -0.5809242473050138, 0.11577018451236276, 0.2662256737719409, -0.16210907576286726, -0.04088046272290302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2942424929174305, 0.10432751411248795, -0.2168323613503749, 0.1546878620522016, -0.11162137135285063, -0.02945347556410772, 0.2007957965510602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20657202204046005, -0.19316296115632664, -0.00890019191856041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999985724046607, 0.11296025548712392, 0.47834557029358193, 0.0, -0.314801405808413, -0.21118625359244553, -2.3685314160903346, -1.2018226217381398, -2.660668603774185, -0.2268306392523497, -0.906272283081831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.195169438262761, 0.7690689721673792, 1.746363206779349, -1.531232376173149, -1.474403504951756, -0.3717100360535933, 0.6463583943527268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5206393882958547, -0.49828517094116875, 0.03308743223331075]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010484112307689969, 0.1457317138311984, 0.04723819261228707, 0.0, 0.5459505224484582, -0.22015626263225668, -0.5572761632336668, 0.12828007665321645, 0.3080048712835719, -0.17263031882503777, -0.013544768675696726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.298098188450805, 0.10015951202012112, -0.21999647156115473, 0.15695057268381932, -0.11618670718729492, -0.030598164739270173, 0.20276610029131695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20648043875314065, -0.19326396380611774, -0.00951183087260194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000386188984348, 0.1203205677287292, 0.48070759131574803, 0.0, -0.287474989770132, -0.22085635045821775, -2.3954222793204267, -1.1948892232481507, -2.643436904418872, -0.23587381765469737, -0.9059314193362062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.180038166023946, 0.7738608510681475, 1.7352056038860497, -1.5232611904860027, -1.4804446693925655, -0.3733069528951633, 0.6565944608268954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5309588079582727, -0.5079534101611066, 0.032609806416965675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010578970365539403, 0.14720624483210576, 0.04724042044332186, 0.0, 0.5465283207656204, -0.19340193731544422, -0.5378172646018428, 0.1386679697997807, 0.34463398710626403, -0.18086356804695347, 0.006817274912495987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30262544477629516, 0.09583757801536633, -0.22315205786598608, 0.15942371374292477, -0.12082328881618842, -0.031938336831399336, 0.20472132948337274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063883932483591, -0.1933647843987567, -0.009552516326901475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000916494083057, 0.12770763567726107, 0.4830687392069244, 0.0, -0.26019308643958283, -0.22931048175714647, -2.4215463400455506, -1.1875815492128718, -2.6246036628231084, -0.24515225513938024, -0.9048815573555332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1647218529199097, 0.7783765005428815, 1.723859375416625, -1.5150999797468971, -1.486737404398827, -0.37496984157688623, 0.6669070107583583, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5412740650655505, -0.5176261007453624, 0.03217890689697536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010606101974169083, 0.1477413589706372, 0.04722295782352715, 0.0, 0.5456380666109822, -0.16908262597857465, -0.522481214502478, 0.1461534807055757, 0.37666483191527816, -0.1855687496936574, 0.020997239613460877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30632626208072616, 0.09031298949467995, -0.22692456938849484, 0.16322421478210972, -0.12585470012523042, -0.03325777363445849, 0.20625099862925758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20630514214555695, -0.19345381168511577, -0.008617990399806234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001438740509397, 0.13491240604240237, 0.4854280578776173, 0.0, -0.23325017153039881, -0.23668803750654724, -2.4469621100956136, -1.180043409121759, -2.604441923727538, -0.2542616803190728, -0.9034046231800951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1500139995816223, 0.7820642540186723, 1.711999903987663, -1.5061554522402196, -1.4934494542740804, -0.37658879725504163, 0.6770756911532064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5515865469940715, -0.5272662582455687, 0.03200561485251141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444928526822455, 0.1440954073028262, 0.04718637341385814, 0.0, 0.5388582981836805, -0.14755111498801532, -0.5083154010012589, 0.15076280182225638, 0.4032347819114077, -0.18218850359385164, 0.029538683508763354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2941570667657477, 0.07375506951581443, -0.23718942857923855, 0.17889055013354835, -0.13424099750506613, -0.03237911356310805, 0.20337360789696188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2062496385704195, -0.1928031500041254, -0.0034658408892790024]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001956923917136, 0.14209490819490286, 0.48778483406484985, 0.0, -0.20719014955641507, -0.2431537045007487, -2.4717559018778976, -1.1723466381173246, -2.5832851837647595, -0.26272698890159707, -0.9018119287954139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1362925875347156, 0.7846942107354439, 1.6995945594881667, -1.4962533594938423, -1.500654434469294, -0.37804175814020746, 0.6869377230363743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5618772554935478, -0.5362481924237863, 0.03193009384487926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001036366815479113, 0.14365004305001008, 0.047135523744650826, 0.0, 0.5212004394796748, -0.12931333988402918, -0.4958758356456816, 0.15393542008868819, 0.42313479925557457, -0.16930617165048542, 0.031853887693621664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2744282409381327, 0.052599134335431535, -0.24810688998992422, 0.1980418549275443, -0.1440996039042721, -0.029059217703316893, 0.1972406376633577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20581416998952623, -0.17963868356435048, -0.001510420152642911]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20002491398495875, 0.1494178801698363, 0.49014213867983025, 0.0, -0.18248615642303045, -0.24874252779424932, -2.495791256850934, -1.1643342319297219, -2.561549609322388, -0.27017462278306265, -0.9004516927928198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1235910388524077, 0.7862627988346579, 1.686786930289798, -1.4854969415594632, -1.5083462475227143, -0.3792270963843562, 0.6964032961833078, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5721284937799476, -0.544042023523245, 0.03174277720679715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010689491574809543, 0.14645943949866824, 0.047146092299607985, 0.0, 0.494079862667692, -0.11177646587001251, -0.4807070994607294, 0.1602481237520551, 0.43471148884742883, -0.14895267762931144, 0.027204720051883843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25403097364615596, 0.031371761984279836, -0.2561525839673737, 0.21512835868758007, -0.15383626106840426, -0.023706764882974334, 0.1893114629386691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2050247657279953, -0.15587662198917399, -0.00374633276164229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000302436587149, 0.1568804363366327, 0.4925089959261279, 0.0, -0.15942620646426864, -0.2535716429058741, -2.5191037233799887, -1.1561081590561926, -2.5395311185199434, -0.2762882019431225, -0.8995733094187667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1117286539701878, 0.7868744141902151, 1.6737792940401723, -1.474100709544747, -1.5164731868474546, -0.3800749465354888, 0.705439711141863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.582334625025694, -0.5505038053914475, 0.031328551739566904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010659347512320952, 0.14925112333592852, 0.04733714492595309, 0.0, 0.46119899917523643, -0.09658230223249553, -0.4662493305810919, 0.16452145747058344, 0.4403698160488929, -0.12227158320119691, 0.017567667481062112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23724769764439968, 0.012232307111143079, -0.26015272499251113, 0.2279246402943277, -0.16253878649480763, -0.016957003022651775, 0.1807282991711045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.204122624914929, -0.12923563736404983, -0.008284509344604833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000355409762551, 0.1643493632969471, 0.4948989781480506, 0.0, -0.138134306608576, -0.25778286324663996, -2.541755761063006, -1.1478203450866038, -2.517453701537978, -0.2808626769029118, -0.8993496529219878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1004377528853015, 0.7866677740581992, 1.6607635289911855, -1.4622859299485154, -1.5249653079719356, -0.38055155981383115, 0.7140521457823096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5924971178994362, -0.5556901650508949, 0.03066177407118626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010594635080377414, 0.14937853920628794, 0.047799644438453984, 0.0, 0.42583799711385245, -0.08422440681531787, -0.45304075366034996, 0.16575627939177673, 0.4415483396393033, -0.09148949919578589, 0.00447312993557779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22581802169772486, -0.004132802640316704, -0.2603153009797381, 0.2362955919246301, -0.16984242248962297, -0.00953226556684723, 0.17224869280893232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324985747484237, -0.1037271931889466, -0.01333555336761289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004081292641204, 0.17163111684490254, 0.4973273540293955, 0.0, -0.11861098806654552, -0.261506003937954, -2.563792455725704, -1.1396190617008346, -2.4954889007469143, -0.2838319038624897, -0.8998890469110882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0894421809363275, 0.7857788657157315, 1.6478909021820578, -1.4502320834056803, -1.5337515051369732, -0.3806565744431942, 0.7222674722419069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6026210959822068, -0.559746501253625, 0.029776897416194534]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010543900313926698, 0.14563507095910855, 0.048567517626897164, 0.0, 0.3904663708406098, -0.0744628138262803, -0.44073389325396295, 0.1640256677153848, 0.4392960158212723, -0.059384539191558075, -0.010787879782008984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21991143897947918, -0.017778166849353613, -0.2574525361825549, 0.2410769308567017, -0.17572394330075108, -0.0021002925872602293, 0.16430652919194655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20247956165541275, -0.08112672405460414, -0.01769753309983457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004606432832564, 0.1785368757147403, 0.4998084022537411, 0.0, -0.10078082637104352, -0.264847160038961, -2.5852379440488384, -1.131630598596612, -2.4737657902986205, -0.28524416183276086, -0.9012452613483256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.078500262559309, 0.7843260714150962, 1.6352650158000486, -1.4380627524161154, -1.5427684175926506, -0.3804169066440311, 0.7301226067745017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6127129574718959, -0.5628429113478618, 0.028737698239593924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001050280382721323, 0.1381151773967553, 0.04962096448691232, 0.0, 0.35660323391003995, -0.06682312202014098, -0.4289097664626888, 0.15976926208445047, 0.43446220896587195, -0.02824515940542372, -0.027124288744748738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21883836754036934, -0.029055886012705798, -0.2525177276401867, 0.24338661979130038, -0.1803382491135461, 0.004793355983261567, 0.1571026906518956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20183722979378182, -0.06192820188473633, -0.020783983532012218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005129930180776, 0.1849245954383537, 0.5023535969404489, 0.0, -0.0845365476780033, -0.26789192708329723, -2.606108693073243, -1.1239444492086228, -2.452378330247755, -0.2852004259172213, -0.903428031037695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0674226840202274, 0.7824081342080057, 1.6229472251942958, -1.4258507451503226, -1.5519634683297958, -0.3798798984965973, 0.7376575659920607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6227788903479773, -0.5651382965458367, 0.027612209173982813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010469946964228746, 0.12775439447226813, 0.05090389373415543, 0.0, 0.32488557386080436, -0.06089534088672406, -0.4174149804880978, 0.1537229877597814, 0.42774920101731634, 0.0008747183107913163, -0.04365539378738713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22155157078163232, -0.038358744141811715, -0.24635581211505642, 0.24424014531585422, -0.18390101474290552, 0.010740162948676057, 0.15069918435117943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2013186575216267, -0.0459077039594976, -0.02250978131222222]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005652136933838, 0.1907115542078159, 0.5049708022133425, 0.0, -0.06976173780440523, -0.27070753685227544, -2.6264208198234114, -1.116616946684467, -2.4313907896673914, -0.2838218803566358, -0.906412585221189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0560736135802962, 0.7801058082827312, 1.6109657132036308, -1.4136290432962257, -1.5612950664604608, -0.37910605441542466, 0.7449113819247415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6328242153560852, -0.5667667343942321, 0.026461026087480004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444135061213921, 0.1157391753892438, 0.052344105457870035, 0.0, 0.29549619747196143, -0.05631219537956404, -0.40624253500336754, 0.14655005048311465, 0.4197508116072699, 0.02757091121170977, -0.05969108366987838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22698140879862486, -0.046046518505490075, -0.23963023981329837, 0.24443403708193845, -0.18663196261329876, 0.015476881623452673, 0.14507631865361617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200906500162158, -0.032568756967906835, -0.023023661730056176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006173377981204, 0.19586946360562876, 0.5076644609626558, 0.0, -0.05634179204398947, -0.27334548158613015, -2.646193322366273, -1.1096790839813315, -2.410842927702957, -0.2812329746831892, -0.9101485177967618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0443638223042633, 0.7774845919923008, 1.5993249042842526, -1.4014024614291, -1.570731417155611, -0.3781624858127281, 0.751920026015881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6428532286355354, -0.5678352846961159, 0.025332638215552584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010424820947313969, 0.10315818795625725, 0.05387317498626852, 0.0, 0.26839891520831505, -0.05275889467709448, -0.3954500508572305, 0.138757254062713, 0.4109572392886899, 0.051778113468932276, -0.07471865151145703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23419582552065923, -0.05242432580860899, -0.23281617838756566, 0.24453163734251182, -0.1887270139030052, 0.018871372053931603, 0.14017288182279053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005802655890033, -0.02137100603767564, -0.02256775743854842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006693974018563, 0.20041148659983554, 0.5104356354131638, 0.0, -0.04416856961827303, -0.2758444403769414, -2.6654490711305923, -1.103143801672166, -2.3907551627710806, -0.2775528776658062, -0.9145677909379701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.032240873995808, 0.7745974410638581, 1.588013709038981, -1.3891577880418844, -1.5802488161344124, -0.37711757562047643, 0.7587156306949181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6528692669109263, -0.5684268272253782, 0.024262524580118537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010411920747207684, 0.09084045988413576, 0.0554234890101607, 0.0, 0.24346444851432894, -0.049979175816224464, -0.3851149752863885, 0.1307056461833094, 0.4017552986375233, 0.07360194034765936, -0.08838546282416829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2424589661691047, -0.05774301856885468, -0.2262239049054323, 0.24489346774431225, -0.19034797957602634, 0.020898203845033683, 0.13591209358074058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032076550781866, -0.011830850585245457, -0.02140227270868092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007214257134473, 0.2043774343813399, 0.5132834444778108, 0.0, -0.033141879221293254, -0.27823311442357535, -2.684214783748266, -1.0970116831686958, -2.3711334911723347, -0.27289151361168223, -0.9195916030855968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0196792372387637, 0.7714870996542419, 1.577012080120262, -1.3768717128358068, -1.5898299178620672, -0.376037003117718, 0.7653264677326032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6628748614477549, -0.5686045085855391, 0.023274225345194223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010405662318178713, 0.07931895563008712, 0.05695618129293898, 0.0, 0.22053380793959546, -0.04777348093267944, -0.3753142523534738, 0.12264237006940129, 0.3924334319749157, 0.09322728108248012, -0.10047624295253367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.251232735140885, -0.06220682819232286, -0.22003257837437873, 0.24572150412155103, -0.191622034553094, 0.02161145005516844, 0.13221674075370154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001118907365725, -0.003553627203219339, -0.019765984698486314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007734580778586, 0.20782070618049545, 0.5162057356413299, 0.0, -0.02316952921589255, -0.2805327086574647, -2.7025206472294165, -1.0912751301891823, -2.3519738846130913, -0.26734808709481267, -0.9251359659670314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0066716891018626, 0.7681879876718668, 1.5662958363212114, -1.364516539676587, -1.5994622264425942, -0.3749810550619353, 0.7717773035049438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728719094996554, -0.5684161418783988, 0.022381311534141354]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010406472882246143, 0.06886543598311097, 0.0584458232703806, 0.0, 0.19944700010801403, -0.04599188467778787, -0.36611726962300406, 0.11473105959026818, 0.3831921311848679, 0.11086853033739165, -0.11088725762869056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26015096273802274, -0.06598223964750083, -0.21432487598101155, 0.24710346318439644, -0.19264617161054026, 0.021118961115654065, 0.1290167154468116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994096103801032, 0.003767334142805944, -0.017858276221057384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008255327007832, 0.2107984551058236, 0.5192101868201725, 0.0, -0.014166840177746965, -0.2827589651423013, -2.7203998728202277, -1.085921389661834, -2.333265997210729, -0.2610109256209237, -0.9311159707638332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.993222525276789, 0.76472770791297, 1.5558399599130788, -1.3520640084958147, -1.609136898369661, -0.3740030351449078, 0.7780898891731596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6828618146769264, -0.5678979208460078, 0.02158961746419203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010414924584927073, 0.059554978506562724, 0.060089023576853036, 0.0, 0.18005378076291173, -0.044525129696731926, -0.35758451181622114, 0.10707481054696666, 0.3741577480472417, 0.12674322947777925, -0.11960009593603711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2689832765014719, -0.06920559517793774, -0.2091175281626519, 0.24905062361544741, -0.19349343854133583, 0.01956039834054967, 0.12625171336431662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19979810354541996, 0.01036442064782242, -0.015833881398986463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008787845500087, 0.21333432017666262, 0.522278620524105, 0.0, -0.005963419259842758, -0.2847067784692105, -2.737706908660592, -1.0808938141815105, -2.3150267722676117, -0.25438667800412285, -0.9374635516762867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9793618168468088, 0.7611051078601969, 1.545609423592007, -1.3394608678986315, -1.6188542055022237, -0.3731361931769705, 0.784273511539081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6928467960164502, -0.5671346529160782, 0.02093020073211555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010650369845106335, 0.050717301416780575, 0.06136867407865102, 0.0, 0.16406841835808414, -0.038956266538184035, -0.34614071680728536, 0.10055150960646979, 0.3647844988623467, 0.13248495233601743, -0.12695161824906995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27721416859960457, -0.07245200105546167, -0.20461072642143427, 0.2520628119436626, -0.194346142651256, 0.01733683935874627, 0.12367244731842914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19969962679047468, 0.015265358598590295, -0.013188334641529539]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000932460772157, 0.2154911957901415, 0.5254075520960675, 0.0, 0.0015154044261366864, -0.28641516619292723, -2.7544320930412285, -1.076174171725622, -2.2972498271597006, -0.24759982073920533, -0.9441141009023792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9651278873460428, 0.757327427091728, 1.535580448860818, -1.326672138264618, -1.628612812424153, -0.37240896197700574, 0.7903376336523634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7028278828753675, -0.5661656331890602, 0.020389486558202795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010735244429674809, 0.04313751226957778, 0.0625786314392504, 0.0, 0.14957647371958888, -0.03416775447433472, -0.33450368761273663, 0.09439284911777152, 0.35553890215822376, 0.13573714529835043, -0.13301098452185098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2846785900153182, -0.07555361536937943, -0.20057949462378213, 0.25577459268027014, -0.19517213843858824, 0.01454462399929483, 0.12128244226564817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.199621737178345, 0.019380394540359974, -0.010814283478255146]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000986504638207, 0.2173348800863795, 0.5285963538711298, 0.0, 0.008311286985787932, -0.2879703140158385, -2.770613356296178, -1.071752895513645, -2.2799188962291113, -0.24064150349451635, -0.9510100879683961, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9505529498723302, 0.7534056826233598, 1.5257378740419243, -1.3136770586139697, -1.63841007581735, -0.37184397678607, 0.7962921332243709, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7128055169800916, -0.5650064298475672, 0.019945411914984862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010808773209972387, 0.036873685924759945, 0.06377603550124566, 0.0, 0.13591765119302487, -0.031102956458224976, -0.32362526509899225, 0.08842552423953609, 0.3466186186117867, 0.13916634489377944, -0.13791974132033838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2914987494742535, -0.07843488936736323, -0.19685149637787305, 0.25990159301296684, -0.19594526786394395, 0.011299703818714464, 0.11908999144014908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19955268209448396, 0.023184066829859785, -0.008881492864358671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001040952281578, 0.21892164502751066, 0.5318443998538492, 0.0, 0.014455434372994066, -0.2894449297458632, -2.7863038589103057, -1.0676217341506595, -2.263014026217533, -0.23346849295648808, -0.9581014231716674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9356598942300804, 0.7493518268839664, 1.5160721145437042, -1.3004642700198759, -1.6482428027961602, -0.37145864779806914, 0.8021471910765554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7227798395497232, -0.5636600458570635, 0.019578016659266558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010889528674247463, 0.03173529882262352, 0.0649609196543887, 0.0, 0.12288294774412264, -0.029492314600493903, -0.313810052282559, 0.08262322725971165, 0.33809740023156404, 0.14346021076056528, -0.14182670406542525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2978611128449939, -0.08107711478786886, -0.19331518996440414, 0.2642557718818771, -0.19665453957620216, 0.007706579760017614, 0.11710115704369055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19948645139263124, 0.026927679810074084, -0.007347905114366092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001095818476272, 0.2202943968225748, 0.535150869996002, 0.0, 0.019976112404964497, -0.2908868408754237, -2.801560742506763, -1.0637723948338313, -2.246514853532375, -0.2260387914595803, -0.9653442577370467, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9204627132754218, 0.7451771967137655, 1.5065767335510407, -1.2870279213106035, -1.6581079764407811, -0.3712661111733493, 0.8079130441774274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7327508384249672, -0.5621229025816208, 0.01927182718937029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010973238938801623, 0.027455035901282798, 0.06612940284305621, 0.0, 0.11041356063940856, -0.028838222591209578, -0.3051376719291418, 0.07698678633656415, 0.3299834537031666, 0.1485940299381555, -0.14485669130758602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3039436190931732, -0.08349260340401757, -0.189907619853269, 0.26872697418544794, -0.19730347289241743, 0.003850732494397405, 0.11531706201743988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19941997750488044, 0.030742865508854446, -0.0061237893979253916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20011511096299092, 0.2214825190671099, 0.5385151065100857, 0.0, 0.02490084713840034, -0.2923229338625861, -2.8164412711336357, -1.060196351782816, -2.2304025030501005, -0.21832156697497618, -0.9726993825050722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9049681306376484, 0.740891755553815, 1.4972467377444765, -1.2733648666517141, -1.6680033011218867, -0.3712761292836445, 0.8135997040895893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7427184266565153, -0.560388285861029, 0.019015717754810958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011058230727444141, 0.023762444890702263, 0.06728473028167319, 0.0, 0.09849469466871684, -0.028721859743248285, -0.2976105725374558, 0.07152086102030841, 0.32224700964548914, 0.15434448969208248, -0.14710249536050946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30989165275546887, -0.08570882319900835, -0.1865999161312844, 0.27326109317778985, -0.19790649362210908, -0.00020036220590430396, 0.11373319824323874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935176463096194, 0.03469233441183588, -0.0051221886911865955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012068354139295, 0.22250349531401678, 0.5419369045324964, 0.0, 0.029256928531896972, -0.29376602433815924, -2.8310013768663658, -1.0568847414431133, -2.2146607151661373, -0.21029745116627052, -0.9801307890007165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8891775148909307, 0.7365037811966567, 1.4880774850525833, -1.2594727666522887, -1.677927543943993, -0.37149579637202673, 0.8192166918784729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.752682486082162, -0.5584484377725315, 0.018802084615086322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011145156804087516, 0.020419524938137586, 0.06843596044821347, 0.0, 0.08712162786993259, -0.02886180951146266, -0.2912021146546042, 0.06623220679405235, 0.3148357576792621, 0.1604823161741131, -0.14862812991288768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3158123149343549, -0.08775948714316552, -0.18338505383786374, 0.2778419999885099, -0.19848485644212302, -0.00439334176764448, 0.112339755777672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19928118851293328, 0.0387969617699493, -0.004272662794492707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012628164617755, 0.22332134060079772, 0.54541662471814, 0.0, 0.03317120156856523, -0.29518464960895535, -2.8451380890300952, -1.053961604220274, -2.1992726208632316, -0.20265878664500153, -0.9876002580722529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8730997429735209, 0.7319946575093498, 1.4790548783712623, -1.2453195416574887, -1.687887002196704, -0.37191213155652425, 0.8247616904031708, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7626439397110358, -0.556356609092534, 0.018669902169850008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001119620956917603, 0.01635690573561878, 0.06959440371287186, 0.0, 0.07828546073336504, -0.02837250541592201, -0.282734243274592, 0.05846274445678641, 0.30776188605811694, 0.15277329042537996, -0.14938938143072922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32155543834819605, -0.0901824737461377, -0.18045213362641968, 0.28306449989600013, -0.1991891650542251, -0.00832670368995064, 0.11089997049395796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19922907257747532, 0.04183657359994846, -0.002643648904726283]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013192442139177, 0.2239482275425103, 0.5489548371269524, 0.0, 0.0366715792278375, -0.296586524353173, -2.8588493933976524, -1.0514203929343469, -2.184236114366281, -0.1954379262848652, -0.9950902730344263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8567527786674105, 0.7273588576734159, 1.4701719485389229, -1.230888881533351, -1.6978848911636142, -0.37251543196268055, 0.8302341701041117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7726029312808944, -0.5541258337645512, 0.018610119682379557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001128555042845191, 0.0125377388342514, 0.07076424817624641, 0.0, 0.07000755318544544, -0.028037494884353635, -0.27422608735114595, 0.050824225718544155, 0.3007301299390082, 0.14441720720272663, -0.1498002992434688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32693928612220846, -0.09271599671867779, -0.17765859664678813, 0.28861320248275546, -0.1999577793382039, -0.012066008123126602, 0.1094495940188172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917983139717088, 0.044615506559656834, -0.0011956497494090225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013761457522716, 0.22440734591479483, 0.5525510066268541, 0.0, 0.03975911638397082, -0.29798216934315713, -2.8721656295211786, -1.0492191300271183, -2.1695526216527776, -0.18848173123026996, -1.0025971718647806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8401509814292484, 0.7225974376254728, 1.461426296142665, -1.2161747018287186, -1.7079221563356972, -0.3732971774069232, 0.8356348772421495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7825592728935553, -0.5517519790258053, 0.018604268532772555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011380307670761093, 0.009182367445690917, 0.07192338999803456, 0.0, 0.06175074312266636, -0.027912899799682093, -0.2663247224705193, 0.044025258144572164, 0.29366985427007, 0.13912390109190506, -0.15013797660708325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3320359447632418, -0.09522840095886133, -0.17491304792515783, 0.2942835940926487, -0.20074530344166105, -0.01563490888485266, 0.1080141427607551, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19912683225321814, 0.04747709477491714, -0.00011702299214006178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014335289543783, 0.22472031035488813, 0.5562052394000923, 0.0, 0.042430718224349184, -0.2993775663249582, -2.885124494559544, -1.0473129015067846, -2.155222804147192, -0.1816201348745458, -1.01012474190697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8233031935612874, 0.7177142448998596, 1.4528175204778178, -1.2011759013625687, -1.7179983908228533, -0.374249479327445, 0.8409652330108597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925126832685195, -0.5492244957458804, 0.018635373875526565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011476640421320383, 0.006259288801865879, 0.07308465546476407, 0.0, 0.05343203680756739, -0.027907939636021756, -0.25917730076730283, 0.03812457040667647, 0.28659635011170964, 0.13723192711448282, -0.1505514008437909, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.33695575735921823, -0.09766385451226353, -0.17217551329694306, 0.2999760093229975, -0.2015246897431223, -0.019046038410436672, 0.10660711537420353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906820749928394, 0.05054966559849752, 0.0006221068550801514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014914122512492, 0.22490281905863652, 0.5599181172915517, 0.0, 0.044685009011025914, -0.3007746371064331, -2.897763192892381, -1.0456630527405861, -2.1412454289020606, -0.1747151974114972, -1.0176787139885983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8062133777782159, 0.7127138428914443, 1.4443454795666644, -1.1858927542576552, -1.7281125254817933, -0.37536492761112034, 0.8462267964200866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8024628663707979, -0.5465312346100106, 0.018690277971370874]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011576659374156097, 0.0036501740749680742, 0.0742575578291891, 0.0, 0.04508581573353464, -0.027941415629497295, -0.25277396665674096, 0.03299697532397076, 0.2795475049026293, 0.13809874926097254, -0.15107944163256468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3417963156614319, -0.100008040168305, -0.1694408182230674, 0.30566294209827055, -0.20228269317880074, -0.022308965673506504, 0.10523126818453868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1990036620455675, 0.05386522271739528, 0.0010980819168861728]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20015498241295324, 0.22496358788852341, 0.5636906952949815, 0.0, 0.046523124895129254, -0.30217304171259973, -2.910116870810712, -1.0442383548647112, -2.127617660175425, -0.16766711338600437, -1.025262800625812, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7888816327849963, 0.7076004604520697, 1.4360093419839672, -1.170324783273599, -1.7382632426248827, -0.3766364801543263, 0.8514208330493006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8124095464110179, -0.5436605129536562, 0.018759558823811803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011682375656639517, 0.0012153765977381483, 0.0754515600685947, 0.0, 0.036762317682066795, -0.027968092123332625, -0.2470735583666168, 0.028493957517499034, 0.2725553745327172, 0.1409616805098563, -0.15168173274427474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3466348998643898, -0.10226764878749364, -0.16672275165394146, 0.31135941968112435, -0.20301434286178807, -0.02543105086411955, 0.10388073258428018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19893360080440123, 0.05741443312708689, 0.0013856170488185833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001608631206162, 0.22486724977568132, 0.5675244651508963, 0.0, 0.04804091382447449, -0.3035412422848025, -2.922052328864245, -1.043124700167149, -2.114336383673618, -0.16144541042735452, -1.0328762966158225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7713251667984461, 0.7023538524834112, 1.4278003950431948, -1.1544406355268644, -1.7484541924423087, -0.3780359169281584, 0.8565366409104427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8223535527855577, -0.5406644830067112, 0.018874481121896925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011761415325926333, -0.0019267622568418198, 0.0766753971182944, 0.0, 0.030355778586904754, -0.02736401144405591, -0.23870916107066367, 0.022273093951243095, 0.2656255300361335, 0.1244340591729968, -0.15226991980021082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35112931973100436, -0.10493215937317057, -0.16417893881545068, 0.3176829549346932, -0.20381899634852044, -0.02798873547664122, 0.1023161572228418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19888012749079415, 0.05992059893890097, 0.0022984459617024834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20016679470852397, 0.22461810660336734, 0.5714204886721297, 0.0, 0.0492515606625755, -0.3048795567549562, -2.9335321144560953, -1.0423074447214344, -2.10140738073954, -0.15596642624339424, -1.0405372644415392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7535642511419999, 0.6969653494000717, 1.4197151124779401, -1.1382226627253809, -1.7586848946400433, -0.37953926699620993, 0.8615644584658677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8322950464256667, -0.5375590699744391, 0.019029445546714298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011863175815503065, -0.0049828634462796215, 0.0779204704246687, 0.0, 0.024212936762020215, -0.026766289403073663, -0.229595711837008, 0.01634510891429119, 0.25858005868156314, 0.1095796836792056, -0.15321935651433463, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3552183131289241, -0.10777006166679028, -0.16170565130509318, 0.3243594560296713, -0.2046140439546916, -0.030067001361030556, 0.10055635110850149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1988298728021799, 0.06210826064544102, 0.003099288496347424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200172776239212, 0.2242322692592346, 0.5753793197616183, 0.0, 0.050143828812840734, -0.3061910582581071, -2.944550534505061, -1.041743376056535, -2.0888357341121013, -0.15093367718695333, -1.048277236264781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7356141941268067, 0.691432512186373, 1.4117532741877563, -1.121661763852356, -1.7689514159459603, -0.3811251082443771, 0.86649506189296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8422339086677469, -0.5343440199178914, 0.019210896739374525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001196306137608304, -0.007716746882654741, 0.07917662178977203, 0.0, 0.0178453630053046, -0.026230030063017495, -0.2203684009793198, 0.011281373297985921, 0.25143293254877075, 0.1006549811288182, -0.15479943646483557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3590011403038624, -0.11065674427397341, -0.15923676580367516, 0.3312179774604951, -0.2053304261183416, -0.031716824963344104, 0.09861206854184656, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19877724484160614, 0.06430100113095442, 0.003629023853204522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017880771966834, 0.2237276625238269, 0.5794013303291399, 0.0, 0.050699909006210096, -0.30747661967759615, -2.9551116517246165, -1.0413867886406278, -2.0766216597974223, -0.14608404137141487, -1.0561326296271798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7174848001385788, 0.6857562710597147, 1.4039161304800842, -1.10475315105645, -1.7792470152797084, -0.3827741958966008, 0.871319355442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8521699154814953, -0.5310119017509993, 0.01940522188486421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012062960912663622, -0.01009213470815384, 0.08044021135043324, 0.0, 0.011121603867387315, -0.025711228389780374, -0.21122234439110926, 0.007131748318146876, 0.2442814862935846, 0.09699271631076936, -0.1571078672479778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36258787976455753, -0.11352482253316624, -0.1567428741534436, 0.33817225591812267, -0.20591198667496285, -0.032981753044473566, 0.0964858709840395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.198720136274969, 0.06664236333784118, 0.0038865029097937334]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001848920125801, 0.22311939837896405, 0.5834870489289138, 0.0, 0.05090078540002527, -0.308735882796434, -2.9652229966883774, -1.0411980034684942, -2.064759670416598, -0.14123323192581774, -1.0641371565315465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6991809830148032, 0.679939291147258, 1.3962051220839664, -1.087493451223696, -1.7895626538601601, -0.3844693487373193, 0.8760279613648302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8621028082079024, -0.5275522348262791, 0.01960080649115936]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012168585823553865, -0.012165282897256904, 0.08171437199547749, 0.0, 0.004017527876303342, -0.025185262376756567, -0.2022268992752162, 0.0037757034426703215, 0.23723978761649236, 0.09701618891194237, -0.16009053808733326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3660763424755128, -0.1163395982491342, -0.15422016792235796, 0.34519399665507955, -0.2063127716090326, -0.03390305681437007, 0.09417211845336478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19865785452814178, 0.06919333849440365, 0.003911692125903012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001910339768254, 0.22241740746155528, 0.5876373692829787, 0.0, 0.05072825256032961, -0.3099686862518699, -2.9748947407521658, -1.0411450762759276, -2.0532395768694993, -0.13626393879654164, -1.0723170910833948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6807032804433021, 0.6739849745819401, 1.388621114169803, -1.0698788282800074, -1.7998873562412572, -0.3861952801931571, 0.8806108106665858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8720323358314703, -0.5239535080029184, 0.019788621026410307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012283928490566007, -0.014039818348175664, 0.083006407081299, 0.0, -0.0034506567939130836, -0.024656069108718866, -0.19343488127577046, 0.0010585438513315741, 0.2304018709419729, 0.09938586258552179, -0.1635986910369645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3695540514300244, -0.1190863313063596, -0.15168015828326817, 0.3522924588737728, -0.20649404762193996, -0.03451862911675506, 0.09165698603511138, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19859055247135768, 0.07197453646721513, 0.0037562907050189094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001972276229123, 0.22160015992593438, 0.5918536565550914, 0.0, 0.05023534327615232, -0.31115485912438157, -2.98399731890119, -1.0412776896283897, -2.0420522122641835, -0.1323673535576393, -1.08069297108184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6620730424338469, 0.6678791574614724, 1.3811606617335281, -1.0518815424837384, -1.8102108812872644, -0.3879171685167433, 0.8850471905233438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8819592391097035, -0.5202568933142251, 0.019987756381997294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012387292173853077, -0.016344950712418115, 0.08432574544225284, 0.0, -0.00985818568354585, -0.023723457450233045, -0.1820515629804796, -0.0026522670492431072, 0.22374729210631697, 0.07793170477804703, -0.16751759996890506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3726047601891036, -0.12211634240935253, -0.1492090487254995, 0.35994571592537883, -0.2064705009201449, -0.034437766471724654, 0.08872759713516082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853806556466372, 0.07393229377386722, 0.0039827071117397314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20020347439010194, 0.22066886640840974, 0.5961368789821828, 0.0, 0.04942137616753238, -0.3122911282120764, -2.9924717451619225, -1.0415807058060549, -2.0311924115217646, -0.12926459359144046, -1.0893046900564256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6433087343387187, 0.6616151695062485, 1.3738233634988397, -1.0334828954614335, -1.820518215348053, -0.3896034935502784, 0.8893152917455368, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918837518366295, -0.5164777926262232, 0.020196315181244682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001249353437924127, -0.018625870350492735, 0.0856644485418279, 0.0, -0.0162793421723988, -0.0227253817538959, -0.1694885252146481, -0.0060603235533009635, 0.21719601484837767, 0.06205519932397649, -0.17223437949171228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3752861619025646, -0.12527975910447817, -0.1467459646937689, 0.36797294044609824, -0.20614668121577498, -0.03372650067070167, 0.08536202444386097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984902545385202, 0.07558201376003792, 0.004171175984947794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002097713156489, 0.21963330701260128, 0.6004876430588264, 0.0, 0.04826735161790908, -0.31337521052871675, -3.0002854311434213, -1.042017856951844, -2.020651124882025, -0.12654774583476963, -1.0982068765058308, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6244231401634923, 0.6551909860127477, 1.3666107181270413, -1.014669781954262, -1.830789814952071, -0.3912255494765068, 0.8933920015145673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9018058862955415, -0.5126188329621287, 0.020406874864572447]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001259385109389794, -0.020711187916169344, 0.08701528153287227, 0.0, -0.023080490992466042, -0.021681646332807118, -0.1562737196299728, -0.008743022915782392, 0.21082573279478972, 0.054336955133416694, -0.17804372898810442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37771188350452867, -0.12848366987001567, -0.14425290743596728, 0.3762622701434281, -0.2054319920803594, -0.032441118524568074, 0.08153419538060984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19844268917823923, 0.07717919328188974, 0.004211193666555281]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021612092282184, 0.21850629281013784, 0.6049063830180879, 0.0, 0.04674694556987107, -0.3144054031470295, -3.0074185370116227, -1.0425507553929605, -2.010411408134718, -0.12394384477934386, -1.1074574531963899, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6054236679376318, 0.6486078022609617, 1.3595250401006225, -0.9954321389298569, -1.8410018235275876, -0.3927577856739413, 0.897252692534199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9117255410177183, -0.5086754720012359, 0.020610626904816205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001269921434586169, -0.022540284049268652, 0.08837479918522834, 0.0, -0.030408120960760072, -0.02060385236625595, -0.1426621173640283, -0.01065796882233028, 0.20479433494613986, 0.052078021108515345, -0.18501153381118132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37998944451720995, -0.1316636750357197, -0.1417135605283744, 0.38475286048810226, -0.20424017151033333, -0.030644723948690555, 0.07721382039263426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19839309444353564, 0.07886721921785816, 0.004075040804875125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022253027785625, 0.2172997061063792, 0.6093940275144712, 0.0, 0.044831410138811985, -0.31538213075779564, -3.0138605032598287, -1.0431464819052012, -2.0004478758145035, -0.12130496351048073, -1.1171087473807155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5863125474238096, 0.6418689300364602, 1.3525686390384142, -0.975760852223192, -1.8511263198677277, -0.3941779859496728, 0.9008708398699348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9216425579681401, -0.5046390286167527, 0.020799215252272733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012818710068790215, -0.024131734075172735, 0.08975288992766754, 0.0, -0.03831070862118175, -0.01953455221532188, -0.12883932496411699, -0.011914530244816071, 0.19927064640429257, 0.05277762537726262, -0.1930258836865146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38222241027644466, -0.13477744449003068, -0.13912802124416684, 0.39342573413329984, -0.20248992680280403, -0.02840400551462917, 0.07236294671471433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19834033900843503, 0.08072886768966328, 0.0037717669491305742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022900860672177, 0.21602149077378158, 0.6139508566643666, 0.0, 0.04249304529260065, -0.3163082802897171, -3.019609641149978, -1.0437794882828788, -1.9907280811770776, -0.11855834742913957, -1.127203397503628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56708689339683, 0.6349787981933329, 1.3457432785905576, -0.9556459545254953, -1.8611315315344155, -0.39546708486206655, 0.9042174428273831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9315567687691604, -0.5004987690426352, 0.020966024033625068]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012956657731027664, -0.02556430665195258, 0.09113658299790565, 0.0, -0.04676729692422672, -0.01852299063842921, -0.11498275780298244, -0.012660127553552256, 0.1943958927485175, 0.054932321626823176, -0.20189300245824846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38451308053959093, -0.13780263686254624, -0.136507208957131, 0.4022979539539349, -0.20010423333375432, -0.02578197824787499, 0.06693205914896853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982842160204063, 0.08280519148234991, 0.003336175627046675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20023567613729168, 0.21468232598148812, 0.618579669380404, 0.0, 0.039716685832498946, -0.3170317589450412, -3.0246594038591277, -1.0443415770723183, -1.9812217011084206, -0.11567135386636834, -1.13777905015814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477513703633965, 0.6279428756470102, 1.3390496574407549, -0.9350758302929199, -1.8709811549442146, -0.39660843413451846, 0.9072602766909373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9414681136338643, -0.49624739219259395, 0.02109857982582755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013335061139804465, -0.02678329584586907, 0.09257625432074831, 0.0, -0.05552718920203407, -0.014469573106482808, -0.1009952541829951, -0.011241775788790789, 0.19012760137314005, 0.05773987125542451, -0.21151305309023985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3867104606686719, -0.14071845092645366, -0.13387242299605406, 0.4114024846515084, -0.1969924681959818, -0.022826985449038478, 0.06085667727108461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982268972940784, 0.08502753700082558, 0.0026511158440496816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024248448796664, 0.2132817010339462, 0.6232850539165122, 0.0, 0.03648736491123274, -0.3176151113242534, -3.029022659188296, -1.0448138848933215, -1.9718877847713319, -0.11262628356749618, -1.1488617258468545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.52829997285123, 0.6207655905849384, 1.332488202871619, -0.914035823072634, -1.8806351577949825, -0.39758655139198784, 0.909962810616463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.951376543075006, -0.49187641030852547, 0.02119267081108958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013616701349902424, -0.028012498950838564, 0.0941076907221639, 0.0, -0.06458641842532403, -0.011667047584244146, -0.08726510658336331, -0.009446156420062756, 0.1866783267417718, 0.060901405977443104, -0.2216535137742917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3890279502433304, -0.1435457012414359, -0.1312290913827172, 0.42080014440571706, -0.19308005701535966, -0.01956234514938717, 0.054050678510513796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19816858882283422, 0.08741963768137005, 0.0018818197052405962]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024942643988033, 0.21179744237757436, 0.6280614356300516, 0.0, 0.032837414321974116, -0.31812578977269435, -3.0326111904443955, -1.0452508930410527, -1.9626876112700173, -0.11087403638981642, -1.1604767590735159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5087462976732324, 0.6134391523867183, 1.3260590187239967, -0.8924938010822095, -1.8900486175493625, -0.3983666197484187, 0.9122756140155615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9612828171656946, -0.48741756737242403, 0.021263334940033223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001388390382738015, -0.029685173127436876, 0.09552763427078588, 0.0, -0.07299901178517247, -0.010213568968818868, -0.07177062512199014, -0.008740162954621399, 0.18400347002629233, 0.035044943553595116, -0.23230066453322595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.391073503559951, -0.14652876396440218, -0.1285836829524449, 0.430840439808488, -0.1882691950876016, -0.015601367128617337, 0.04625606798196829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1981254818137743, 0.0891768587220289, 0.0014132825788728686]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025648617165462, 0.2102159997234052, 0.6329105085744566, 0.0, 0.02877294974059154, -0.31860398466958934, -3.0353794732601376, -1.0456722544572943, -1.9535790164030598, -0.10975106669980453, -1.1726841966576451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48909731099497733, 0.6059579119762081, 1.3197643797852852, -0.8704192973769448, -1.8991693651637631, -0.39891412960312955, 0.9141417636527343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711873739518471, -0.4828893418700921, 0.0213193368087825]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001411946354858873, -0.03162885308338303, 0.09698145888810075, 0.0, -0.08128929162765157, -0.009563897937899444, -0.05536565631484504, -0.008427228324830742, 0.18217189733915135, 0.022459393800237974, -0.24414875168258673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39297973356510235, -0.1496248082102037, -0.12589277877422897, 0.44149007410529506, -0.1824149522880104, -0.01095019709421708, 0.03732299274345578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19809113572304787, 0.0905645100466391, 0.0011200373749855554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20026365067228066, 0.20853153423470647, 0.6378348053398177, 0.0, 0.024287414359991967, -0.31906383544072553, -3.03730358821359, -1.0460803808476857, -1.944506846300838, -0.10880336925481057, -1.1855679286607015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46935386567918885, 0.5983182674664688, 1.3136084475674703, -0.8477824018146772, -1.9079370164244762, -0.3991966785218747, 0.9154962070713135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9810904491676253, -0.47830120746567945, 0.021365983100818976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014329001252086628, -0.0336893097739748, 0.09848593530722288, 0.0, -0.08971070761199146, -0.009197015422723371, -0.03848229906904507, -0.008162527807830557, 0.18144340204443837, 0.018953948899879114, -0.2576746400611291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39486890631576926, -0.1527928901947863, -0.12311864435629659, 0.4527379112453502, -0.17535302521426147, -0.005650978374902695, 0.02708886837158525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19806150431556513, 0.09176268808825254, 0.0009329258407294982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002709181633583, 0.2067445984866543, 0.6432883074780156, 0.0, 0.019368020415770022, -0.319506030596099, -3.0383767612417256, -1.0464716606443134, -1.93539817392384, -0.10785793321986444, -1.1992183447754208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.449511737566043, 0.5905186190172917, 1.30759712755751, -0.8245528155742337, -1.9162819395303767, -0.39918565990323196, 0.9162647015301013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9909921334418351, -0.4736560022976525, 0.021405717349798476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014534982155259296, -0.035738714961043055, 0.1090700427639566, 0.0, -0.0983878788844389, -0.008843903107469055, -0.021463460562710514, -0.007825595932554615, 0.1821734475399597, 0.018908720698922653, -0.2730083222943843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39684256226291714, -0.15599296898354148, -0.1202264001992059, 0.46459172480887045, -0.1668984621180081, 0.0002203723728545822, 0.015369889175756525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19803368548419537, 0.09290410336053989, 0.000794684979589968]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20027829438051795, 0.20485868510348465, 0.6490013560727583, 0.0, 0.014002434650858962, -0.31992610835046786, -3.0386077281967667, -1.0468412358708508, -1.9261612032181843, -0.10686461645591573, -1.2137239690189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295630481332781, 0.5825587072681266, 1.3017382359732208, -0.8006983855868464, -1.9241240546061331, -0.39885668361580096, 0.9163618604901093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0008924345494923, -0.4689530184259971, 0.02143932756822293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001475243431933699, -0.037718267663393076, 0.11426097189485505, 0.0, -0.10731171529822119, -0.008401555087377478, -0.0046193391008222465, -0.007391504530747066, 0.18473941411311273, 0.01986633527897399, -0.2901124848695834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39897378865529753, -0.15919823498330188, -0.11717783168578469, 0.4770885997477463, -0.15684230151512948, 0.006579525748620504, 0.0019431792001582751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980060221531453, 0.09405967743310696, 0.0006722043684891009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028578925979554, 0.20287743274338085, 0.6547406686796089, 0.0, 0.008185018820865536, -0.32031794640898287, -3.0380197116706626, -1.0471838245626715, -1.9166848868198592, -0.10581108299932915, -1.2291713152384198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.409497880984442, 0.5744384300934184, 1.2960420336682963, -0.7761829962429637, -1.9313712603623479, -0.39818884409194577, 0.9156880981674309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0107913532621287, -0.46419123734401335, 0.021467110255929775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014989758555187285, -0.03962504720207571, 0.11478625213701081, 0.0, -0.11634831659986852, -0.007836761170300528, 0.011760330522081603, -0.0068517738364139965, 0.18952632796650123, 0.02107066913173159, -0.30894692439039756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4013033429767219, -0.16240554349416467, -0.11392404609848922, 0.49030778687765375, -0.1449441151242955, 0.013356790477103832, -0.01347524645356626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19797837425272766, 0.09523562163967537, 0.0005556537541368603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20029341668299114, 0.20080310284452807, 0.6604121090446456, 0.0, 0.001921849586408484, -0.3206748265522026, -3.036649950845352, -1.0474931959378289, -1.9068372060650318, -0.10469342341170036, -1.2456491252742798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38930633750726457, 0.5661566921582276, 1.2905223641067847, -0.750964653980663, -1.9379170515353874, -0.3971633693842987, 0.9141253637504341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0206889396240197, -0.45937220777499244, 0.021489539567299338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015254846391213545, -0.04148659797705568, 0.11342880730073404, 0.0, -0.12526338468914103, -0.007137602864394741, 0.027395216506216978, -0.006187427503146391, 0.1969536150965476, 0.022353191752575823, -0.32955620071719854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.403830869543549, -0.16563475870381658, -0.11039339123023295, 0.5043668452460132, -0.13091582346079012, 0.020509494152941406, -0.03125468833993677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979517272378216, 0.09638059138041875, 0.00044858622739128284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030119568854826, 0.19863638606599057, 0.6660139722038477, 0.0, -0.0047654859416252715, -0.32098958444084497, -3.034549899605448, -1.047761372718335, -1.8964610837443059, -0.10350850752967147, -1.2632545889497222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3689808614367368, 0.5577104480698207, 1.2851985271167368, -0.7249939125996567, -1.9436369605967867, -0.39576205076792975, 0.9115313297721367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305853548399064, -0.45450238080270544, 0.021507407707782908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015558011114232356, -0.04333433557074981, 0.1120372631840425, 0.0, -0.1337467105606751, -0.006295157772847987, 0.04200102479807478, -0.005363535610125525, 0.207522446414517, 0.023698317640577764, -0.3521092735088453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40650952141055535, -0.16892488176813872, -0.10647673980095607, 0.5194148276201257, -0.11439818122798806, 0.028026372327378497, -0.05188067956594836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792830431773525, 0.09739653944573959, 0.0003573628096714333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030914634140978, 0.19637390500117713, 0.6715828451201916, 0.0, -0.011823845857501004, -0.32125109674842384, -3.0317232352621573, -1.047993758889174, -1.8853759253989026, -0.10350850752923797, -1.282109695006647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34853531759768974, 0.5490903893140774, 1.2800996783217704, -0.6982100150772024, -1.9483808813828611, -0.3939543090524812, 0.9077272656514751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0404812611623253, -0.44961272326613566, 0.021525033954934155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001590130572305638, -0.045249621296268805, 0.11137745832687744, 0.0, -0.14116719831751465, -0.005230246151577747, 0.056533286865820584, -0.004647723416777062, 0.22170316690806577, 8.670054257864379e-12, -0.37710212113849784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4089108767809417, -0.17240117511486672, -0.10197697589932689, 0.535677950449087, -0.09487841572149006, 0.036154834308971096, -0.07608128241323243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19791812644837758, 0.09779315073139577, 0.00035252494302495706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003172693409572, 0.1940175527107981, 0.6771603689056768, 0.0, -0.019193679667741763, -0.321440476638921, -3.028179268613157, -1.0481732072969074, -1.8733471366727263, -0.10350850752836022, -1.3024202699248018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3279913270141919, 0.5402847239915176, 1.2752683565321803, -0.670544663390444, -1.9519661143688292, -0.39170631156022995, 0.9024892898828979, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0503774344917505, -0.4447394511672975, 0.021544256271463894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016245999094805286, -0.047127045807580724, 0.11155047570970374, 0.0, -0.1473966762048152, -0.0037875978099430434, 0.07087933298000587, -0.003588968154669996, 0.24057577452352463, 1.7555029717154477e-11, -0.40621149836309306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4108798116699565, -0.17611330645119624, -0.09662643579180089, 0.5533070337351663, -0.07170465971936085, 0.04495994984502532, -0.10475951537154438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792346658850413, 0.09746544197676281, 0.000384446330594774]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032562408611035, 0.19157898268789894, 0.6827789936632113, 0.0, -0.02680877064690194, -0.32154935222513786, -3.0239496911498267, -1.048269333871253, -1.8600634801830365, -0.10350850752892245, -1.3244520270897273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3073749799692585, 0.5312801892863821, 1.2707653820007925, -0.641920890359514, -1.9541671935741474, -0.38898616714406864, 0.8955337475218497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0602746926488202, -0.43992003567794874, 0.02156267750140531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016709490306319699, -0.04877140045798318, 0.11237249515069075, 0.0, -0.15230181958320357, -0.002177511724336902, 0.0845915492666035, -0.0019225314869087012, 0.2656731297937968, -1.1244587338957728e-11, -0.440635143298511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41232694089866834, -0.18009069410271097, -0.09005949062775538, 0.5724754606185991, -0.04402158410636586, 0.05440288832322622, -0.13911084722096373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979451631413971, 0.09638830978697575, 0.0003684245988282738]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003343827899983, 0.18908234189505516, 0.6884591475134899, 0.0, -0.03458886264762535, -0.32156845280526186, -3.019089507224257, -1.0482170064255085, -1.8451117116401439, -0.10350850752801133, -1.348545726744807, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.28671800434849704, 0.5220618657484017, 1.2666775150992649, -0.6122492040576393, -1.9547005956772974, -0.38576786993113416, 0.886494070350839, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0701739237493035, -0.4351940617873942, 0.02157207271245176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017517407775899616, -0.04993281585687589, 0.11360307700557186, 0.0, -0.15560184001446814, -0.0003820116024801435, 0.09720367851139555, 0.0010465489148875277, 0.29903537085785037, 1.8222420301728088e-11, -0.48187399310159584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4131395124152298, -0.18436647075960821, -0.08175733803055242, 0.5934337260374951, -0.010668042062998706, 0.06436594425868974, -0.18079354342021137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19798462200966607, 0.09451947781108981, 0.00018790422092902821]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003437113012565, 0.1865590655037719, 0.6942110743842566, 0.0, -0.042433366863801565, -0.32148710723549906, -3.013687044176947, -1.0479506258393319, -1.8279278250508226, -0.10350850752730906, -1.3751539477281702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26605257839378216, 0.5126101957533383, 1.263130067889564, -0.5814169572975708, -1.953201116026987, -0.38203307191891245, 0.8748821920655593, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0800761664844183, -0.43060595297904586, 0.021563618093416753]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018657022516393627, -0.05046552782566498, 0.11503853741533392, 0.0, -0.15689008432352433, 0.0016269113952556665, 0.10804926094620285, 0.00532761172353181, 0.34367773178642597, 1.4045463697372213e-11, -0.5321644196672647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41330851909429756, -0.1890333999012687, -0.07094894419401514, 0.6166449352013684, 0.02998959300620538, 0.07469596024443391, -0.23223756570559562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19804485470229513, 0.09176217616696702, -0.00016909238070013938]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20035384746092152, 0.18404512675042728, 0.7000380490622289, 0.0, -0.050212851054079896, -0.32129764731835564, -3.007872020375405, -1.047408573474381, -1.807714696520507, -0.1035085075265131, -1.4049158957652377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24540734864367067, 0.5028965248793075, 1.260308356335637, -0.5492699698748068, -1.949181545315102, -0.3777738292535714, 0.8600228144996451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899826588460824, -0.42620844655981927, 0.021530459334271956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020272319330068492, -0.050278775066892704, 0.11653949355944743, 0.0, -0.1555896838055666, 0.003789198342868636, 0.11630047603084057, 0.01084104729901766, 0.4042625706063127, 1.5919110619624917e-11, -0.5952389607413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41290459500222965, -0.19427341748061752, -0.0564342310785417, 0.6429397484552792, 0.08039141423770374, 0.08518485330682168, -0.2971875513182835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19812984723328245, 0.08795012838453235, -0.0006631751828959446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036843163460358, 0.18136281953048786, 0.7059390781648229, 0.0, -0.057767388905325394, -0.3210710738639323, -3.0019894450633307, -1.0466631557182662, -1.7833826261393904, -0.10350850752649103, -1.4386498684378064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22607875701511615, 0.49392618538752037, 1.2587569083891101, -0.5184133404197366, -1.941897647938553, -0.3738639731587597, 0.8417880744913834, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0998962708048692, -0.4221692529637803, 0.021686362584224045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002916834736410404, -0.053646144398788474, 0.1180205820518809, 0.0, -0.1510907570249099, 0.0045314690884670624, 0.1176515062414791, 0.014908355122296033, 0.4866414076223328, 4.4136456503999646e-13, -0.6746794534513738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3865718325710906, -0.17940678983574165, -0.03102895893053481, 0.6171325891014039, 0.1456779475309793, 0.07819712189623458, -0.36469480016523564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19827223917573664, 0.08078387192078006, 0.0031180649990417805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003942537113021, 0.17828529615059197, 0.7119086970749711, 0.0, -0.06481104577349599, -0.32095649077276867, -2.9965751754981027, -1.0458472146225162, -1.753576222358894, -0.10350850752557518, -1.476720268237994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21045717232158523, 0.4874910167006223, 1.2591597974561297, -0.492597068932329, -1.930827428581285, -0.371992393713558, 0.821011277691062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1098211641847406, -0.4187433454099081, 0.02231639502794631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000516441533970284, -0.061550467597917866, 0.11939237820296275, 0.0, -0.14087313736341175, 0.0022916618232726514, 0.10828539130455896, 0.016318821914997908, 0.5961280756099278, 1.8317036250482457e-11, -0.7614079960037541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.31243169387061864, -0.12870337373796226, 0.008057781340389522, 0.5163254297481521, 0.22140438714536217, 0.03743158890403379, -0.4155359360064289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984978675974289, 0.06851815107744402, 0.012600648874445338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004388397255267, 0.17485617009380533, 0.7179373658089209, 0.0, -0.0708799625458358, -0.32108736955233547, -2.9921991868446067, -1.0449728458633074, -1.7183656050601326, -0.103508507551078, -1.5186732699592207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20058607313259408, 0.48488016496026076, 1.261770084558291, -0.47557115538422545, -1.9164565911539984, -0.3734251779064008, 0.7994134183993886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1197616468296943, -0.41613950387568394, 0.023478168149860274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008917202844920643, -0.06858252113573299, 0.12057337467899516, 0.0, -0.12137833544679619, -0.002617575591335923, 0.08751977306991583, 0.01748737518417392, 0.70421234597523, -5.100565746783541e-10, -0.8390600344245331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19742198377982317, -0.052217034807230445, 0.052205742043229766, 0.34051827096207177, 0.2874167485457316, -0.028655683856854998, -0.43195718583346787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19880965289907265, 0.0520768306844828, 0.023235462438279234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005152505839828, 0.1713391455780551, 0.7240261343656306, 0.0, -0.0757735884958979, -0.3213355926797959, -2.9889814816028712, -1.0440263392981617, -1.6783008240333939, -0.10350850760301146, -1.5640162619985774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19755116875234574, 0.48665761041572353, 1.2661729829388388, -0.4710855997270218, -1.9005937735528882, -0.3787027586782937, 0.7798707452587533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.129720437439687, -0.4144030404743032, 0.02505428898970948]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015282171691219392, -0.07034049031500482, 0.12177537113419343, 0.0, -0.09787251900124191, -0.004964462549208628, 0.0643541048347083, 0.018930131302915862, 0.8012956205347723, -1.0386692511734449e-09, -0.9068598407871321, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06069808760496673, 0.03554890910925572, 0.08805796761095572, 0.08971111314407304, 0.31725635202220503, -0.10555161543785882, -0.3908534628127065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917581219985286, 0.034729268027614696, 0.03152241679698409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20065601839622627, 0.16807247951426837, 0.7301320595769725, 0.0, -0.07969648408535791, -0.32176962153628585, -2.986607289663825, -1.0431390960024967, -1.6342489992114075, -0.10350850760306361, -1.6122408329025861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20067328395522496, 0.492400892843251, 1.2716015314676967, -0.47859763667929617, -1.8855827822470475, -0.3876223444709693, 0.7649963838140723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1396650036073466, -0.41338405076823215, 0.026870077922475817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0028153562448687964, -0.06533332127573466, 0.12211850422683904, 0.0, -0.07845791178920039, -0.008680577129799173, 0.04748383878092355, 0.017744865913298997, 0.881036496439728, -1.042922814899149e-12, -0.9644914180801775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062442304057584455, 0.11486564855054912, 0.10857097057715762, -0.1502407390454879, 0.30021982611681386, -0.1783917158535125, -0.29748722889361945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19889132335319332, 0.02037979412142081, 0.036315778655326744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20096542306793036, 0.1654449932387038, 0.7362508424313801, 0.0, -0.08304710453424663, -0.32573663391034274, -2.9837188757965825, -1.0443762733868391, -1.5870075393538325, -0.10521373332923009, -1.662240832902595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2086725093691195, 0.5012186466235822, 1.2773543946865247, -0.496107667472857, -1.874211870670797, -0.3994081790168006, 0.7573401079606881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1494812901559333, -0.4128914605340995, 0.02866861537375455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006188093434081931, -0.0525497255112915, 0.1223756570881518, 0.0, -0.06701240897777443, -0.07934024748113738, 0.05776827734485358, -0.024743547686851254, 0.9448291971514986, -0.034104514523329695, -1.0000000000001805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998450827789035, 0.17635507560662322, 0.1150572643765603, -0.35020061587121726, 0.22741823152500568, -0.2357166909166251, -0.15312551706768568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1963257309717322, 0.009851804682653769, 0.03597074902557463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20152838728931086, 0.16369481209325562, 0.7423906816198869, 0.0, -0.08691864583703286, -0.3314701379428469, -2.9768146445403336, -1.0486542064114133, -1.5393105615783342, -0.11197817370281932, -1.712240832902578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22038123413262947, 0.5120842470988328, 1.282798670935164, -0.5219493598008356, -1.870009977014743, -0.4126385789809851, 0.7601173661938881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158737285299586, -0.41276466205298745, 0.030274916064017]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011259284427610077, -0.035003622908963465, 0.12279678377013534, 0.0, -0.07743082605572461, -0.11467008065008287, 0.13808462512497643, -0.08555866049148067, 0.9539395555099669, -0.13528880747178448, -0.999999999999657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2341744952701998, 0.21731200950501292, 0.1088855249727857, -0.5168338465595709, 0.08403787312108424, -0.2646079992836903, 0.05554516466400122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18511990287305707, 0.0025359696222403425, 0.03212601380524895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20202627967430978, 0.16284106308747984, 0.7485249734313544, 0.0, -0.09344210826657097, -0.33808688780499263, -2.962144595895054, -1.0563212869545757, -1.4949080658849068, -0.1275518286405913, -1.7622408329025676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2350154259370006, 0.5242289585463547, 1.287687448692728, -0.5546227136632432, -1.873673089113286, -0.42613294628406545, 0.7728950815705997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1674067985535097, -0.41296480272338026, 0.031647632194646884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009957847699978529, -0.017074980115515438, 0.12268583622935114, 0.0, -0.1304692485907622, -0.1323349972429145, 0.29340097290509703, -0.15334161086325052, 0.8880499138684388, -0.31147309875544, -0.9999999999997944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.29268383608742216, 0.24289422895043714, 0.09777555515128335, -0.6534670772481537, -0.0732622419708612, -0.2698873460616072, 0.25555430753423225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17339026507847224, -0.004002813407856775, 0.027454322612597743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.202398800107997, 0.16280683147053426, 0.7545672663418745, 0.0, -0.10236052291981554, -0.34514526068085766, -2.938669555357371, -1.066806922522258, -1.4566519388420978, -0.15099873731396388, -1.8122408329025614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2521359232549917, 0.5371313790297202, 1.2922238548942178, -0.5927613967532037, -1.8839800229080845, -0.4391346299700987, 0.794086424033654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1756525480679787, -0.413549951262761, 0.03278605831622804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007450408673744192, -0.0006846323389115214, 0.12084585821040356, 0.0, -0.17836829306489152, -0.141167457517301, 0.4695008107536621, -0.2097127113536453, 0.7651225408561788, -0.4689381734674513, -0.9999999999998763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3424099463598216, 0.2580484096673115, 0.090728124029795, -0.76277366179921, -0.20613867589596885, -0.26003367372066566, 0.42382684926108727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16491499028938097, -0.01170297078761519, 0.022768522431623063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2027163628310531, 0.163548418785463, 0.7604249409633889, 0.0, -0.1129019331978828, -0.34889525657054227, -2.9078895229271913, -1.0783023625548778, -1.4236392592615992, -0.1812568968502859, -1.862240832902567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27156293012603155, 0.5504404420941427, 1.2967143864739177, -0.6352723432251367, -1.8997476245278966, -0.4511342511228243, 0.8224317087991058, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.18355943573368, -0.4145957872726459, 0.03365033610337059]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006351254461121899, 0.014831746298575024, 0.11715349243028593, 0.0, -0.21082820556134538, -0.07499991779359372, 0.6156006486035991, -0.2299088006523955, 0.6602535916099723, -0.6051631907264403, -1.000000000000111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3885401374207975, 0.26618126128844893, 0.08981063159399902, -0.85021892943866, -0.31535203239624304, -0.23999242305451118, 0.5669056953090346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15813775331402652, -0.020916720197697428, 0.01728555574285116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20300062721202383, 0.16503843169782795, 0.7660373673432823, 0.0, -0.12443766154595379, -0.35264525165413685, -2.8712654969834506, -1.0900256812328397, -1.3939445447531358, -0.217290875746959, -1.9122408329024576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29321619565331164, 0.563902471783936, 1.3017963568395874, -0.6812811004027302, -1.920152501583522, -0.46209018873095564, 0.856740237231522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1912604617573923, -0.41613681364612143, 0.0342114464647145]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005685287619414848, 0.029800258247298695, 0.11224852759786824, 0.0, -0.23071456696141968, -0.07499990167189127, 0.7324805188748166, -0.23446637355923902, 0.5938942901692699, -0.7206795779334619, -0.9999999999978096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4330653105456018, 0.2692405937958666, 0.10163940731339415, -0.92017514355187, -0.4080975411125062, -0.21911875216262716, 0.6861705686483266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1540205204742444, -0.030820527469511003, 0.01122220722687825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20327350143028525, 0.16728785758489248, 0.7713944842449668, 0.0, -0.1366453821212773, -0.35264524971890543, -2.829966276228405, -1.1011813700863278, -1.3659979985495936, -0.25811805886428807, -1.9622408329024688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.317005942110701, 0.5772663034002397, 1.3082663081475974, -0.7300881061447986, -1.9449740073709518, -0.4723040399021917, 0.8960526609708361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1988628223791276, -0.4181387944267183, 0.034438861496440466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005457484365228559, 0.04498851774129044, 0.10714233803369108, 0.0, -0.24415441150647035, 3.8704628849139944e-08, 0.8259844151009157, -0.2231137770697607, 0.5589309240708441, -0.8165436623465813, -1.000000000000223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47579492914778665, 0.26727663232607307, 0.12939902616019983, -0.976140114841369, -0.49643011574859736, -0.2042770234247212, 0.786248474786281, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1520472124347034, -0.040039615611937036, 0.004548300634519246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354427407946665, 0.17029590589764237, 0.7765242390469841, 0.0, -0.14957609567993307, -0.3526452497225634, -2.784926899624365, -1.111502092915575, -1.3387330147559335, -0.30277980535815, -2.012240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3425978958829109, 0.59021135720085, 1.3168912697811177, -0.7800881312000915, -1.9743114642801527, -0.4823756353417002, 0.939502599962036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2064712450597492, -0.42048907395168095, 0.0343385347184016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005415452983628351, 0.06016096625499762, 0.10259509604034556, 0.0, -0.25861427117311553, -7.315934072253455e-11, 0.900787532080797, -0.20641445658494453, 0.5452996758732007, -0.8932349298772394, -0.9999999999999883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5118390754441977, 0.258901076012207, 0.17249923267040806, -1.0000005011058573, -0.5867491381840184, -0.20143190879016956, 0.8689987798239975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15216845361243223, -0.047005590499253035, -0.0020065355607773996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20380902679416726, 0.1740250608263596, 0.7814815414939414, 0.0, -0.16345409175240433, -0.35264524972256756, -2.7368953983411313, -1.1210488685706324, -1.3114909002989157, -0.3505092025532365, -2.062240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3694491359183932, 0.6024375144364038, 1.3280363297310942, -0.8300881562554033, -2.008190975646627, -0.49297056126018424, 0.9862625511421699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2141691199585547, -0.4230301045584226, 0.033953799488170976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005295054294012406, 0.07458309857434448, 0.09914604893914625, 0.0, -0.277559921449425, -8.306185477170416e-14, 0.960630025664667, -0.19093551310114656, 0.544842289140358, -0.954587943901729, -0.9999999999999948, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5370248007096454, 0.2445231447110752, 0.22290119899952948, -1.0000005011062378, -0.6775902273294845, -0.2118985183696804, 0.9351990236026778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15395749797610853, -0.05082061213483312, -0.007694704604612444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20405302516662302, 0.17839110823571697, 0.7863344254845989, 0.0, -0.17851430003789928, -0.35264524972255495, -2.686895373285901, -1.1300227185258729, -1.2838256251509144, -0.40050922760850854, -2.112240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3969237492142522, 0.613741097894437, 1.3415486574536832, -0.8800881813106121, -2.0459772709518442, -0.504647076992953, 1.0355802259860223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2220102602948362, -0.4255933560538981, 0.03335268787598558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004879967449115027, 0.0873209481871476, 0.09705767981314739, 0.0, -0.30120416570989883, 2.525265043987572e-13, 1.000000501104607, -0.17947699910481119, 0.5533055029600262, -1.0000005011054416, -0.9999999999999959, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5494922659171806, 0.22607166916066412, 0.2702465544517814, -1.0000005011041742, -0.7557259061043429, -0.23353031465537516, 0.9863534968770462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15682280672562757, -0.05126502990950946, -0.012022232243707826]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20427427775571064, 0.1832657630480131, 0.7911560606975594, 0.0, -0.19402046241882806, -0.3526452497225476, -2.6369255548772657, -1.1381357395602882, -1.2541818029209706, -0.4505092526637864, -2.1622408329024654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4241780894055525, 0.6240109137311005, 1.3565984597849061, -0.9300882063658712, -2.086394358193773, -0.5175612797107543, 1.085580225986022, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2299439964350036, -0.4280393053467843, 0.03261250819647751]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004425051781752245, 0.09749309624592228, 0.09643270425921166, 0.0, -0.3101232476185755, 1.46698788079243e-13, 0.9993963681727096, -0.16226042068830895, 0.5928764445988757, -1.0000005011055564, -0.9999999999999505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5450868038260062, 0.2053963167332707, 0.3009960466244557, -1.0000005011051827, -0.8083417448385756, -0.2582840543560268, 0.9999999999999947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15867472280334796, -0.04891898585772456, -0.014803593590161389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20448925460959733, 0.1884861482941713, 0.7960013837556438, 0.0, -0.20812797112921447, -0.3526452497225536, -2.590735943115225, -1.1442111287049983, -1.2195158208931738, -0.5005092777190392, -2.2122408329024843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4501567220181025, 0.6334540335899963, 1.3712930643842167, -0.9782469378031894, -2.1265963620534154, -0.531072591019149, 1.1355802259860202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2377756105301416, -0.43028076956376143, 0.03180917214483589]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004299537077733934, 0.10440770492316372, 0.09690646116168819, 0.0, -0.28215017420772837, -1.204229784694197e-13, 0.923792235240814, -0.12150778289419997, 0.6933196405559353, -1.0000005011050557, -1.000000000000377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5195726522509989, 0.1888623971779163, 0.29389209198621125, -0.9631746287463633, -0.8040400771928422, -0.2702262261678953, 0.9999999999999597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1566322819027592, -0.04482928433954309, -0.016066721032832413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2047468885177489, 0.19387014210656023, 0.8008866381240283, 0.0, -0.21961803998109392, -0.3521226426517718, -2.5514919148248616, -1.1465010588890092, -1.1798068664050003, -0.5505093027742914, -2.262240832902491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4737450900696767, 0.642079354452608, 1.3843459861892113, -1.0220309843042243, -2.1630376093293977, -0.5443202336407252, 1.1818302260191775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2452004234030019, -0.4322623985728623, 0.031009374273467866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005152678163031458, 0.10767987624777886, 0.09770508736768965, 0.0, -0.2298013770375888, 0.010452141415636393, 0.784880565807272, -0.04579860368021922, 0.794179089763471, -1.0000005011050457, -1.0000000000001337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47176736103148464, 0.17250641725223376, 0.2610584360998941, -0.8756809300207011, -0.7288249455196422, -0.2649528524315232, 0.9250000006631481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14849625745720518, -0.03963258018201765, -0.015995957427360454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2051287495455325, 0.19923065914216656, 0.8057737414679297, 0.0, -0.2281785742138778, -0.35022616837644915, -2.519391471608246, -1.1433405956760947, -1.136039702814632, -0.6005093278295216, -2.3122408329025026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4940033565817461, 0.6497248585809339, 1.3951808982628564, -1.059285479802085, -2.192812112797505, -0.5564281233814546, 1.2207959277732934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2519001603691544, -0.4339526108995303, 0.030265197010617452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007637220555672521, 0.10721034071212654, 0.09774206687802872, 0.0, -0.1712106846556775, 0.03792948550645252, 0.6420088643323169, 0.06320926425829188, 0.8753432718073637, -1.0000005011046043, -1.0000000000002376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4051653302413882, 0.15291008256651703, 0.21669824147290176, -0.7450899099572149, -0.5954900693621484, -0.24215779481458866, 0.7793140350823167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13399473932305103, -0.03380424653335981, -0.014883545257008256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20576022076715375, 0.2043888656870428, 0.8105783890627817, 0.0, -0.2337123229928388, -0.3464879381815168, -2.4940922874295155, -1.1337999009427524, -1.0890259719424475, -0.650509352884751, -2.362240832902516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510514236160238, 0.6564071831994994, 1.403620965527082, -1.0890059379932011, -2.214526068245795, -0.5667107378922177, 1.2507736607049844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2576710963515167, -0.4353477493425074, 0.029610162330812134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012629424432424752, 0.10316413089752449, 0.09609295189704037, 0.0, -0.11067497557922014, 0.07476460389864714, 0.5059836835746102, 0.19081389466684653, 0.9402746174436897, -1.0000005011045867, -1.0000000000002702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33021759156983965, 0.133646492371311, 0.16880134528450907, -0.5944091638223233, -0.43427910896580035, -0.20565229021526063, 0.5995546586338187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11541871964724648, -0.027902768859541856, -0.013100693596106397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064101730111816, 0.20918969614030278, 0.8151985088088208, 0.0, -0.23619468757488218, -0.34091006903492105, -2.475337384198103, -1.1177464421455081, -1.0394149872447274, -0.7005093779400104, -2.412240832902519, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.523403301297924, 0.6622822239167705, 1.4098182069669167, -1.1113813433797564, -2.2283755764191837, -0.5748417513451253, 1.2719013258029221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2624608795377155, -0.43646862893810046, 0.029057378771169932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880557524, 0.09601660906519982, 0.09240239492078313, 0.0, -0.04964729164086727, 0.11155738293191456, 0.375098064628254, 0.3210691759448877, 0.9922196939544017, -1.0000005011051882, -1.0000000000000613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2577813027537198, 0.11750081434542253, 0.1239448287966965, -0.44750810773110444, -0.27699016346777455, -0.16262026905815133, 0.42255330195875485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.095795663723975, -0.022417591911861316, -0.011055671192844046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2070601252552261, 0.2135221305357053, 0.8195134890305069, 0.0, -0.23592775110245523, -0.33388518964591246, -2.462551220837017, -1.0959194558390715, -0.9894149872447394, -0.7505094029952885, -2.4622408329025243, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5333287265246551, 0.667481948193073, 1.4142498397471182, -1.1277963513126714, -2.2360476984196853, -0.5810006042943882, 1.2859313215966783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.266386030912219, -0.4373574993376022, 0.028596672850609083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880889928, 0.08664868790805016, 0.08629960443372142, 0.0, 0.005338729448539366, 0.1404975877801714, 0.25572326722171174, 0.4365397261287322, 0.9999999999997586, -1.0000005011055593, -1.0000000000001035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19850850453462252, 0.10399448552605098, 0.08863265560402797, -0.32830015865830164, -0.1534424400100285, -0.12317705898525709, 0.2805999158751256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07850302749007283, -0.017777407990034997, -0.009214118411216964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20771007749924222, 0.2173234455155467, 0.823412480102414, 0.0, -0.2331721748620815, -0.3259143561449327, -2.4553099141551606, -1.0691483838741687, -0.9394149872447404, -0.8005094280505596, -2.512240832902523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5410462930877361, 0.6720870992422457, 1.4174490504828554, -1.1398783046788483, -2.23955831534367, -0.5855875325806078, 1.2949642850495815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2696122536938677, -0.43805918705077557, 0.028207867985896987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880322287, 0.07602629959682783, 0.0779798214381413, 0.0, 0.05511152480747473, 0.1594166700195956, 0.14482613363713087, 0.5354214392980579, 0.9999999999999802, -1.0000005011054218, -0.9999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15435133126162043, 0.09210302098345298, 0.0639842147147435, -0.2416390673235393, -0.07021233847969158, -0.09173856572439221, 0.18065926905806198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0645244556329731, -0.014033754263467138, -0.007776097294241945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20836002974325324, 0.220580738424814, 0.8268497555052778, 0.0, -0.22776557192265945, -0.3174532650407923, -2.453736299899618, -1.0373651970028064, -0.8894149872447474, -0.8505094531076175, -2.562240832903147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5471275253317054, 0.6760967766719892, 1.419812030834297, -1.1488903227386842, -2.2406049125982195, -0.5889740129652162, 1.3007316657284402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2722569064454363, -0.43861191622931434, 0.02786773997931919]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880220122, 0.06514585818534588, 0.06874550805727751, 0.0, 0.10813205878844129, 0.1692218220828084, 0.03147228511085087, 0.6356637374272478, 0.9999999999998577, -1.0000005011411581, -1.0000000000124751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12162464487938615, 0.08019354859486817, 0.04725960702883106, -0.18024036119671732, -0.020931945090991222, -0.067729607692168, 0.1153476135771768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0528930550313747, -0.011054583570775578, -0.006802560131555889]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20890236731276418, 0.22331947192858484, 0.8299126941352141, 0.0, -0.21963384384261464, -0.3087547466632327, -2.457943386608462, -1.0008838400568223, -0.8394149872448201, -0.9005094781628663, -2.6122408329031273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519614181536695, 0.6795011419163419, 1.4215954927811791, -1.1557017087656305, -2.2403813722918278, -0.5914575442271724, 1.3044574108583427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2744018531044412, -0.43904510173632294, 0.027557092385001702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010846751390218888, 0.05477467007541689, 0.06125877259872422, 0.0, 0.16263456160089598, 0.17397036755119216, -0.08414173417687226, 0.7296271389196829, 0.9999999999985463, -1.0000005011049757, -0.9999999999996081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0966778564392827, 0.06808730488705383, 0.035669238937643385, -0.13622772053892793, 0.004470806127835566, -0.04967062523912445, 0.07451490259804805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04289893318009702, -0.008663710140172066, -0.006212951886349732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924014300176616, 0.22558907526272806, 0.832516028451838, 0.0, -0.2088784119570595, -0.29988190631457157, -2.4679101480898793, -0.9600673236121545, -0.7894149872448852, -0.9505095032181211, -2.6622408329031124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558093246584372, 0.6822883123648255, 1.4229550903934498, -1.1609092407972317, -2.239690744526241, -0.5932717611957165, 1.3069797006688277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2761077168336417, -0.4393805271434575, 0.027263123491609406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006755513780039767, 0.04539206668286434, 0.0520666863324798, 0.0, 0.2151086377111026, 0.17745680697322283, -0.19933522962834466, 0.8163303288933546, 0.9999999999986986, -1.0000005011050965, -0.9999999999997062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07695813009535564, 0.05574340896967034, 0.027191952245415554, -0.10415064063202173, 0.01381255531173049, -0.03628433937087952, 0.050445796209702576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03411727458400836, -0.006708508142691235, -0.00587937786784593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932616161286308, 0.22744569050308344, 0.834826254295132, 0.0, -0.19579154426530776, -0.2908321419076912, -2.483469466430795, -0.9154141104565975, -0.739414987245167, -1.000509528273315, -2.712240832902818, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5588604330257323, 0.6844420565639199, 1.4239877225131137, -1.164969402369256, -2.239103536428652, -0.5946108692553929, 1.3089117387084355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2774277204317501, -0.4396341865431943, 0.02698265280572664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017203722219384116, 0.037132304807107774, 0.04620451686587979, 0.0, 0.2617373538350347, 0.18099528813760773, -0.3111863668183114, 0.8930642631111416, 0.9999999999943651, -1.0000005011038793, -0.9999999999941117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06102216734590005, 0.04307488398188946, 0.020652642393276476, -0.08120323144048687, 0.011744161951782052, -0.0267821611935287, 0.03864076079215309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026400071962168384, -0.005073187994736585, -0.005609413717655272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20933056938417735, 0.228938372466004, 0.8366688095526873, 0.0, -0.18217453223378702, -0.2814297402669101, -2.500887728282853, -0.870306111972243, -0.6931649872445551, -1.0491367343047637, -2.7584908329056668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5612536679267874, 0.6860483734709207, 1.4247430436927009, -1.168155308410831, -2.2387880875171633, -0.595590809248792, 1.3105357742296277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.278425135211993, -0.4398232632180623, 0.02672449963672147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.815542628558227e-05, 0.029853639258411103, 0.03685110515110657, 0.0, 0.2723402406304148, 0.18804803281562182, -0.3483652370411696, 0.9021599696870902, 0.9250000000122373, -0.9725441206289748, -0.9250000000569817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.047864698021103345, 0.032126338140017016, 0.01510642359174525, -0.06371812083149866, 0.006308978229771619, -0.0195987998679837, 0.032480710423844435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01994829560486069, -0.003781533497360421, -0.005163063380103397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932884115003778, 0.23011316550761649, 0.8381225057841533, 0.0, -0.1693528861440909, -0.27255979656795276, -2.518771328661458, -0.8284933281084138, -0.654414987213272, -1.0926411213852207, -2.7972408329494938, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631048045192583, 0.687252723211333, 1.4252317019514358, -1.1706501793212163, -2.2387012797308765, -0.5962762215751217, 1.3119750197448723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2791678862882272, -0.4399629161625189, 0.02649902814853944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.456468279174673e-05, 0.023495860832250186, 0.029073924629319937, 0.0, 0.2564329217939224, 0.17739887397914625, -0.35767200757209533, 0.836255677276582, 0.7750000006256631, -0.8700877416091413, -0.7750000008765425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0370227318494159, 0.024086994808245304, 0.009773165174699198, -0.04989741820770852, 0.001736155725733773, -0.013708246526593065, 0.0287849103048912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014855021524681263, -0.002793058889132289, -0.004509429763640606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932788289126003, 0.23101798821627914, 0.8391026888525631, 0.0, -0.15818501666305668, -0.26483319096932273, -2.5359587088692606, -0.7937257558710759, -0.6250680896836437, -1.1277424437604398, -2.8260974817958933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564512246192544, 0.6882110000970189, 1.4254194277410992, -1.172594032649529, -2.2387410078804804, -0.5966909778580843, 1.3133183993931452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2797159619590375, -0.4400654543891233, 0.026310697312253172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9165175554961214e-05, 0.018096454173253205, 0.0196036613681976, 0.0, 0.22335738962068408, 0.15453211197260083, -0.34374760415605077, 0.6953514447467598, 0.5869379505925651, -0.7020264475043795, -0.5771329769279895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02814883346571545, 0.01916553771371786, 0.0037545157932705603, -0.0388770665662527, -0.0007945629920774432, -0.008295125659251692, 0.02686759296545663, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010961513416206263, -0.002050764532088299, -0.003766616725725312]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209326967977962, 0.23170153162576393, 0.8397180196333647, 0.0, -0.14905358832275853, -0.25852071302748747, -2.5515493738647765, -0.7668782370757354, -0.6040801048930344, -1.1540211237438165, -2.8459557199745085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5655600193084604, 0.6890612677378614, 1.4252544891234067, -1.1741005473302502, -2.2388086006669075, -0.5968383061702716, 1.3146469020890874, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2801180324457406, -0.44014044847222306, 0.0261579683581745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.829826596068004e-05, 0.013670868189695779, 0.01230661561603071, 0.0, 0.1826285668059628, 0.12624955883670494, -0.31181329991032136, 0.5369503759068073, 0.4197596958121855, -0.5255735996675329, -0.397164763572303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02095546231832748, 0.01700535281684921, -0.003298772353851691, -0.030130293614425267, -0.001351855728544265, -0.002946566243744073, 0.02657005391884625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008041409734061587, -0.001499881661994671, -0.003054579081573399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093259380204269, 0.23220977394247713, 0.8400854275917896, 0.0, -0.14197612515217423, -0.2536482214865198, -2.564986775067951, -0.7473180611300209, -0.5895743811466219, -1.1724845390217244, -2.858801959448876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663198497966578, 0.6899025586887599, 1.424707731640309, -1.1752628476276366, -2.2388339068055143, -0.5967248652769541, 1.3160195454508985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2804118817113503, -0.440195155718598, 0.02603609857431136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0599150701613132e-05, 0.010164846334263896, 0.007348159168498353, 0.0, 0.14154926341168605, 0.09744983081935366, -0.2687480240634872, 0.39120351891429056, 0.29011447492825215, -0.36926830555815804, -0.2569247894873526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015196609763948796, 0.016825819017970946, -0.010935149661955473, -0.023246005947725922, -0.0005061227721400406, 0.0022688178663480153, 0.027452867236222957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005876985312195564, -0.0010941449274996567, -0.002437395677262807]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932478082939882, 0.23258303632233118, 0.8403182736213654, 0.0, -0.13673976621698192, -0.25009048605629397, -2.5760634691920976, -0.7338035035911181, -0.5797348308047431, -1.1846861181123198, -2.8666674562661716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5668496073376568, 0.690808718640863, 1.423754695329556, -1.176157114405769, -2.2387707525162717, -0.5963535131611295, 1.3174903452101003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2806261112024597, -0.4402349952513054, 0.02593967049718884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.314382056186457e-05, 0.007465247597081032, 0.004656920591515499, 0.0, 0.10472717870384635, 0.07115470860451609, -0.22153388248293018, 0.2702911507780543, 0.19679100683757533, -0.24403158181190557, -0.1573099363459114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010595150819977833, 0.018123199042062353, -0.019060726215059675, -0.017885335562650054, 0.001263085784849995, 0.007427042316493482, 0.02941599518403489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004284589822188753, -0.0007967906541475968, -0.00192856154245041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932339724114024, 0.2328547249447787, 0.8404844977878413, 0.0, -0.13302175330080057, -0.2476419798401231, -2.5848497946527678, -0.7249578381638652, -0.5731054595349542, -1.1922294288601571, -2.8712263686173403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5671915980120815, 0.6918542953571599, 1.4223367074189475, -1.1768459124727995, -2.2385826009709686, -0.5957045777303653, 1.3191371386595554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2807820429389665, -0.440263974177527, 0.025863793622816735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.76717651716686e-05, 0.0054337724489508295, 0.003324483329518648, 0.0, 0.0743602583236267, 0.048970124323417547, -0.17572650921339994, 0.17691330854505882, 0.13258742539577828, -0.1508662149567478, -0.09117824702337414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006839813488494819, 0.020911534325937276, -0.028359758212169114, -0.013775961340610206, 0.0037630309060581193, 0.012978708615283687, 0.03293586898910326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003118634730133735, -0.000579578524432414, -0.001517537487442093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932160909258068, 0.2330513790842077, 0.840695975766972, 0.0, -0.1304781107382692, -0.24608019902554626, -2.5915906810501066, -0.7195101586413297, -0.5686273915797048, -1.1965227031409893, -2.873712065986655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5673716881041702, 0.6931383151733975, 1.420324885976035, -1.1773812592468422, -2.2382285951112917, -0.5947182660780783, 1.321087474954143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2808954222641762, -0.44028503700835714, 0.025804395699238862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.576297119099514e-05, 0.003933082788579588, 0.004229559582612759, 0.0, 0.05087285125062718, 0.031235616291536917, -0.1348177279467748, 0.1089535904507085, 0.08956135910498746, -0.08586548561664105, -0.04971394738629807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003601801841772482, 0.02568039632475126, -0.0402364288582501, -0.01070693548085521, 0.007080117193534543, 0.019726233045739956, 0.03900672589175434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022675865041934746, -0.000421256616602761, -0.0011879584715574895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931920301568352, 0.2331934293386948, 0.8408585872212334, 0.0, -0.12879737342821995, -0.245203650165338, -2.5966091754426435, -0.7164018528654865, -0.5655782245461377, -1.198687194199383, -2.8749662449540203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56739952898861, 0.6947976467255678, 1.417501623225868, -1.1778071478137369, -2.2376551247952263, -0.5932859412217962, 1.3235316849239758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.280977805635369, -0.4403003384623748, 0.025758135598587646]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.812153794340694e-05, 0.0028410050897417867, 0.0032522290852278627, 0.0, 0.03361474620098516, 0.017530977204165292, -0.10036988785073828, 0.0621661155168642, 0.06098334067134223, -0.04328982116787521, -0.02508357934730481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005568176887978771, 0.033186631043404066, -0.056465255003339654, -0.008517771337891071, 0.011469406321307846, 0.02864649712564206, 0.04888419939665492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016476674238530644, -0.0003060290803538771, -0.0009252020130243051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931618104453162, 0.23329626311703922, 0.8409724071782145, 0.0, -0.12772312341066705, -0.24481395712687198, -2.6002446659971485, -0.7148146095129365, -0.5634795661829842, -1.199550618643628, -2.875531087473784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5672778537988058, 0.6969542188524047, 1.4136642286778873, -1.1781593437099984, -2.2368185258139257, -0.5913055409781842, 1.3266454613493943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810376429208725, -0.44031145120516274, 0.02572219668437234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0439423038208124e-05, 0.002056675566888427, 0.002276399139622121, 0.0, 0.021485000351057923, 0.007793860769319941, -0.07270981109009911, 0.03174486705099942, 0.041973167263069225, -0.01726848888489693, -0.011296850395268064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024335037960834314, 0.04313144253673796, -0.07674789095961343, -0.007043917925231801, 0.016731979626013978, 0.03960800487223917, 0.06227552850837193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011967457100707489, -0.00022225485575790908, -0.0007187782843061262]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093132596300379, 0.2333713576137685, 0.8411024824889938, 0.0, -0.12705684411839407, -0.2447149090405895, -2.602818979415272, -0.7141544056546724, -0.5620128669998177, -1.199683608494942, -2.8757399307150244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5670300950976542, 0.6995436439667067, 1.4089507589655348, -1.1784599753817526, -2.2357609555553686, -0.5888537791612296, 1.3303470237452841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810810937432404, -0.4403195204187482, 0.0256940742681744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.842828987430867e-05, 0.0015018899345859969, 0.0026015062155844244, 0.0, 0.013325585845459686, 0.00198096172564936, -0.0514862683624715, 0.013204077165283132, 0.029333983663330492, -0.002659797026282086, -0.004176864824815902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004955174023030489, 0.05178850228603931, -0.09426939424704964, -0.0060126334350839375, 0.021151405171141162, 0.04903523633909185, 0.07403124791779794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008690164473574144, -0.00016138427170990318, -0.0005624483239587907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931107145574457, 0.23342725960843494, 0.8412299048084414, 0.0, -0.1266536488275151, -0.24475560750623362, -2.6046089182401073, -0.71401434648281, -0.56096890190329, -1.1994554876513186, -2.875785908046203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5667027024736216, 0.7023252529122656, 1.4038254173463194, -1.1787187226710483, -2.234602608355407, -0.5861785294179096, 1.334307758548752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811126383451363, -0.44032537855362475, 0.02567146062408601]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3763485867001316e-05, 0.001118039893328548, 0.002548446388953234, 0.0, 0.008063905817579597, -0.0008139693128823918, -0.035798776496701455, 0.002801183437245544, 0.020879301930553273, 0.004562416872467299, -0.0009195466235717882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006547852480650781, 0.05563217891117837, -0.10250683238430679, -0.005174945785914244, 0.023166943999231908, 0.053504994866400785, 0.07921469606935587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006308920379176483, -0.00011716269753029164, -0.0004522728817677998]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093095357777038, 0.23347030733254687, 0.8413333933949931, 0.0, -0.12641317592168402, -0.2448425633689893, -2.6058359713905936, -0.7141318406218842, -0.5602121250904676, -1.1990895838369133, -2.8757726831399966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663405076834858, 0.7050641520890193, 1.398739313522182, -1.1789408532348258, -2.23345759570976, -0.5835200154982266, 1.3382051322199189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281135535361113, -0.44032963089928073, 0.02565226245036766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0713560815450024e-05, 0.0008609544822384934, 0.002069771731034684, 0.0, 0.00480945811662164, -0.001739117255113497, -0.024541063009727, -0.0023498827814825117, 0.015135536256447077, 0.007318076288105374, 0.0002644981241333316, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007243895802718277, 0.0547779835350745, -0.10172207648274745, -0.004442611275548488, 0.022900252912939713, 0.05317027839365999, 0.07794747342334042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00045794031953013753, -8.504691312025128e-05, -0.0003839634743670364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093083863401872, 0.23350509051701604, 0.8413646252815028, 0.0, -0.12626914210007656, -0.2449286003817336, -2.606668321483937, -0.7143485456589677, -0.5596551025701284, -1.1987097357395833, -2.875750105900365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.565974677304888, 0.7076153731996925, 1.393973547800686, -1.1791313171364814, -2.2323958449919328, -0.5810281181019368, 1.3418399661678189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811521534988537, -0.4403327173759992, 0.025634732928234014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2988750332211854e-05, 0.0006956636893833827, 0.0006246377301939144, 0.0, 0.0028806764321491277, -0.001720740254886341, -0.016647001866865102, -0.004334100741669422, 0.011140450406784304, 0.007596961946602426, 0.0004515447926331461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007316607571954944, 0.051024422213464565, -0.09531531442991814, -0.0038092780331124413, 0.021235014356552527, 0.049837947925796156, 0.07269667895799907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000332362754814236, -6.172953436950594e-05, -0.0003505904426728646]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093074345213319, 0.23353476076684745, 0.8413867836530399, 0.0, -0.12617978319897336, -0.2449968772106131, -2.6072287718098015, -0.714577054554873, -0.559240923775451, -1.1983759739779265, -2.8757378530791198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5656226078371608, 0.7099212289243557, 1.3896443520739996, -1.1792953816447265, -2.2314451351174696, -0.5787651709376522, 1.345133091682759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811642136478232, -0.4403349575490008, 0.02561761009628726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9036377105635495e-05, 0.0005934049966281783, 0.000443167430740441, 0.0, 0.0017871780220643492, -0.0013655365775899187, -0.011209006517291896, -0.0045701779181072716, 0.008283575893547793, 0.006675235233133516, 0.00024505642489917266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007041389354544094, 0.0461171144932648, -0.08658391453372918, -0.003281290164901044, 0.01901419748926482, 0.045258943285691154, 0.06586251029880365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002412029793911311, -4.480346003190916e-05, -0.0003424566389351333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930656804015205, 0.23356129882315158, 0.8413701620718517, 0.0, -0.12612001251429453, -0.24504422559840863, -2.607604653229138, -0.7147753717799153, -0.5589313399745239, -1.1981100556589004, -2.8757403173484275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5652913274534491, 0.7119836069201142, 1.385754835100013, -1.1794382729338133, -2.2306047665306026, -0.5767333927952603, 1.3480873651022844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281172965508997, -0.440336583464336, 0.025600174956988263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7329623597052658e-05, 0.0005307611260826335, -0.00033243162376509416, 0.0, 0.0011954136935767837, -0.0009469677559102456, -0.007517628386735238, -0.003966344500848236, 0.006191676018541968, 0.005318366380524382, -4.928538615713067e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006625607674232605, 0.04124755991517044, -0.077790339479733, -0.0028578257817353727, 0.01680737173734279, 0.040635562847839264, 0.059085468390505325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017503722347327722, -3.2518306703991607e-05, -0.00034870278597991196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930571697289413, 0.23358578927657528, 0.8413301762265463, 0.0, -0.1260756570374459, -0.24507464315984007, -2.6078564227091303, -0.7149285725174833, -0.5586999459037346, -1.1979128602868756, -2.8757551078398103, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5649807970422012, 0.7138384212270887, 1.3822426312907556, -1.1795648525660125, -2.229858153091005, -0.5749001873910619, 1.3507527457911412, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811793163762348, -0.4403377635721811, 0.02558220222703967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.702134515844646e-05, 0.0004898090684743421, -0.000799716906108358, 0.0, 0.0008871095369727812, -0.0006083512286286783, -0.0050353895998431234, -0.0030640147513591332, 0.004627881415787143, 0.003943907440495759, -0.0002958098276514625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006210608224958936, 0.03709628613948982, -0.07024407618514973, -0.0025315926439827795, 0.014932268791951654, 0.036664108083967424, 0.05330761377713449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001270173447574517, -2.360215690101155e-05, -0.00035945459897185014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093048289687132, 0.23360869936906162, 0.8412687929570802, 0.0, -0.12603921694238535, -0.24509250940629626, -2.6080254533918, -0.7150364279503766, -0.5585275030750284, -1.197775332567186, -2.8757778356522703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5646863279103231, 0.7155384116720686, 1.3790120388227531, -1.1796795240936315, -2.229181352658341, -0.5732152525497688, 1.3532028827256402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811839248259298, -0.44033862013547376, 0.02556383189244487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7760083618687023e-05, 0.0004582018497266741, -0.0012276653893209275, 0.0, 0.0007288019012108107, -0.00035732492912375895, -0.0033806136533930773, -0.0021571086578656457, 0.00344885657412393, 0.002750554393789047, -0.00045455624919883757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005889382637561511, 0.03399980889959524, -0.06461184936005213, -0.002293430552380959, 0.013536008653279674, 0.033698696825861935, 0.04900273868997617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.216899389749787e-05, -1.713126585362548e-05, -0.0003674066918959724]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093038618960449, 0.23363013314251516, 0.8412021612596656, 0.0, -0.12600711441060672, -0.24510213748602921, -2.6081395104400515, -0.7151055316030717, -0.5583997009662818, -1.1976850765639133, -2.8758042432433197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5644002197876236, 0.7171431776920782, 1.3759527757440497, -1.1797862949051272, -2.228548011012204, -0.571620595983273, 1.3555215766006095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811872688471595, -0.44033924188535506, 0.02554541065054421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9341453365596536e-05, 0.00042867546907065216, -0.0013326339482925987, 0.0, 0.0006420506355724892, -0.00019256159465898116, -0.0022811409650317937, -0.00138207305390175, 0.0025560421749317797, 0.0018051200654563017, -0.0005281518209890811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005722162453991348, 0.03209532040019296, -0.06118526157406873, -0.002135416229915026, 0.01266683292273626, 0.03189313132991613, 0.04637387749938665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.688042459223199e-05, -1.243499762654782e-05, -0.0003684248380132118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930277955712914, 0.23365003479002197, 0.841142355991144, 0.0, -0.12597786919762735, -0.2451067040304369, -2.608217050437533, -0.7151446630045013, -0.5583056253473476, -1.1976298647099906, -2.875831082964572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564112916098539, 0.718713631945134, 1.3729505868607748, -1.1798888818872901, -2.227932048589906, -0.5700562098209019, 1.3577952065121577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811896953317157, -0.44033969321508903, 0.025527345973332755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1646778315541915e-05, 0.0003980329501363525, -0.0011961053704323751, 0.0, 0.0005849042595874469, -9.133088815418519e-05, -0.0015507999496303946, -0.0007826280285938342, 0.001881512378682125, 0.0011042370784556759, -0.0005367944250410268, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005746073781690693, 0.03140908506111582, -0.06004377766550069, -0.002051739643259896, 0.012319248445959628, 0.03128772324742158, 0.04547259823096527, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.852969112507101e-05, -9.026594679226684e-06, -0.0003612935442291047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930155521577734, 0.23366833009605906, 0.841094961488964, 0.0, -0.12595099681958702, -0.24510830575426978, -2.608270244854492, -0.7151623127094201, -0.5582368711318413, -1.1975992576938694, -2.8758562656040474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5638140257817605, 0.7203079847006745, 1.369895085563649, -1.1799907533268417, -2.227309439495549, -0.5684642412888999, 1.360107104727664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281191456016363, -0.440340020855898, 0.02550999675993775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4486827036107972e-05, 0.0003659061207415492, -0.0009478900435981089, 0.0, 0.0005374475608064811, -3.203447665762285e-05, -0.0010638883391749958, -0.0003529940983749414, 0.0013750843101261174, 0.0006121403224216934, -0.0005036527895113157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0059778063355689585, 0.03188705511080903, -0.061110025942516716, -0.0020374287910290695, 0.012452181887139795, 0.03183937064003895, 0.046237964310127326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.521369294633575e-05, -6.552816180006944e-06, -0.0003469842679000255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930018081720683, 0.23368500968621683, 0.8410609628302775, 0.0, -0.125926388040214, -0.24510836130916702, -2.6083070567133824, -0.7151655660674753, -0.5581869933210988, -1.1975851125906631, -2.875878686583119, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.563493591706401, 0.7219767244682881, 1.3666896025534783, -1.18009501357608, -2.226660223367573, -0.5667941725697253, 1.3625303249008929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811927335841258, -0.44034025872312105, 0.025493606580810426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7487971409974618e-05, 0.00033359180315545664, -0.0006799731737292077, 0.0, 0.0004921755874602552, -1.1110979447739581e-06, -0.0007362371778133676, -6.506716110269497e-05, 0.0009975562148499739, 0.0002829020641273661, -0.0004484195814282261, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006408681507189875, 0.033374795352271634, -0.06410966020341216, -0.002085204984763627, 0.012984322559509329, 0.033401374383493235, 0.04846440346457676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5551355253924737e-05, -4.757344460149128e-06, -0.00032780358254653704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929867884331144, 0.2337001652461733, 0.8410398000736337, 0.0, -0.1259039816055719, -0.24510771241587442, -2.608332691702937, -0.7151597804444204, -0.5581510785125475, -1.1975814871566215, -2.875897971265622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631438560880656, 0.7237552448328658, 1.3632656213457324, -1.180204082582403, -2.225971326545408, -0.5650103653121799, 1.365116883684307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281193660600752, -0.4403404314317798, 0.025478275340491713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0039477908181726e-05, 0.00030311119912921383, -0.00042325513287815654, 0.0, 0.0004481286928418511, 1.2977865851722881e-05, -0.0005126997910942445, 0.00011571246109806768, 0.0007182961710260918, 7.250868083288599e-05, -0.0003856936500588376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006994712366707671, 0.03557040729155468, -0.0684796241549184, -0.002181380126459792, 0.013777936443305007, 0.03567614515090822, 0.051731175668285306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8540332523773255e-05, -3.4541731755088937e-06, -0.00030662480637424854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092971066962968, 0.23371399345663038, 0.8410315183894932, 0.0, -0.12588360240755486, -0.24510639356105499, -2.6083506489147124, -0.7151486795474746, -0.5581253344249605, -1.1975842653907938, -2.875914255468676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5627612462555937, 0.7256557504430601, 1.3595986979929144, -1.180319265356326, -2.225239514424052, -0.5631003451914094, 1.3678858125913502, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811943332514166, -0.44034055684806567, 0.025463959270514265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.144294029240099e-05, 0.000276564209141811, -0.0001656336828101733, 0.0, 0.00040758396034068956, 2.6377096388984554e-05, -0.00035914423550959505, 0.00022201793891585123, 0.0005148817517415824, -5.55646834436625e-05, -0.0003256840610755665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007652196649439385, 0.03801011220388612, -0.07333846705635926, -0.0023036554784603078, 0.014636242427122956, 0.03820040241540994, 0.055378578140861626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3453013296197203e-05, -2.508325717375635e-06, -0.000286321399548956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929554240381656, 0.23372677844954556, 0.8410309175430131, 0.0, -0.12586495439624742, -0.24510451324511714, -2.608363229770946, -0.715134626654381, -0.5581069586289285, -1.1975907620666153, -2.875927934791054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5623475532949853, 0.7276636348005215, 1.355715874881219, -1.1804404942998248, -2.2244724050053057, -0.5610786053208363, 1.3708175312484436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811948213291113, -0.4403406479415184, 0.025450491256586823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.128584960460454e-05, 0.0002556998583034697, -1.2016929603494417e-05, 0.0, 0.00037296022614867746, 3.7606318756892435e-05, -0.0002516171246731703, 0.00028105786187182383, 0.00036751592064140806, -0.00012993351642981148, -0.00027358644755902454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008273859212166279, 0.040157687149229564, -0.07765646223390661, -0.002424578869977944, 0.015342188374920577, 0.040434797411462116, 0.05863437314186746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.7615538926286e-06, -1.8218690544552197e-06, -0.00026936027854881727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209294053398125, 0.23373885868698788, 0.8410335748135789, 0.0, -0.12584763873052435, -0.24510210272088584, -2.6083719747967073, -0.7151189612611795, -0.558093895091273, -1.197599327374643, -2.8759395243000445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.561909294418856, 0.7297428023174414, 1.3516858663276905, -1.1805665121830295, -2.2236858833252864, -0.5589813906049087, 1.3738611251068245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195175474863, -0.4403407141278588, 0.025437617055845567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9780113831033408e-05, 0.00024160474884648138, 5.314541131553214e-05, 0.0, 0.00034631331446133593, 4.821048462616556e-05, -0.00017490051522889565, 0.00031330786403151347, 0.0002612707531080156, -0.00017130616055594606, -0.00023179017981265172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008765177522586246, 0.041583350338396, -0.080600171070569, -0.0025203576640966487, 0.01573043360038643, 0.04194429431855181, 0.060871877167615614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.082915030469657e-06, -1.3237268083657956e-06, -0.0002574840148251435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929267402278356, 0.23375058401338336, 0.8410368464974026, 0.0, -0.1258312071972287, -0.24509912738008263, -2.608377934289759, -0.7151023257509268, -0.5580846474444042, -1.1976090235471704, -2.8759495580003933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5614554637779701, 0.7318480731070073, 1.3475954379145076, -1.180695442257408, -2.222898841005886, -0.5568542851154894, 1.3769520004783893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195432432936, -0.4403407622430411, 0.0254250422090177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7587506829197594e-05, 0.00023450652790980332, 6.543367647447401e-05, 0.0, 0.0003286306659130794, 5.9506816063916064e-05, -0.00011918986102826232, 0.0003327102050529317, 0.00018495293737567448, -0.00019392345054728718, -0.00020067400697726577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009076612817717112, 0.04210541579131824, -0.08180856826365653, -0.0025786014875700805, 0.015740846388008323, 0.04254210978838492, 0.06181750743129771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.139161459139613e-06, -9.623036454801814e-07, -0.0002514969365572958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929140492578405, 0.23376226979364867, 0.8410366838434314, 0.0, -0.1258152304891205, -0.24509561131307556, -2.6083818247290775, -0.7150849474311873, -0.5580781479145169, -1.1976193739597198, -2.875958516984219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5609949280913906, 0.7339380409830827, 1.3435246690204103, -1.180825424830752, -2.22212797938815, -0.5547392558008276, 1.380030415191857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811956188667661, -0.44034079724974484, 0.025412482780436875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.538193999048871e-05, 0.00023371560530605358, -3.2530794247178512e-06, 0.0, 0.0003195341621644069, 7.032134014142217e-05, -7.78087863706458e-05, 0.0003475663947893592, 0.00012999059774529547, -0.00020700825098755003, -0.0001791796765088974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009210713731589496, 0.04179935752150859, -0.08141537788194497, -0.002599651466876533, 0.015417232354719007, 0.042300586293236575, 0.06156829426935478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7286766039075745e-06, -7.001340752734186e-07, -0.0002511885716165004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929022605121414, 0.23377415724123438, 0.8410354043712006, 0.0, -0.12579936807991787, -0.245091880159618, -2.6083840897483874, -0.7150668577609607, -0.55807369540577, -1.197630180755887, -2.8759667720472466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5605345511860355, 0.7359832897091294, 1.3395309574510912, -1.1809550542929945, -2.2213846728043958, -0.552666304106167, 1.3830534858866987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811957541294259, -0.44034082274968717, 0.025399710587983983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3577491398254557e-05, 0.000237748951714319, -2.5589444615739494e-05, 0.0, 0.0003172481840523629, 7.462306915097544e-05, -4.5300386200787526e-05, 0.00036179340453244813, 8.905017493845235e-05, -0.00021613592333979306, -0.0001651012605533446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009207538107104077, 0.040904974520935396, -0.07987423138638482, -0.002592589244853728, 0.01486613167508669, 0.04145903389321194, 0.06046141389683468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7052531964609267e-06, -5.099988465446153e-07, -0.00025544384905784367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092891087142332, 0.2337863889700238, 0.8410360082603573, 0.0, -0.12578335826999573, -0.24508741702397602, -2.6083851827022246, -0.715048050955997, -0.5580706532528865, -1.1976413418152407, -2.8759746453116835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5600783519138955, 0.7379690563802977, 1.3356436247608887, -1.1810835571516842, -2.2206741594981336, -0.5506506833394155, 1.3859992698826669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811958522663727, -0.4403408413557531, 0.025386583483815072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2346739618580776e-05, 0.0002446345757885683, 1.207778313352136e-05, 0.0, 0.0003201961984425355, 8.926271283950733e-05, -2.18590767437206e-05, 0.0003761360992743255, 6.084305766997865e-05, -0.00022322118707697718, -0.00015746528873960834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009123985442799153, 0.03971533342336723, -0.07774665380405146, -0.002570057173793344, 0.014210266125241882, 0.04031241533503041, 0.058915679919361294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9627389349568807e-06, -3.721213176678822e-07, -0.0002625420833782228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928802517115022, 0.23379900514934923, 0.8410349328638245, 0.0, -0.125767081482586, -0.24508231676848866, -2.6083853909718746, -0.7150285610661412, -0.5580686155401812, -1.1976528125791381, -2.8759823294466824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5596274722157201, 0.7398939844199924, 1.3318660572606382, -1.1812107802490412, -2.219996308616668, -0.5486940638167193, 1.3888652079976598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959234561143, -0.4403408549627982, 0.025373054806792944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1670861659835338e-05, 0.00025232358650895104, -2.1507930657501184e-05, 0.0, 0.00032553574819482414, 0.00010200510974724494, -4.1653930017752455e-06, 0.0003897977971152688, 4.075425410771976e-05, -0.0002294152779486388, -0.0001536826999770408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00901759396351018, 0.038498560793894, -0.07555135000501167, -0.002544461947141193, 0.013557017629314352, 0.03913239045392443, 0.05731876229985881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4237948324154929e-06, -2.721409020453415e-07, -0.00027057354044257597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928695084797927, 0.2338119584573455, 0.8410321159752371, 0.0, -0.12575052771739645, -0.2450766126830368, -2.6083849522399776, -0.7150084945107471, -0.558067272264523, -1.1976645422434569, -2.875989934475641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5591806119876536, 0.7417669828489495, 1.3281815578917626, -1.181337083108363, -2.219347098584525, -0.5467876350123405, 1.3916637907816496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959750864783, -0.4403408649438677, 0.025359163293032172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.148646341928201e-05, 0.00025906615992544573, -5.6337771747108655e-05, 0.0, 0.00033107530379099525, 0.00011408170903712871, 8.774637939968811e-06, 0.0004013311078828809, 2.6865513162621074e-05, -0.00023459328637668916, -0.0001521005791680687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00893720456133019, 0.03745996857914207, -0.07368998737751273, -0.002526057186434127, 0.012984200642861312, 0.038128576087575396, 0.05597165567979601, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.032607281879432e-06, -1.9962139030758776e-07, -0.000277830275215461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928586632714155, 0.23382514213019298, 0.8410281279171928, 0.0, -0.1257337701212526, -0.245070380155813, -2.608384056205543, -0.7149880199197897, -0.5580663940860073, -1.1976764629807153, -2.875997503976249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5587346767482065, 0.7436035660074914, 1.3245602911608023, -1.1814631941859728, -2.218720221675862, -0.5449157679568635, 1.3944173987513842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196012518856, -0.4403408722934107, 0.02534500869895688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.169041675451192e-05, 0.0002636734569495852, -7.976116088462764e-05, 0.0, 0.000335151922876737, 0.00012465054447576959, 1.7920688690471714e-05, 0.0004094918191487047, 1.756357031465416e-05, -0.000238414745170206, -0.0001513900121642371, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008918704788940066, 0.036731663170838695, -0.07242533461920501, -0.0025222215521966854, 0.012537538173262038, 0.03743734110954007, 0.05507215939469092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.486475535157642e-07, -1.4699085936223667e-07, -0.0002830918815058249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928475816571282, 0.23383842289331924, 0.8410237772334282, 0.0, -0.12571693075540719, -0.24506380536438543, -2.6083828393500443, -0.7149673371095181, -0.5580658266392596, -1.1976884972615673, -2.876005033477747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5582855023094606, 0.7454223285409701, 1.320966063736913, -1.1815900579661462, -2.2181085407857957, -0.5430595762208513, 1.397153250655472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960396432749, -0.4403408777315123, 0.025330721100861507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2163228574663497e-05, 0.00026561526252498984, -8.701367529104261e-05, 0.0, 0.00033678731690860153, 0.00013149582855127422, 2.4337109971788726e-05, 0.0004136562054321969, 1.134893495327528e-05, -0.00024068561703942797, -0.00015059002995320076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008983488774919038, 0.03637525066957294, -0.07188454847778691, -0.002537275603468942, 0.012233617801327062, 0.03712383472024385, 0.05471703808175564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.424883800536471e-07, -1.0876203281328585e-07, -0.00028575196190749576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928361962021858, 0.233851671975343, 0.8410200329115725, 0.0, -0.12570014481308564, -0.24505718307812926, -2.608381384654628, -0.714946639975147, -0.5580654824178932, -1.19770057133443, -2.87601249037681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5578285987012843, 0.7472417640137283, 1.317362530804653, -1.1817186799421848, -2.217505315958886, -0.5412001596216567, 1.3998987606241629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960592890377, -0.4403408817798127, 0.025316430660225216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2770909884935263e-05, 0.00026498164047559765, -7.488643711521706e-05, 0.0, 0.0003357188464307567, 0.00013244572512316, 2.909390832013645e-05, 0.0004139426874227912, 6.884427328987225e-06, -0.0002414814572513849, -0.00014913798126398273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00913807216352482, 0.036388709455163676, -0.07207065864519666, -0.0025724395207737606, 0.012064496538201786, 0.037188331983892126, 0.054910199373815416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9291525549217034e-07, -8.096600676193637e-08, -0.0002858088127258603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928245108894183, 0.23386478804542368, 0.8410174650185066, 0.0, -0.125683527186835, -0.24505075403237622, -2.6083797446478076, -0.7149260860247941, -0.55806531127179, -1.1977126232930966, -2.876019838179076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.557359873636548, 0.7490775025074466, 1.31371866460612, -1.181849972036363, -2.216905181731572, -0.5393214456994128, 1.402677423283606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960735113084, -0.4403408848165188, 0.025302244240532755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3370625534722936e-05, 0.0002623214016136919, -5.135786131682776e-05, 0.0, 0.000332352525012723, 0.00012858091506071477, 3.280013641051642e-05, 0.0004110790070570588, 3.4229220628398828e-06, -0.000241039173333795, -0.0001469560453180969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00937450129472489, 0.03671476987436629, -0.07287732397065966, -0.0026258418835635637, 0.01200268454627503, 0.03757427844487955, 0.05557325318886109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.844454131390296e-07, -6.07341217716913e-08, -0.0002837283938491854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928125975254663, 0.2338777108130339, 0.8410158630732162, 0.0, -0.1256671439747314, -0.24504447219903447, -2.608377986471098, -0.7149057769458779, -0.5580652503388998, -1.1977246030067663, -2.876027063526532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5568762726491504, 0.7509401348519842, 1.3100131355736913, -1.181984612037136, -2.2163048343526506, -0.5374124503813171, 1.4055054932543025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196083799387, -0.44034088711628594, 0.02528823051558007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3826727904008558e-05, 0.0002584553522042788, -3.203890580907234e-05, 0.0, 0.000327664242072245, 0.00012563666683489575, 3.516353418872416e-05, 0.0004061815783248623, 1.2186578059567068e-06, -0.0002395942733952444, -0.00014450694912265818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009672019747952372, 0.03725264689075036, -0.07411058064857856, -0.002692800015456993, 0.012006947578431529, 0.0381799063619132, 0.056561399413934295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0576157060140677e-07, -4.5995343059355314e-08, -0.0002802744990537038]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928005822107565, 0.23389042542853103, 0.8410148861598132, 0.0, -0.1256510139598323, -0.24503832647630847, -2.608376152939475, -0.7148857485231586, -0.5580652620672273, -1.1977364858353845, -2.8760341665429783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5563762310020239, 0.7528339407988729, 1.3062369547787211, -1.182122942229882, -2.2157033441213, -0.535468624793998, 1.4083899574042051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960912332747, -0.4403408888790849, 0.02527441387595175]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4030629419687853e-05, 0.0002542923099423783, -1.953826805875379e-05, 0.0, 0.00032260029798148945, 0.00012291445452000235, 3.667063245698228e-05, 0.00040056845438629304, -2.3456654998743283e-07, -0.0002376565723656537, -0.00014206032892117383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010000832942529793, 0.037876118937773505, -0.07552361589940103, -0.002766603854918861, 0.012029804627013495, 0.038876511746381424, 0.057689282998053766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.486777525501345e-07, -3.525597893159262e-08, -0.00027633279256637983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927886130024168, 0.2339029581009885, 0.8410143843772253, 0.0, -0.12563511083264114, -0.2450323182141585, -2.6083742664359377, -0.7148659747237618, -0.5580653290243688, -1.1977482722593595, -2.876041161779588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558598237937736, 0.7547568426705952, 1.3023937086428552, -1.182264935247827, -2.21510201780957, -0.5334919482142477, 1.4113283165359392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960965966573, -0.4403408902509209, 0.025260777130170713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.393841667927272e-05, 0.0002506534491489933, -1.0035651758644546e-05, 0.0, 0.0003180625438231048, 0.00012016524299924724, 3.773007074423181e-05, 0.0003954759879352741, -1.339142829504216e-06, -0.0002357284794985124, -0.00013990473219042374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010328144165007061, 0.038458037434445515, -0.07686492271731701, -0.0028398603588998673, 0.012026526234592393, 0.039533531595005764, 0.05876718263468003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0726765329846376e-07, -2.7436719599043683e-08, -0.00027273491562077913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092776824624636, 0.23391536552185, 0.8410144391534922, 0.0, -0.12561937333641351, -0.24502644928800751, -2.608372332749249, -0.714846381459219, -0.5580654492593156, -1.197759983980225, -2.8760480752640456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5553285643804892, 0.7567016476649344, 1.2984972245575668, -1.182410240711934, -2.2145038309831597, -0.5314896916689004, 1.4143103114192785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961004586885, -0.440340891338681, 0.025247270725072626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3576755561743843e-05, 0.0002481484172302796, 1.0955253381353154e-06, 0.0, 0.00031474992455246607, 0.00011737852301981131, 3.8673733772419264e-05, 0.0003918652908572367, -2.4046989356143726e-06, -0.00023423441731272078, -0.00013826968915586324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010625188265690203, 0.03889609988678383, -0.07792968170576704, -0.002906109282138934, 0.011963736528207015, 0.040045130906946655, 0.05963989766678648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.724062164925631e-08, -2.175520169768459e-08, -0.00027012810196172857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927653107197078, 0.23392772070120912, 0.84101540580586, 0.0, -0.12560372148059526, -0.2450207360536313, -2.608370340249683, -0.7148268663770398, -0.5580656368309801, -1.1977716584644167, -2.8760549373458373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5547849118132201, 0.7586582290391126, 1.2945673283683066, -1.1825582987058603, -2.2139125863543287, -0.5294722015989911, 1.417321104001079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961032334704, -0.44034089222072975, 0.02523382607193861]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3027809855934757e-05, 0.0002471035871828815, 1.9333047355637315e-05, 0.0, 0.0003130371163650664, 0.00011426468752416804, 3.984999132486252e-05, 0.00039030164358217097, -3.751433291583298e-06, -0.00023348968383076396, -0.00013724163583012978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010873051345381439, 0.03913162748356494, -0.07859792378520314, -0.0029611598785264674, 0.011824892576616503, 0.04034980139818535, 0.06021585163600526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.5495637686507746e-08, -1.764097494381458e-08, -0.00026889306268031713]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927541131276883, 0.23394009802358995, 0.8410185932189661, 0.0, -0.12558808170539637, -0.24501536003159705, -2.6083682275172504, -0.7148073196989726, -0.5580659552445796, -1.1977833488101328, -2.8760617628774376, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5542316414209236, 0.7606159964722238, 1.2906249655285476, -1.182708483457291, -2.21333203892798, -0.5274503660158455, 1.4203449570214883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196105224699, -0.4403408929544426, 0.025220370236506463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2395184038915284e-05, 0.00024754644761651673, 6.374826212170298e-05, 0.0, 0.0003127955039780514, 0.00010752044068553737, 4.225464864792489e-05, 0.0003909335613460387, -6.368271990569878e-06, -0.00023380691432252473, -0.00013651063200414507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011065407845928948, 0.039155348662223484, -0.07884725679517919, -0.0030036950286129248, 0.011610948526976715, 0.04043671166291232, 0.06047706040818713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.982457199812676e-08, -1.4674257741168563e-08, -0.0002691167086428905]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092743215783537, 0.23395255998394907, 0.8410230051473843, 0.0, -0.1255723470215273, -0.24500948683706794, -2.6083661263330646, -0.7147876519622324, -0.5580662673833868, -1.1977950636282821, -2.8760686341751702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5536712534113452, 0.7625660031818171, 1.2866879830377118, -1.182860236787746, -2.2127652088517054, -0.5254334347642385, 1.4233684315272994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066363056, -0.4403408935819532, 0.025206839486613532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1794688302532136e-05, 0.0002492392071820842, 8.823856836351996e-05, 0.0, 0.00031469367738097055, 0.00011746389058215508, 4.202368371624377e-05, 0.0003933547348035006, -6.242776145484021e-06, -0.00023429636298597504, -0.000137425954647393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011207760191569353, 0.03900013419186768, -0.0787396498167154, -0.0030350666091020382, 0.011336601525492554, 0.04033862503213897, 0.06046949011622329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.823213433133761e-08, -1.2550211904220164e-08, -0.0002706149978586365]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927325796914456, 0.23396514844578484, 0.8410271275585507, 0.0, -0.1255564580338701, -0.24500311691316207, -2.6083640599432076, -0.7147677981657665, -0.5580665472338727, -1.1978068265208242, -2.876075583750252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.553105546653773, 0.7645022849839103, 1.2827683981542415, -1.1830131612272698, -2.2122139963352003, -0.5234276176635633, 1.426382469184317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119610762088, -0.44034089413375943, 0.025193188723775455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1272184183163444e-05, 0.00025176923671551226, 8.244822332876133e-05, 0.0, 0.0003177797531437408, 0.00012739847811768642, 4.132779714126504e-05, 0.0003970759293174542, -5.597009716998422e-06, -0.00023525785083845817, -0.00013899150163114093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011314135151442745, 0.03872563604186414, -0.07839169766940694, -0.0030584887904729547, 0.011024250330098417, 0.04011634201350546, 0.06028075314034978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9691486868662377e-08, -1.1036124096475251e-08, -0.00027301525676155737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927221430519952, 0.23397788059636185, 0.8410270716064849, 0.0, -0.12554039099261471, -0.24499642276078032, -2.608362020589197, -0.7147477276260098, -0.5580668007004707, -1.197818655240422, -2.8760826201722662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5525354056982379, 0.7664223422694074, 1.278871353095892, -1.1831670647227828, -2.2116791073875484, -0.5214355596259588, 1.4293832066465353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961082891086, -0.4403408946317607, 0.025179396447075814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0873278901138924e-05, 0.00025464301154047255, -1.119041316239696e-06, 0.0, 0.0003213408251079206, 0.00013388304763496832, 4.0787080209078265e-05, 0.0004014107951335775, -5.069331957641143e-06, -0.00023657439195773594, -0.00014072844028634236, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011402819110700887, 0.03840114570994267, -0.07794090116698955, -0.003078069910258842, 0.010697778953041907, 0.03984116075209075, 0.06001474924436734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3364573338846698e-08, -9.96002479206681e-09, -0.00027584553399285095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927118397610842, 0.23399075006007178, 0.8410239311303209, 0.0, -0.1255241513808587, -0.24498956199327032, -2.608359996228923, -0.7147274444229025, -0.5580670386222834, -1.1978305548826256, -2.8760897378995463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519607905134508, 0.7683268961315398, 1.2749955209541877, -1.1833219600052314, -2.2111602189092636, -0.5194565663562908, 1.4323716913338567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087239965, -0.44034089509134106, 0.025165464592248835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0606581822150228e-05, 0.00025738927419882105, -6.280952327926157e-05, 0.0, 0.00032479223511994534, 0.00013721535019996331, 4.048720548120468e-05, 0.0004056640621466314, -4.758436254420416e-06, -0.0002379928440712219, -0.00014235454560254028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492303695741828, 0.0380910772426483, -0.07751664283408612, -0.0030979056489716097, 0.010377769565691192, 0.03957986539335971, 0.05976969374642933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.697758470711222e-09, -9.191606961494153e-09, -0.0002786370965395946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927016114082483, 0.23400373210759065, 0.8410194512123002, 0.0, -0.12550776676360897, -0.24498264241683182, -2.6083579783408393, -0.7147069809039911, -0.558067269018674, -1.1978425179494117, -2.8760969224402344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5513808833672721, 0.770219150729859, 1.2711345184463556, -1.1834780299146201, -2.210656286818563, -0.5174873471763168, 1.4353528300773581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961089872947, -0.4403408955231401, 0.025151414134471806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0456705671853165e-05, 0.0002596409503772192, -8.959836041594101e-05, 0.0, 0.00032769234499486994, 0.00013839152876997973, 4.035776167439639e-05, 0.0004092703782273909, -4.607927813112079e-06, -0.00023926133572264456, -0.0001436908137622857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011598142923575108, 0.037845091966384706, -0.0772200501566399, -0.0031213981877756675, 0.010078641814011902, 0.03938438359947973, 0.05962277487002981, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.265964787306103e-09, -8.635980485045285e-09, -0.0002810091555406154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092691414881666, 0.23401679135898465, 0.8410150085045758, 0.0, -0.12549127854671643, -0.24497574505774763, -2.608355960179742, -0.7146863868814608, -0.5580674989080651, -1.1978545284643507, -2.8761041534961382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5507943371419204, 0.7721037991406221, 1.2672788624344777, -1.1836355715101474, -2.2101659072623985, -0.5155230332547469, 1.4383339177750694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091267843, -0.4403408959343855, 0.02513727793862914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0393053164340324e-05, 0.00026118502787984593, -8.885415448636424e-05, 0.0, 0.00032976433785099205, 0.00013794718168371885, 4.036322194714469e-05, 0.0004118804506054077, -4.597787821579858e-06, -0.00024021029877926975, -0.0001446211180774292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011730924507034505, 0.037692968215261316, -0.07711312023755544, -0.003150831910545682, 0.009807591123291796, 0.0392862784313995, 0.059621753954225365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7897920090490064e-09, -8.224908377818695e-09, -0.00028272391685331427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926812261786906, 0.23402988986582984, 0.8410113546364125, 0.0, -0.1254747319744555, -0.24496891110737837, -2.6083539390949957, -0.7146657179611566, -0.5580677317620203, -1.1978665659441785, -2.8761114100393854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5501995705682504, 0.7739859735345267, 1.2634180710725733, -1.1837949304919402, -2.209687661112676, -0.5135582639844605, 1.441323046386029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091769961, -0.44034089633000717, 0.025123092917831803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.037740595119924e-05, 0.00026197013690362075, -7.307736326522295e-05, 0.0, 0.0003309314452189297, 0.00013667900738548018, 4.042169492600479e-05, 0.000413378406083312, -4.657079103848079e-06, -0.00024074959655829772, -0.00014513086494717239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011895331473398937, 0.037643487878091735, -0.07721582723808787, -0.0031871796358551034, 0.009564922994449472, 0.039295385405728384, 0.05978257221919284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0042353279090035e-09, -7.91243332768826e-09, -0.00028370041594671626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209267104140628, 0.2340429943556656, 0.8410087467675743, 0.0, -0.12545816787715466, -0.24496215978482463, -2.6083519141469704, -0.7146450246015063, -0.5580679696948085, -1.1978786103348296, -2.8761186733775808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5495950616600683, 0.7758702989590087, 1.2595425870350851, -1.1839564366614876, -2.2092203933095136, -0.5115881754110759, 1.4443276391989144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091630049, -0.44034089671341636, 0.025108892724971923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0369544821449065e-05, 0.00026208979671518603, -5.215737676477587e-05, 0.0, 0.0003312819460165331, 0.0001350264510744388, 4.049896050569199e-05, 0.00041386719300691855, -4.75865576519643e-06, -0.00024088781302224356, -0.00014526676390855757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012090178163641576, 0.0376865084896394, -0.07750968074976214, -0.0032301233909471402, 0.009345356063242948, 0.039401771467691124, 0.060091856257709055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7982296091932287e-10, -7.668184058429974e-09, -0.00028400385719756733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926608744319491, 0.2340560813647748, 0.84100714592006, 0.0, -0.12544161653442082, -0.244955497567562, -2.6083498843726542, -0.7146243440160265, -0.558068214967887, -1.1978906458593799, -2.8761259294668036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5489795953441095, 0.7777601731303376, 1.2556452680292212, -1.1841203496511143, -2.2087633966761158, -0.50960916074856, 1.447353305741198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091030892, -0.4403408970870755, 0.025094702314994995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0333948661378775e-05, 0.00026174018218340985, -3.20169502866619e-05, 0.0, 0.0003310268546768269, 0.00013324434525306686, 4.059548631981508e-05, 0.0004136117095959833, -4.905461569446624e-06, -0.000240710491007444, -0.0001451217844593823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012309326319177109, 0.03779748342657835, -0.07794638011728017, -0.003278259792533467, 0.009139932667958336, 0.03958029325031823, 0.06051333084567211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1983133136278932e-09, -7.473183279607074e-09, -0.00028380819953853617]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926507518548892, 0.23406913975715812, 0.8410063972109484, 0.0, -0.1254250943916626, -0.24494892316027456, -2.608347847602481, -0.7146036957909659, -0.5580684709624298, -1.197902663376985, -2.8761331701051116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5483524295994947, 0.7796573562743375, 1.2517222633995697, -1.1842868227479875, -2.208316486536265, -0.5076193119658289, 1.450403158759081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961090106299, -0.4403408974528865, 0.025080534974728976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.024515411962932e-05, 0.00026116784766674965, -1.4974182231708038e-05, 0.0, 0.0003304428551644765, 0.00013148814574851165, 4.073540347224048e-05, 0.0004129645012103608, -5.11989085565838e-06, -0.00024035035209954281, -0.00014481276615678032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012543314892294048, 0.03794366287999797, -0.07846009259303048, -0.0033294619374617247, 0.008938202797012384, 0.039796975654622084, 0.06099706035765974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8491878388867557e-09, -7.316219767631447e-09, -0.00028334680532038955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092640706247312, 0.23408217066001355, 0.8410063526322429, 0.0, -0.12540860373294258, -0.2449424304491214, -2.60834579975472, -0.7145830813160546, -0.5580687427240117, -1.1979146611692344, -2.876140392932268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477133581084443, 0.7815619052704538, 1.2477731946150523, -1.184455889736394, -2.207879969820352, -0.5056185028546967, 1.4534776604086994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961088954982, -0.44034089781242836, 0.025066391894913224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.009121515419239e-05, 0.000260618057108365, -8.915741105720763e-07, 0.0, 0.00032981317440052325, 0.00012985422306327325, 4.095695521190876e-05, 0.0004122894982256085, -5.435231639094996e-06, -0.00023995584498924465, -0.00014445654312312013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012781429821006966, 0.03809097992232506, -0.07898137569034647, -0.0033813397681313325, 0.008730334318258284, 0.0400161822226447, 0.06149003299236816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3026331635870013e-09, -7.190836763878865e-09, -0.00028286159631504327]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926307691308385, 0.23409518526677917, 0.8410069402647227, 0.0, -0.1253921349031404, -0.24493601079447763, -2.6083437344912714, -0.7145624864817306, -0.5580690372130511, -1.1979266443344707, -2.8761476003795403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5470626671276048, 0.7834724248618756, 1.2438006829971782, -1.184627475277609, -2.207454529886821, -0.5036081384235395, 1.4565749690388725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087651023, -0.44034089816707767, 0.025052263927612763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.987423294722793e-05, 0.0002602921353122936, 1.1752649594739351e-05, 0.0, 0.00032937659604336363, 0.00012839309287525946, 4.1305268976469446e-05, 0.0004118966864805311, -5.889780787719116e-06, -0.00023966330472836243, -0.00014414894544540635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013013819616792176, 0.03821039182843783, -0.07945023235748334, -0.0034317108242994452, 0.008508798670629213, 0.04020728862314311, 0.061946172603460165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.6079186586223684e-09, -7.0929858090402915e-09, -0.0002825593460092203]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926209653450153, 0.23410820123521298, 0.8410082143246913, 0.0, -0.1253756709732818, -0.24492966907772523, -2.6083416402413238, -0.7145418865534288, -0.5580693663526989, -1.1979386237684981, -2.8761547968083865, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5464010059180497, 0.7853865487005857, 1.2398093933607142, -1.1848014244146543, -2.207041062165461, -0.5015906591196544, 1.4596916611728852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961086252894, -0.44034089851804437, 0.025038134870181875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9607571646466996e-05, 0.0002603193686763777, 2.5481199373799305e-05, 0.0, 0.00032927859717196993, 0.0001268343350481614, 4.188499894923267e-05, 0.00041199856603673615, -6.582792954605186e-06, -0.00023958868055025964, -0.0001439285769249745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013233224191099789, 0.038282476774199756, -0.0798257927292779, -0.003478982740907496, 0.008269354427197501, 0.04034958607770108, 0.06233384268025381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7962567570105424e-09, -7.0193344667182365e-09, -0.00028258114861774437]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926113099265617, 0.234121238526162, 0.8410105984550883, 0.0, -0.1253591947926548, -0.24492346106987012, -2.6083394906020354, -0.7145212518834684, -0.5580697569854639, -1.1979506160215903, -2.8761619827878184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5457292068060542, 0.7873015241020881, 1.2358048465440552, -1.184977542987103, -2.206640501330332, -0.49956893056404467, 1.4628236370430239, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961084815775, -0.4403408988663479, 0.025023985465707808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931083690758048e-05, 0.0002607458189806041, 4.768260794038333e-05, 0.0, 0.00032952361254006915, 0.00012416015710208913, 4.2992785767106124e-05, 0.0004126933992083718, -7.812655299679258e-06, -0.0002398450618418897, -0.0001437195886432252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01343598223991072, 0.03829950803004944, -0.08009093633318079, -0.0035223714489752, 0.008011216702579899, 0.0404345711121948, 0.06263951740277536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8742398780104438e-09, -6.966071248459883e-09, -0.0002829880894813476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926018097379936, 0.23413431550550415, 0.8410167207029203, 0.0, -0.12534271040293332, -0.2449177927150775, -2.608337171986235, -0.7145005514573702, -0.5580703255885383, -1.1979626566472965, -2.876169126106767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5450480973304483, 0.7892147697485378, 1.2317922688863037, -1.1851556392368676, -2.206253675763402, -0.4975456560147912, 1.4659670042325852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961083432173, -0.4403408992127139, 0.025009797299432257]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9000377136226644e-05, 0.0002615395868425685, 0.00012244495664020678, 0.0, 0.00032968779442995655, 0.00011336709585256783, 4.637231600443822e-05, 0.00041400852196258844, -1.1372061487813333e-05, -0.00024081251412407916, -0.00014286637897059832, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013622189512117975, 0.03826491292899262, -0.08025155315503234, -0.003561924995294374, 0.007736511338602989, 0.040465490985068735, 0.06286734379122626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7672025351042834e-09, -6.927319278877532e-09, -0.0002837633255110353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925924473431196, 0.23414744577279814, 0.8410295052634726, 0.0, -0.12532615413129616, -0.24491146594222257, -2.6083348858091493, -0.7144797706276045, -0.5580708638242928, -1.1979747109666614, -2.876176309298787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5443583420276428, 0.7911243028203149, 1.2277756938930156, -1.1853355594288222, -2.205881215621574, -0.49552292125638464, 1.4691187756999138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961081996834, -0.4403408995579558, 0.024995556101940583]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.872478974795834e-05, 0.0002626053458798795, 0.0002556912110465393, 0.0, 0.0003311254327433029, 0.00012653545709845852, 4.5723541721021796e-05, 0.0004156165953142211, -1.0764715090429236e-05, -0.00024108638729753126, -0.00014366384040922283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013795106056110737, 0.038190661435542575, -0.08033149986576091, -0.0035984038390933335, 0.007449202836556653, 0.04045469516813203, 0.06303542934656964, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.870679197150595e-09, -6.904837927637466e-09, -0.00028482394983349996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209258321812838, 0.23416063671814646, 0.8410437398870134, 0.0, -0.12530950693366413, -0.2449045021895959, -2.6083326703868854, -0.7144588979179173, -0.5580713315230594, -1.1979867766771146, -2.876183551344064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5436603401302411, 0.7930289777705635, 1.2237574461151752, -1.1855172087541164, -2.205523515013933, -0.4935019358093305, 1.4722772729752847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196108047214, -0.4403408999025876, 0.02498125341052859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8458429479456307e-05, 0.00026381890696620686, 0.00028469247081648613, 0.0, 0.00033294395264052857, 0.0001392750525336554, 4.430844527807723e-05, 0.0004174541937448723, -9.353975332314504e-06, -0.00024131420906434384, -0.00014484090553941895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013960037948034177, 0.03809349900497107, -0.08036495555680431, -0.003632986505881571, 0.007154012152821098, 0.04041970894108255, 0.06316994550741814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0493887787539148e-09, -6.892636135295253e-09, -0.00028605382823986507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925741079071422, 0.23417388915558981, 0.8410558513561877, 0.0, -0.1252927688848866, -0.24489716620190444, -2.608330514922322, -0.7144379299689384, -0.5580717393380537, -1.1979988583162735, -2.876190849474161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5429541857656108, 0.7949285340699397, 1.219738015378438, -1.1857005597806267, -2.20518074960298, -0.49148297443279904, 1.4754422337730737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961078852034, -0.44034090024685824, 0.02496688719657855]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.822044247553129e-05, 0.00026504874886679614, 0.00024222938348463573, 0.0, 0.00033476097555076287, 0.00014671975382885406, 4.3109291263184026e-05, 0.00041935897957802475, -8.15629988416167e-06, -0.00024163278317604285, -0.00014596260194143167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014123087292605495, 0.0379911259875245, -0.08038861473474176, -0.003667020530205452, 0.006855308219058671, 0.04037922753062938, 0.06329921595578203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.240211931340805e-09, -6.8854117509447195e-09, -0.0002873242790007967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925651016993824, 0.2341871982181353, 0.841064560189934, 0.0, -0.12527594904818817, -0.244889683732324, -2.6083283999322955, -0.7144168718483338, -0.5580721071402739, -1.1980109586672534, -2.8761981945080244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5422396885604397, 0.796823478601238, 1.2157162776406405, -1.1858856473286126, -2.204852931173053, -0.48946549449193955, 1.4786146509471971, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961077143157, -0.440340900590808, 0.024952461212057558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8012415519644415e-05, 0.0002661812509097066, 0.00017417667492830742, 0.0, 0.0003363967339687805, 0.00014964939160868815, 4.22998005336657e-05, 0.0004211624120919971, -7.356044404709993e-06, -0.00024200701959800386, -0.00014690067726872157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014289944103422625, 0.03789889062596692, -0.08043475475595119, -0.003701750959717785, 0.006556368598541364, 0.04034959881719022, 0.06344834348246732, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.417755392511266e-09, -6.878994897202412e-09, -0.0002885196904198138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925561871488957, 0.2342005551099568, 0.8410618129676085, 0.0, -0.12525905888066197, -0.24488214897121363, -2.6083263175041984, -0.7143957352424114, -0.5580724431370468, -1.1980230752117988, -2.876205579243565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5415164409760148, 0.7987148547729442, 1.2116899592973498, -1.1860725531242928, -2.204539981107109, -0.4874483756147806, 1.4817964206867469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196107529577, -0.4403409009345591, 0.024937983419938786]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7829100973510103e-05, 0.00026713783642982983, -5.494444651112204e-05, 0.0, 0.00033780335052389384, 0.00015069522220727264, 4.1648561942064236e-05, 0.00042273211844828475, -6.719935459193817e-06, -0.00024233089091155212, -0.0001476947108070534, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0144649516884974, 0.03782752343412516, -0.08052636686581613, -0.0037381159136050312, 0.006259001318883878, 0.04034237754317851, 0.063635394790993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.6947749940585474e-09, -6.875021760779324e-09, -0.00028955584237541106]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925473569686348, 0.23421394931927147, 0.8410514001986437, 0.0, -0.1252421128803267, -0.24487463982329583, -2.6083242575075474, -0.714374534897885, -0.5580727580383967, -1.1980352043068812, -2.876212994467474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5407839134953499, 0.8006039588567667, 1.207656221940558, -1.186261384604039, -2.2042418051162214, -0.48543021847138557, 1.484989893729473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961073308133, -0.4403409012779771, 0.024923463887919817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.766036052164086e-05, 0.0002678841862932682, -0.0002082553792966759, 0.0, 0.0003389200067054922, 0.00015018295835598537, 4.119993302519067e-05, 0.00042400689052663815, -6.298026998768619e-06, -0.00024258190164787988, -0.00014830447818341125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014650549613298546, 0.037782081676448954, -0.08067474713583679, -0.0037766295949263422, 0.005963519817753503, 0.04036314286790055, 0.06386946085452182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.975271951200736e-09, -6.868360176661031e-09, -0.00029039064037935573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092538608537945, 0.23422737072300479, 0.8410381966315522, 0.0, -0.12522512498451718, -0.24486719520491726, -2.6083222122520726, -0.7143532856264078, -0.558073060175217, -1.1980473414524133, -2.8762204318291222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5400415571601024, 0.802492060683494, 1.203612248263087, -1.1864522523033614, -2.203958355577257, -0.48340964194609903, 1.4881974215808351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961071196258, -0.4403409016208386, 0.024908912697799563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7496861379995055e-05, 0.0002684280746661161, -0.00026407134182844635, 0.0, 0.0003397579161902799, 0.00014889236757115187, 4.0905109493422496e-05, 0.0004249854295460771, -6.042736403583455e-06, -0.00024274291064534188, -0.00014874723296733107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014847126704950253, 0.03776203653454571, -0.08087947354941886, -0.0038173539864452552, 0.005668990779289269, 0.04041153050573016, 0.06415055702724443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.223748727891442e-09, -6.857230398915573e-09, -0.0002910238024050965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092529944076841, 0.23424081134161082, 0.8410256342076418, 0.0, -0.1252081083032503, -0.24485987423481367, -2.6083201681803243, -0.7143319993473054, -0.5580733639668903, -1.19805948425245, -2.876227881748336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5392888952123503, 0.8043801749776589, 1.199555730702428, -1.1866452498983047, -2.203689672700999, -0.4813855291015325, 1.4914209744135996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961069010158, -0.44034090196284364, 0.024894338130268572]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.73289222079557e-05, 0.0002688123721204562, -0.00025124847820875187, 0.0, 0.0003403336253374409, 0.0001464194020714956, 4.088143496894334e-05, 0.00042572558204703276, -6.075833466954572e-06, -0.00024285600073301045, -0.00014899838427806628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015053238955041206, 0.037762285883297685, -0.08113035121317991, -0.00385995189886731, 0.005373657525156167, 0.0404822568913309, 0.06447105665528777, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.372200407588851e-09, -6.840101178064515e-09, -0.00029149135061983824]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925213689002095, 0.2342542662563984, 0.8410156966170897, 0.0, -0.12519107192954645, -0.24485269584579836, -2.6083181143208978, -0.7143106838121357, -0.5580736811329241, -1.1980716312967383, -2.8762353371275893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5385255891694956, 0.8062689141714454, 1.1954851943908478, -1.1868404398340329, -2.2034359013919644, -0.47935718789178705, 1.4946618848676878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066785933, -0.44034090230379175, 0.024879745639150908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.715035326296363e-05, 0.00026909829575125156, -0.00019875181104035377, 0.0, 0.0003407274740771001, 0.00014356778030618733, 4.1077188530469014e-05, 0.0004263107033934446, -6.343320675583013e-06, -0.000242940885769391, -0.00014910758505718826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015266120857095179, 0.03777478387572981, -0.08141072623160639, -0.0039037987145622843, 0.00507542618069157, 0.04056682419490884, 0.06481820908176425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.448451342577258e-09, -6.818962556157126e-09, -0.0002918498223532651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925128903715878, 0.23426773395518843, 0.8410091822802671, 0.0, -0.1251740209093694, -0.24484566153708204, -2.608316039956505, -0.7142893418370708, -0.5580740230314425, -1.1980837830640352, -2.8762427927565875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5377514715302819, 0.8081584355938903, 1.191400123617303, -1.1870378465048221, -2.203197285560948, -0.47732441194759734, 1.4979207434700035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961064552824, -0.44034090264356734, 0.024865137375008096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6957057243526444e-05, 0.00026935397580074723, -0.0001302867364530094, 0.0, 0.00034102040354084764, 0.00014068617432632294, 4.1487287853933165e-05, 0.00042683950129745, -6.8379703677965584e-06, -0.00024303534593528628, -0.0001491125799654512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015482352784273262, 0.037790428448899266, -0.08170141547089317, -0.003948133415784107, 0.004772316620325626, 0.04065551888379408, 0.06517717204631435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4662181708756e-09, -6.795512158578875e-09, -0.00029216528285619614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925045163771558, 0.23428121600255097, 0.841006182580274, 0.0, -0.1251569578582527, -0.2448387886481049, -2.6083139287135433, -0.7142679714400227, -0.5580744067173158, -1.198095943175205, -2.8762502430157117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5369665434085289, 0.8100484778689586, 1.1873008984865836, -1.1872374571208901, -2.202974145462632, -0.47528744564920095, 1.5011974420998633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961062340045, -0.44034090298211515, 0.02485051238883319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.674798886404033e-05, 0.00026964094725063224, -5.999399986235081e-05, 0.0, 0.0003412610223343902, 0.0001374577795425186, 4.2224859239858586e-05, 0.0004274079409619088, -7.673717465437287e-06, -0.00024320222339622167, -0.00014900518248552445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015698562435060924, 0.03780084550136615, -0.08198450261439016, -0.003992212321361882, 0.00446280196632445, 0.04073932596792761, 0.06553397259719447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.425557552529118e-09, -6.770956109758903e-09, -0.000292499723498149]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092496254561651, 0.23429471621174008, 0.8410070818992268, 0.0, -0.12513988917033175, -0.24483220114101195, -2.6083117354932526, -0.7142465662167454, -0.5580748787203342, -1.1981081230145345, -2.876257672920959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5361709421772896, 0.8119384662083703, 1.1831885815751473, -1.1874392290545575, -2.2027668457589105, -0.47324687428874174, 1.5044913358973206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961060191408, -0.4403409033193899, 0.024835867359076832]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6523631009647197e-05, 0.00027000418378232623, 1.7986379055652413e-05, 0.0, 0.00034137375841914824, 0.0001317501418588057, 4.38644058126588e-05, 0.000428104465546681, -9.440060369282882e-06, -0.00024359678659280064, -0.00014859810494164313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01591202462478672, 0.03779976678823284, -0.082246338228728, -0.004035438673345594, 0.004145994074430361, 0.04081142720918442, 0.06587787594914715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.2972752186325556e-09, -6.745495156767535e-09, -0.0002929005951271798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924881037954635, 0.23430823941628123, 0.8410104805760512, 0.0, -0.12512278443502178, -0.24482522520652472, -2.6083095683298225, -0.7142251228420964, -0.5580753276019556, -1.1981203016818394, -2.876265125001612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5353648890732149, 0.8138276562638193, 1.1790646163154206, -1.1876431018294107, -2.2025757636634418, -0.47120347108002103, 1.507801477500176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961058005932, -0.4403409036557102, 0.02482119775785553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6301532375350888e-05, 0.00027046409082271354, 6.797353648898557e-05, 0.0, 0.00034209470619956105, 0.00013951868974477018, 4.334326859974839e-05, 0.0004288674929802702, -8.977632425557614e-06, -0.00024357334609904135, -0.00014904161305743515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016121062081492537, 0.037783801108978735, -0.08247930519453568, -0.004077455497066453, 0.0038216419093723523, 0.04086806417441358, 0.0662028320571086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.370951473633228e-09, -6.7264061167353235e-09, -0.00029339202442599564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924800703709684, 0.23432179057086786, 0.8410220134799768, 0.0, -0.1251056348788504, -0.24481791065265449, -2.608307439769383, -0.7142036343470946, -0.5580757402627518, -1.1981324793969663, -2.876272606590669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5345486301753641, 0.815715283537283, 1.174930509137666, -1.187849009680018, -2.202401260338183, -0.46915803691662905, 1.511126864406344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961055784995, -0.44034090399110765, 0.024806498730338414]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6066848990084677e-05, 0.000271023091732647, 0.0002306580785137615, 0.0, 0.0003429911234276098, 0.00014629107740476386, 4.2571208786319135e-05, 0.00042976990003583957, -8.253215924271817e-06, -0.00024355430253760203, -0.00014963178114351563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01632517795701424, 0.037752545469273785, -0.08268214355509021, -0.00411815701214592, 0.003490066505177751, 0.040908683267839405, 0.06650773812336223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.441875061750068e-09, -6.707948679834676e-09, -0.0002939805503423458]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924721542543817, 0.23433537370842256, 0.8410361863605892, 0.0, -0.12508843718601376, -0.24481039522159975, -2.608305342609468, -0.7141820942853051, -0.5580761239398435, -1.1981446603147465, -2.8762801172878922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5337223806981956, 0.8176006922550547, 1.1707875488863044, -1.1880568938312568, -2.202243664018041, -0.46711126031023903, 1.5144666613670423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961053527348, -0.4403409043256543, 0.024791766155124875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5832233173576852e-05, 0.0002716627510938502, 0.00028345761224643766, 0.0, 0.0003439538567329903, 0.0001503086210947443, 4.194319830212943e-05, 0.000430801235789004, -7.673541835312326e-06, -0.00024361835560364367, -0.00015021394446600118, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01652498954337114, 0.037708174355435345, -0.08285920502723475, -0.004157683024774714, 0.0031519264028380908, 0.040935532127800434, 0.06679593921396432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.515292675017828e-09, -6.690933603425866e-09, -0.00029465150427082805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924643533830425, 0.2343489912932732, 0.8410488218063917, 0.0, -0.12507119063353525, -0.2448027929086804, -2.6083032659665797, -0.7141604982942021, -0.558076489693346, -1.1981568485621175, -2.8762876545351124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5328862835321865, 0.8194834221540722, 1.1666366132028636, -1.1882667114267673, -2.2021032639672424, -0.4650636217414324, 1.5178203558558363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961051233105, -0.4403409046594021, 0.024776997345098726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5601742678380886e-05, 0.0002723516970125972, 0.0002527089160520015, 0.0, 0.00034493104957015075, 0.00015204625838715168, 4.153285776985821e-05, 0.000431919822058675, -7.315070048949514e-06, -0.0002437649474163956, -0.00015074494440707218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0167219433201824, 0.03765459798034946, -0.08301871366881823, -0.004196351910210223, 0.002808001015978366, 0.04095277137613264, 0.06707388977588098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.588484374229094e-09, -6.674955954323654e-09, -0.0002953762005229549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924566647408677, 0.2343626439628206, 0.8410582188776666, 0.0, -0.12505389614320422, -0.2447951709450306, -2.6083012010642563, -0.7141388447389879, -0.5580768464749206, -1.198169046739875, -2.876295215589466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5320403872014193, 0.8213632450124095, 1.1624780814579907, -1.1884784401226691, -2.2019803143826557, -0.46301535181210113, 1.5211878305426285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196104890307, -0.4403409049923652, 0.02476219137471044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5377284349828743e-05, 0.0002730533909486646, 0.00018794142549695913, 0.0, 0.0003458898066202609, 0.00015243927299610655, 4.129804646886761e-05, 0.0004330711042844184, -7.135631492355292e-06, -0.0002439635551490929, -0.00015122108707033406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016917926615343505, 0.03759645716674715, -0.08317063489745692, -0.004234573918034956, 0.002458991691729575, 0.04096539858662546, 0.0673494937358462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.660066937348196e-09, -6.659262154159706e-09, -0.00029611940776575553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924490848327904, 0.23437633061949292, 0.8410560835309228, 0.0, -0.12503655431277882, -0.24478752010214577, -2.6082991495782464, -0.7141171348764142, -0.5580771925424345, -1.1981812541074885, -2.8763028006481965, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5311846441002754, 0.8232401533797046, 1.1583118511849793, -1.1886920782222765, -2.201875045276336, -0.4609664411809146, 1.524569354157154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961046486924, -0.44034090532473663, 0.024747349055800713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.515981615443592e-05, 0.0002737331334461661, -4.2706934877010327e-05, 0.0, 0.0003468366085082563, 0.0001530168576964341, 4.102972019804011e-05, 0.0004341972514756301, -6.921350278078256e-06, -0.0002441473522719288, -0.0001517011746054956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017114862022878714, 0.037538167345899924, -0.08332460546022809, -0.004272761992147246, 0.0021053821263965393, 0.04097821262373043, 0.0676304722905131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.8322945298618424e-09, -6.647428706090912e-09, -0.00029684637819448666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924416111709013, 0.23439004885222628, 0.8410461448202162, 0.0, -0.12501916851060207, -0.24477986099661353, -2.608297108373726, -0.7140953718715477, -0.5580775311962143, -1.1981934700527117, -2.8763104073626153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5303189263193195, 0.8251143119355534, 1.1541374375979159, -1.1889076410571624, -2.2017876764519566, -0.458916691640201, 1.527965505878348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961043974682, -0.44034090565650524, 0.024732472576478384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.494732377830591e-05, 0.00027436465466719494, -0.0001987742141298727, 0.0, 0.00034771604353479976, 0.00015318211064475697, 4.082409040750608e-05, 0.0004352600973289408, -6.773075596842037e-06, -0.0002443189044638289, -0.0001521342883787291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017314355619117806, 0.03748317111697732, -0.0834882717412666, -0.004311256697716052, 0.0017473764875824422, 0.0409949908142728, 0.06792303442387358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.024482560456021e-09, -6.6353721321817925e-09, -0.0002975295864465577]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092434241898101, 0.23440379548519505, 0.8410332845986868, 0.0, -0.12500174317378177, -0.24477220846572847, -2.608295074172032, -0.7140735601679984, -0.5580778659557126, -1.1982056933796754, -2.876318032849949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5294430534430056, 0.8269859865684598, 1.1499541243889762, -1.189125154817421, -2.2017184311773126, -0.45686579217268836, 1.5313770578414172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961041372786, -0.4403409059875701, 0.024717564985329347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4738545600715052e-05, 0.0002749326593754455, -0.0002572044305889292, 0.0, 0.00034850673640610146, 0.0001530506177013048, 4.068403387558512e-05, 0.0004362340709858327, -6.695189967279231e-06, -0.00024446653927346663, -0.00015250974666713418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01751745752627855, 0.037433492658127586, -0.08366626417879379, -0.004350275205172314, 0.0013849054928832506, 0.04101798935025297, 0.0682310392613842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.20379147070437e-09, -6.6212970787305426e-09, -0.0002981518229807454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924269768571976, 0.23441756723256021, 0.8410211936055637, 0.0, -0.12498428656625127, -0.24476466142210812, -2.6082930282445553, -0.7140517040554214, -0.5580782163099339, -1.1982179260165966, -2.876325668360499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5285568258487621, 0.8288554673713606, 1.1457611312938534, -1.1893446493034172, -2.2016675466270863, -0.4548134026388708, 1.5348048426790608, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196103873076, -0.44034090631767464, 0.024702629546660564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4530081806884725e-05, 0.0002754349473032083, -0.00024181986246085216, 0.0, 0.0003491321506098486, 0.00015094087240714833, 4.091854953169874e-05, 0.00043712225154075634, -7.007084426564443e-06, -0.0002446527384237837, -0.00015271021099671814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017724551884869048, 0.03738961605801727, -0.08385986190245388, -0.004389889719921877, 0.0010176910045214236, 0.041047790676350795, 0.06855569675287329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.284054276865303e-09, -6.602091496072119e-09, -0.00029870877337561573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924198163869062, 0.2344313611202062, 0.8410122464977837, 0.0, -0.12496680663473403, -0.2447572764006, -2.608290952109812, -0.7140298075149323, -0.5580786015168077, -1.1982301698893667, -2.8763333053410314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5276600565197247, 0.8307230000548407, 1.141557766052324, -1.1895661509740727, -2.2016352798132326, -0.45275922901337, 1.5382496319416816, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961036089454, -0.44034090664660797, 0.024687669311053716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4320940582745845e-05, 0.00027587775291998173, -0.0001789421555994827, 0.0, 0.000349598630344771, 0.00014770043016274956, 4.152269486684434e-05, 0.0004379308097814693, -7.704137474671007e-06, -0.0002448774554009283, -0.00015273961065152483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017935386580748176, 0.03735065366960045, -0.08406730483058789, -0.004430033413108865, 0.0006453362770783385, 0.04108347251001572, 0.0688957852524162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.282608769722518e-09, -6.578666193878617e-09, -0.00029920471213696226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924127625602892, 0.2344451748886894, 0.8410079530709207, 0.0, -0.12494931498664277, -0.244750168298184, -2.6082888080760194, -0.7140078729634463, -0.5580790606308612, -1.1982424314263758, -2.8763409284529082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5267525963935548, 0.8325887363924743, 1.1373435371498235, -1.1897896775209689, -2.2016219084821045, -0.4507030786006588, 1.5417120444288943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961033496475, -0.4403409069741575, 0.02467268668987216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4107653234047511e-05, 0.00027627536966383934, -8.58685372608118e-05, 0.0, 0.00034983296182516905, 0.00014216204832000084, 4.288067585132707e-05, 0.0004386910297200211, -9.182281072144481e-06, -0.0002452307401810137, -0.0001524622375366768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018149202523398262, 0.0373147267526732, -0.08428457805000901, -0.004470530937921876, 0.00026742662256651394, 0.04112300825422484, 0.06924824974425506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.1859567260439755e-09, -6.5509905493119906e-09, -0.00029965242363114023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092405814221847, 0.23445900711925993, 0.8410076193949413, 0.0, -0.12493180308159409, -0.24474297271213807, -2.6082866415957042, -0.7139859042924999, -0.5580795469753796, -1.1982546995110912, -2.876348553631648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5258343494031532, 0.8344527092342277, 1.1331182132852262, -1.1900152349403026, -2.2016277287256725, -0.44864488862339164, 1.5451924969752042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961030939942, -0.440340907300321, 0.024657683298567584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3896676884206326e-05, 0.0002766446114107791, -6.67351958730456e-06, 0.0, 0.0003502381009738575, 0.0001439117209183849, 4.3329606299553536e-05, 0.00043937341892728914, -9.726890369524963e-06, -0.000245361694308613, -0.0001525035747982607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01836493980803164, 0.037279456835067414, -0.08450647729194553, -0.004511148386673094, -0.00011640487135941536, 0.04116379954534321, 0.06960905092619887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.113067642888294e-09, -6.523269362194304e-09, -0.0003000678260915194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923989737066429, 0.23447285729849482, 0.8410173949544465, 0.0, -0.12491426032710078, -0.2447354537589122, -2.608284502251769, -0.71396390406394, -0.5580800095622412, -1.198266962763555, -2.8763561988785353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5249052765248465, 0.8363148320871545, 1.1288818293044027, -1.1902428166137695, -2.201653048920596, -0.4465847280576006, 1.5486911968215638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961028376508, -0.44034090762510103, 0.024642659859163866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3681030408542761e-05, 0.00027700358469752445, 0.00019551119010394067, 0.0, 0.0003508550898663204, 0.00015037906451729831, 4.27868787103912e-05, 0.00044000457119782273, -9.251737232382818e-06, -0.00024526504927672977, -0.00015290493773938857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018581457566134493, 0.03724245705853732, -0.08472767961646975, -0.004551633469339973, -0.0005064038984640953, 0.041203211315821324, 0.06997399692719035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.126869319532842e-09, -6.495600528856092e-09, -0.0003004687880743624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092392244501384, 0.234486725664656, 0.8410311200160856, 0.0, -0.12489668545552522, -0.24472768583321533, -2.6082823951474987, -0.7139418722212836, -0.5580804432043482, -1.1982792199698034, -2.8763638661337536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5239653889266263, 0.8381749203751567, 1.1246346429876275, -1.1904724048381408, -2.201698183225296, -0.4445227753775335, 1.5522081740767828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961025786713, -0.4403409079485101, 0.024627616319695567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3458410517791e-05, 0.0002773673232235325, 0.00027450123278138414, 0.0, 0.0003514974315111833, 0.00015535851393738803, 4.214208540367673e-05, 0.00044063685312759504, -8.672842140828888e-06, -0.0002451441249686973, -0.00015334510436367145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018797751964405293, 0.037201765760044934, -0.08494372633550343, -0.004591764487425716, -0.0009026860940070896, 0.041239053601341294, 0.07033954510438059, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.179590171708666e-09, -6.4681820872776385e-09, -0.00030087078936595537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092385628245801, 0.23450061290819943, 0.841043974989202, 0.0, -0.12487907955192709, -0.24471978613250056, -2.6082803126668055, -0.7139198076214038, -0.5580808557941545, -1.1982914729840688, -2.87637155287179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5230147331040501, 0.840032726778139, 1.1203770586254933, -1.1907039742031829, -2.201763446439512, -0.44245928030608556, 1.555743342117177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961023164102, -0.4403409082705559, 0.024612552136522255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3232511166461702e-05, 0.0002777448708686309, 0.0002570994623296304, 0.0, 0.0003521180719626334, 0.00015799401429511677, 4.164961386793083e-05, 0.0004412919975958298, -8.251796124645198e-06, -0.0002450602853071114, -0.00015373476072257683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01901311645152213, 0.0371561280596449, -0.08515168724268607, -0.004631387300841511, -0.0013052642843153798, 0.04126990142895847, 0.07070336080788225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.245223065171383e-09, -6.440916079248447e-09, -0.000301283663466211]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923791258923294, 0.23451451984754135, 0.841053839335408, 0.0, -0.124861443738691, -0.24471183909284877, -2.6082782461560727, -0.7138977088744598, -0.5580812562752453, -1.198303724005304, -2.876379256266048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5220533722188224, 0.8418879814421235, 1.1161095379235029, -1.1909374956665297, -2.201849150615711, -0.4403945196928669, 1.5592965689997291, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196102050767, -0.44034090859124075, 0.024597466590461522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3004706942721193e-05, 0.0002781387868381211, 0.00019728692411996905, 0.0, 0.00035271626472192926, 0.00015894079303583724, 4.1330214656937515e-05, 0.00044197493888114875, -8.009621817293962e-06, -0.0002450204247059355, -0.00015406788515755283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019227217704553823, 0.03710509327968975, -0.0853504140398068, -0.004670429266939552, -0.0017140835239768332, 0.041295212264373216, 0.0710645376510457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.312866158655143e-09, -6.413697667347336e-09, -0.0003017109212146423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923727385304727, 0.2345284471820798, 0.8410522138073605, 0.0, -0.12484378254230989, -0.24470398536804427, -2.6082761725991963, -0.7138755742604499, -0.5580816683877518, -1.1983159783207948, -2.876386968121842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5210813675425818, 0.8437404292008875, 1.111832515911148, -1.191172940537945, -2.2019556038910966, -0.4383287562399933, 1.56286774570927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961017818023, -0.44034090891060784, 0.024582359033059612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2774723713286888e-05, 0.00027854669076925285, -3.251056095003856e-05, 0.0, 0.00035322392762227256, 0.00015707449608995283, 4.147113752742501e-05, 0.0004426922801981734, -8.242250128389216e-06, -0.0002450863098167964, -0.00015423711587763197, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01944009352481135, 0.03704895517528012, -0.08554044024709782, -0.004708897428303273, -0.002129065507710266, 0.04131526905747279, 0.07142353419081342, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.379290814927804e-09, -6.3873414308310886e-09, -0.000302151148038187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092366466504449, 0.2345423951962035, 0.8410434472930469, 0.0, -0.12482610237027067, -0.2446963384501182, -2.6082740628509478, -0.7138534024818921, -0.5580821222057958, -1.1983282422944421, -2.8763946777497114, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5200987630336469, 0.8455898577733169, 1.107546335549563, -1.1914102836995266, -2.2020831116149004, -0.4362622067468347, 1.566456840158064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961015123277, -0.44034090922857455, 0.024567229195095627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2544052047728873e-05, 0.0002789602824744588, -0.00017533028627138354, 0.0, 0.00035360344078455975, 0.000152938358521538, 4.2194964967829366e-05, 0.0004434355711551118, -9.0763608804408e-06, -0.000245279472945569, -0.00015419255739288778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019652090178698466, 0.03698857144858722, -0.08572360723169974, -0.004746863231634872, -0.002550154476074551, 0.04133098986317244, 0.07178188897588188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.389492783145938e-09, -6.359334203315072e-09, -0.0003025967592796801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923603119785542, 0.23455636366143515, 0.8410353019987932, 0.0, -0.1248084242584862, -0.24468923095470801, -2.6082718269296277, -0.713831191059617, -0.5580827105398091, -1.1983405351414187, -2.876402351621198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.519105575620468, 0.8474361134617115, 1.1032512099441503, -1.1916495054977405, -2.202231978612754, -0.4341950240570607, 1.5700639289912093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961012491604, -0.4403409095449165, 0.024552077293800822]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2309051789507755e-05, 0.00027936930463274916, -0.00016290588507396475, 0.0, 0.00035356223568931217, 0.00014214990820386725, 4.471842639831812e-05, 0.00044422844550102134, -1.1766680265442813e-05, -0.00024585693952967403, -0.00015347742973165416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019863748263576935, 0.03692511376789492, -0.08590251210825339, -0.004784435964277944, -0.0029773399570713964, 0.04134365379548046, 0.07214177666290271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.26334369806623e-09, -6.326839330366228e-09, -0.00030303802589605624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092354267738185, 0.2345703517593418, 0.841037086357163, 0.0, -0.12479072675782128, -0.24468196978950849, -2.608269562166431, -0.71380894456449, -0.5580833331616019, -1.1983528350359811, -2.87641002529331, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5181017919564832, 0.8492791034645827, 1.0989472139222365, -1.1918905930169712, -2.2024025140696923, -0.4321272937656738, 1.5736892075793183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961010055812, -0.4403409098589737, 0.02453690412215113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2088480738122096e-05, 0.0002797619581327564, 3.568716739713108e-05, 0.0, 0.0003539500132983976, 0.00014522330399074646, 4.529526392674975e-05, 0.0004449299025413268, -1.2452435856533942e-05, -0.00024599789125044413, -0.0001534734422348367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020075673279695384, 0.03685980005742207, -0.08607992043827516, -0.004821750384614016, -0.003410709138764685, 0.04135460582773689, 0.07250557176218154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.871585243622658e-09, -6.281143838603349e-09, -0.0003034634329938299]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923483351000108, 0.23458435821041387, 0.8410433690732536, 0.0, -0.1247729928187537, -0.24467419120495768, -2.6082673488459154, -0.7137866672064415, -0.5580839074054937, -1.198365123797158, -2.87641772791869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5170873720815716, 0.85111878546559, 1.0946343060215737, -1.192133538432852, -2.202595032702884, -0.43005904517215826, 1.5773329717200524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961007619495, -0.4403409101713919, 0.024521710933646846]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1865276348927471e-05, 0.0002801290214417316, 0.00012565432181280977, 0.0, 0.00035467878135150756, 0.0001555716910162052, 4.4266410315425116e-05, 0.0004455471609690459, -1.1484877837322644e-05, -0.00024577522353742175, -0.0001540525076079574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020288397498231026, 0.0367936400201483, -0.0862581580132528, -0.00485890831761699, -0.003850372663837832, 0.04136497187031095, 0.07287528281468234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.872635981013225e-09, -6.248363731130677e-09, -0.00030386377008570877]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923425164787207, 0.2345983814792764, 0.841050347506695, 0.0, -0.12475522292646406, -0.24466603816082416, -2.6082651926888545, -0.713764361211254, -0.5580844274851053, -1.1983773992061868, -2.876425460844925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5160622570306792, 0.8529551512103469, 1.09031236495632, -1.1923783374825825, -2.2028098565664673, -0.4279902694218642, 1.5809955887759293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961005111467, -0.4403409104823721, 0.02450649925825024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.163724258027144e-05, 0.0002804653772501444, 0.0001395686688296028, 0.0, 0.0003553978457929012, 0.0001630608826704875, 4.312314121554707e-05, 0.0004461199037493099, -1.0401592232705189e-05, -0.0002455081805767086, -0.00015465852470114935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02050230101784817, 0.03672731489513667, -0.08643882130507669, -0.004895980994609451, -0.004296477271664276, 0.041375515005881276, 0.073252341117538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.0160564280701034e-09, -6.219605362174422e-09, -0.0003042335079320552]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092336812073117, 0.23461241991371726, 0.8410561678621937, 0.0, -0.12473742219781848, -0.24465770728454195, -2.6082630802066746, -0.7137420285191424, -0.5580849074418099, -1.198389663027904, -2.8764332181693337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5150263785751835, 0.8547882069357311, 1.0859812336661037, -1.1926249875088784, -2.2030473162083246, -0.4259209411969448, 1.5846774624480346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961002514438, -0.44034091079192145, 0.024491270776937437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1408811207364125e-05, 0.0002807686888172977, 0.00011640710997282274, 0.0, 0.00035601457291151454, 0.00016661752564447262, 4.224964359557917e-05, 0.0004466538422316748, -9.599134091982837e-06, -0.0002452764343438294, -0.0001551464881691109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020717569109913524, 0.03666111450768433, -0.08662262580432678, -0.004933000525917938, -0.0047491928371491505, 0.041386564498387415, 0.07363747344210625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.194058572993528e-09, -6.190986860384029e-09, -0.00030456962625612414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092331222669531, 0.23462647193549757, 0.841052066079572, 0.0, -0.12471959924255467, -0.24464941954873765, -2.608260982624077, -0.713719670597397, -0.55808537708744, -1.1984019203027907, -2.8764409883123934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5139796698170055, 0.8566179539149585, 1.0816407643975692, -1.1928734852410094, -2.203307750057057, -0.4238510406151482, 1.5883789956931182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960999830891, -0.44034091110001405, 0.02447602713313368]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1178807172321633e-05, 0.00028104043560611415, -8.203565243488869e-05, 0.0, 0.00035645910527626145, 0.00016575471608629082, 4.195165195554541e-05, 0.00044715843490582383, -9.392912601900415e-06, -0.00024514549773298693, -0.00015540286119064626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02093417516356161, 0.03659493958454977, -0.08680938537068913, -0.004969954642621503, -0.005208676974652198, 0.04139801163593095, 0.07403066490167189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.367093402234195e-09, -6.1618522748371104e-09, -0.0003048728760751354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923257491223984, 0.23464053609047267, 0.8410419055366319, 0.0, -0.12470176364589647, -0.24464133781230815, -2.6082588665282125, -0.7136972887095854, -0.5580858710249742, -1.1984141770704049, -2.8764487579958957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5129220742543645, 0.8584443728070699, 1.077290855772315, -1.1931238248543903, -2.2035915028096063, -0.42178057102604194, 1.5921005596733184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960997096226, -0.440340911406489, 0.024460769881989263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0947094264936601e-05, 0.00028128309950176415, -0.0002032108588002307, 0.0, 0.00035671193316402056, 0.00016163472858988137, 4.232191728334855e-05, 0.0004476377562333042, -9.878750685222405e-06, -0.0002451353522834519, -0.00015539367005093068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021151911252818414, 0.03652837784222549, -0.08699817250508257, -0.005006792267617171, -0.005675055050982058, 0.04140939178212616, 0.07443127960400155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.469333852017078e-09, -6.129498761064716e-09, -0.00030514502288832664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923203945074248, 0.234654611139149, 0.8410329760044956, 0.0, -0.12468393783006151, -0.24463381737345521, -2.608256641870117, -0.7136748820675878, -0.5580864822372624, -1.1984264517189394, -2.876456493033111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5118535520675944, 0.86026741417937, 1.0729314763532303, -1.193375996563004, -2.2038989229339174, -0.4197095700785597, 1.59584247316251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960994386653, -0.4403409117110504, 0.024445500384940443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0709229947061336e-05, 0.0002815009735270556, -0.00017859064272867818, 0.0, 0.0003565163166989832, 0.00015040877705849477, 4.449316191303092e-05, 0.000448132839952295, -1.2224245764281534e-05, -0.00024549297069120405, -0.0001547007443032467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0213704437354033, 0.036460827446003485, -0.08718758838169695, -0.005043434172273638, -0.0061484024862227945, 0.041420018949645344, 0.07483826978383265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.41914580147142e-09, -6.091227530342086e-09, -0.00030538994097642047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923151539108384, 0.23466869601465398, 0.8410369603092293, 0.0, -0.12466610730241652, -0.24462629384666287, -2.6082543779253315, -0.7136524549442156, -0.5580871394853086, -1.1984387281294149, -2.876464218332244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5107740827551385, 0.8620869957374822, 1.0685626721506054, -1.1936299866938658, -2.2042303620937327, -0.41763811324967404, 1.5996049968703707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960991865436, -0.44034091201287073, 0.024430219834777226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0481193173066671e-05, 0.0002816975100991661, 7.968609467351684e-05, 0.0, 0.00035661055289996446, 0.00015047053584673302, 4.5278895708661466e-05, 0.0004485424674445845, -1.3144960923647588e-05, -0.0002455282095096486, -0.00015450598266201668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02158938624911852, 0.03639163116224268, -0.08737608405249829, -0.005079802617235855, -0.006628783196301097, 0.04142913657771301, 0.07525047415721449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.042432717502845e-09, -6.0364069223755525e-09, -0.0003056110032643384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923100283255752, 0.23468278982685334, 0.8410444950602779, 0.0, -0.12464825226265315, -0.24461829692062967, -2.6082521656327224, -0.713630011550289, -0.5580877491526708, -1.198450985861604, -2.8764719670998957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5096836649634202, 0.8639030045311199, 1.0641845631582998, -1.1938857771391707, -2.2045861721409685, -0.4155663116254859, 1.603388334133879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960989332096, -0.44034091231267136, 0.024414929235849793]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0251170526505469e-05, 0.00028187624398724346, 0.0001506950209727834, 0.0, 0.00035710079526729164, 0.00015993852066417723, 4.4245852182918864e-05, 0.0004488678785303976, -1.219334724283644e-05, -0.00024515464378050837, -0.0001549753530299669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021808355834365044, 0.03632017587275478, -0.08756217984611223, -0.005115808906095752, -0.007116200944715079, 0.041436032483762424, 0.07566674527016634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.066679126741525e-09, -5.996012086212419e-09, -0.00030581197854868307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923050216204658, 0.23469689186915452, 0.8410516616188889, 0.0, -0.12463037171473912, -0.24460994079275783, -2.6082500133720026, -0.7136075531239947, -0.5580883027034881, -1.1984632225123395, -2.8764797420544017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5085823128939614, 0.8657153051896176, 1.0597973256827151, -1.194143346163699, -2.2049667038536658, -0.4134943030747915, 1.6071926446615838, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196098671681, -0.44034091261067837, 0.024399629399881436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0013410218914426e-05, 0.00028204084602383465, 0.00014333117222068478, 0.0, 0.00035761095828053827, 0.00016712255743682876, 4.304521440058582e-05, 0.0004491685258869663, -1.1071016345658088e-05, -0.0002447330147117217, -0.00015549909012203795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022027041389176896, 0.03624601316995274, -0.08774474951169516, -0.0051513804905646155, -0.007610634253944473, 0.041440171013887465, 0.07608621055409705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.230571128178997e-09, -5.960140387646349e-09, -0.0003059967193671177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923001346662412, 0.23471100150640223, 0.8410570992865238, 0.0, -0.124612469576945, -0.24460141530682628, -2.6082479078840874, -0.7135850801968361, -0.5580888139089831, -1.1984754403653106, -2.876487537895516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5074700501760492, 0.867523751218759, 1.0554011660280609, -1.1944026698833945, -2.2053723078435907, -0.4114222395388834, 1.6110180667421843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960984004842, -0.440340912906907, 0.024384321059351226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.77390844932557e-06, 0.0002821927449540467, 0.000108753352697927, 0.0, 0.00035804275588250685, 0.00017050971863127144, 4.210975830491218e-05, 0.0004494585431732285, -1.0224109900509904e-05, -0.0002443570594232101, -0.0001559168222916129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022245254358245144, 0.036168920582829035, -0.08792319309308277, -0.005186474393909225, -0.008112079798501207, 0.04144127071816173, 0.07650844161200956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.423937811173064e-09, -5.924572664479066e-09, -0.0003061668106041999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092295368781185, 0.23472511812237018, 0.8410525567244167, 0.0, -0.12459455539927589, -0.24459298694859025, -2.608245811408167, -0.7135625925579099, -0.5580893217995248, -1.1984876469894246, -2.876495340225951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5063469036469429, 0.8693281958882545, 1.0509962948414044, -1.1946637235971365, -2.205803335645199, -0.40935027469185803, 1.6148647387961867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960981211883, -0.440340913201293, 0.024369004918805077]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.531770112582698e-06, 0.0002823323193592111, -9.085124214319048e-05, 0.0, 0.0003582835533821116, 0.00016856716472041987, 4.192951841072784e-05, 0.00044975277852422565, -1.0157810831525628e-05, -0.0002441324822768575, -0.00015604660869718368, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02246293058212572, 0.03608889338990902, -0.08809742373312995, -0.005221074274839436, -0.008620556032167825, 0.04143929694050713, 0.07693344108004997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.585919470088617e-09, -5.8877196347280575e-09, -0.00030632281092298554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922907254402637, 0.23473924097755533, 0.8410430468096177, 0.0, -0.12457664465750391, -0.24458494204825634, -2.6082436611804063, -0.7135400894695607, -0.558089891193906, -1.1984998552367652, -2.8765031252828543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5052128977614048, 0.871128501107967, 1.0465829055964682, -1.194926482883499, -2.2062601412752496, -0.4072785536904651, 1.6187328177432267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960978396832, -0.44034091349359755, 0.024353681801970777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.286681842308948e-06, 0.00028245710370275603, -0.00019019829597943813, 0.0, 0.00035821483543939294, 0.00016089800667815171, 4.3004555210236635e-05, 0.0004500617669834312, -1.1387887624443933e-05, -0.00024416494681227545, -0.00015570113806031218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022680117710762223, 0.03600610439425101, -0.08826778489872511, -0.005255185727246861, -0.009136112601008644, 0.04143442002785773, 0.07736157894079969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.630101619651346e-09, -5.8460912789013415e-09, -0.00030646233668602126]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092286203029788, 0.2347533691199173, 0.8410366097666756, 0.0, -0.12455873906782257, -0.24457712016806227, -2.608241455221437, -0.7135175725101464, -0.5580905242752763, -1.1985120646248903, -2.876510891702536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5040680507202013, 0.872924542990264, 1.042161160418863, -1.1951909245602055, -2.2067430834685604, -0.40520720662076, 1.6226224919949306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960975589218, -0.4403409137837116, 0.02433835273812638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.044820950828083e-06, 0.00028256284723898446, -0.00012874085884307046, 0.0, 0.00035811179362700286, 0.00015643760388143953, 4.411917938666845e-05, 0.0004503391882867604, -1.2661627407282987e-05, -0.00024418776250376096, -0.00015532839362946262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022896940824068145, 0.03592083764594023, -0.08843490355210347, -0.00528883353413279, -0.009658843866211879, 0.0414269413941024, 0.0777934850340786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6152266013673606e-09, -5.802281156345202e-09, -0.0003065812768879271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922817994548892, 0.23476750143913333, 0.8410317368181572, 0.0, -0.12454082133663524, -0.24456902851836237, -2.6082392747393492, -0.713495046101068, -0.5580911374821886, -1.1985242565890923, -2.87651866889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5029123732057359, 0.8747162132660619, 1.0377311860746754, -1.1954570270293148, -2.207252526997856, -0.40313634677010934, 1.6265339855381478, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960972813505, -0.4403409140713817, 0.024323018905498428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.807149797687654e-06, 0.0002826463843210159, -9.74589703665631e-05, 0.0, 0.0003583546237463803, 0.00016183299399782965, 4.360964175396415e-05, 0.00045052818156762596, -1.2264138246990007e-05, -0.0002438392840411457, -0.00015554380207734861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02311355028930857, 0.035833405515955936, -0.0885994868837508, -0.005322049382186002, -0.010188870585910479, 0.04141719701301333, 0.07822987086434155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5514245871595604e-09, -5.753402196005454e-09, -0.000306676652559026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922775208871658, 0.23478163673089025, 0.8410269189424823, 0.0, -0.12452290749927553, -0.2445610802733366, -2.60823705671734, -0.7134725099597611, -0.5580917959042532, -1.1985364438454809, -2.876526432828552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5017458688935809, 0.876503417771528, 1.0332930775127567, -1.1957247695296482, -2.2077888417223948, -0.4010660722071327, 1.6304675538598268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196097005762, -0.44034091435659856, 0.02430768157447591]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.557135447079631e-06, 0.00028270583513837535, -9.63575134987599e-05, 0.0, 0.00035827674719448194, 0.00015896490051578013, 4.4360440186066256e-05, 0.00045072282613815867, -1.3168441291317371e-05, -0.00024374512776992012, -0.00015527871823862847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023330086243100588, 0.03574409010932276, -0.08876217123837545, -0.005354850006668302, -0.010726294490778453, 0.041405491259532884, 0.07867136643357993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5117697080917796e-09, -5.704337183720439e-09, -0.00030674662045039944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092273364795529, 0.23479577360256368, 0.8410267217978544, 0.0, -0.12450499913756155, -0.2445531912725162, -2.6082348019596893, -0.7134499663025892, -0.5580924988772874, -1.1985486250627273, -2.876534182971404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5005685356159986, 0.8782860735546842, 1.0288469036469596, -1.1959941324338006, -2.2083524046662615, -0.3989964689225732, 1.6344234810585367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960967315432, -0.44034091463937164, 0.024292342210012866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.31218327346479e-06, 0.00028273743346835396, -3.942892555852602e-06, 0.0, 0.000358167234279383, 0.00015778001640777447, 4.50951530158411e-05, 0.0004508731434375434, -1.4059460683804483e-05, -0.00024362434492997581, -0.00015500285704769982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02354666555164614, 0.03565311566312634, -0.08892347731593916, -0.005387258083048048, -0.011271258877333048, 0.04139206569119055, 0.07911854397420086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4843783973253375e-09, -5.655461688257759e-09, -0.00030678728926084454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092269328669074, 0.2348099105758585, 0.8410328085718266, 0.0, -0.12448707681038215, -0.2445448705057502, -2.608232602889105, -0.7134274203571955, -0.5580931513025706, -1.1985607790395163, -2.876541952707773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4993803688712595, 0.880064103097541, 1.0243927211786348, -1.1962650965612587, -2.208943599389502, -0.3969276174649741, 1.6384020683100775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960964513507, -0.440340914919795, 0.02427700236992856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.072252910155402e-06, 0.00028273946589653745, 0.00012173547944455026, 0.0, 0.00035844654358794566, 0.0001664153353203612, 4.398141168845759e-05, 0.00045091890787210125, -1.3048505665113734e-05, -0.00024307953578067693, -0.00015539472737960248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023763334894781794, 0.03556059085713516, -0.08908364936649825, -0.005419282549162722, -0.011823894464809255, 0.04137702915198115, 0.07957174503081545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6038510622082095e-09, -5.608466697218602e-09, -0.00030679680168615704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922654166067067, 0.23482404617815011, 0.8410412273442239, 0.0, -0.12446914038951988, -0.24453622390550075, -2.608230468085501, -0.7134048745361499, -0.5580937444931828, -1.1985729027930856, -2.876549744394196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49818136574451966, 0.8818374283976583, 1.019930589651557, -1.1965376419472014, -2.2095628134221337, -0.3948595998606208, 1.6424036197278522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960961632773, -0.44034091519783325, 0.024261663614724982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.824124734902576e-06, 0.0002827120458322431, 0.0001683754479456738, 0.0, 0.0003587284172453867, 0.00017293200498848488, 4.2696072079051175e-05, 0.00045091642091311116, -1.1863812242775575e-05, -0.00024247507138728597, -0.00015583372845762609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023980062534796138, 0.035466506002346784, -0.08924263054155514, -0.00545090771885237, -0.012384280652634735, 0.04136035208706627, 0.08003102835549275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.761465067164659e-09, -5.5607647810329235e-09, -0.00030677510407153255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922616295505392, 0.23483817896123738, 0.8410490852513846, 0.0, -0.12445119489880907, -0.24452743829899679, -2.6082283837711637, -0.7133823305847966, -0.5580942928161348, -1.198584998145203, -2.8765575520800817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4969715275917248, 0.8836059669803608, 1.0154605812500674, -1.196811747499963, -2.2102104377362424, -0.39279250428916135, 1.6464284343560336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095867687, -0.44034091547339604, 0.024246327492719974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.574112335228865e-06, 0.0002826556617451584, 0.00015715814321276875, 0.0, 0.00035890981421632693, 0.00017571213007928167, 4.1686286744317405e-05, 0.0004508790270657108, -1.0966459037819545e-05, -0.00024190704235009058, -0.00015615371771426863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024196763055897286, 0.035370771654048096, -0.08940016802979006, -0.0054821110552363845, -0.012952486282172465, 0.04134191142918913, 0.0804962925636271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.911807805937267e-09, -5.5112561318106675e-09, -0.0003067224401001848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922579680585263, 0.23485230751964287, 0.8410551260082697, 0.0, -0.12443324572456714, -0.24451864694277212, -2.6082263344864067, -0.7133597902155533, -0.5580948123792668, -1.1985970672594228, -2.8765653691833957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49575086226104903, 0.8853696289438552, 1.0109827884664662, -1.1970873906083481, -2.2108868656457132, -0.39072642862796775, 1.65047679939993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960955656938, -0.4403409157463759, 0.024230995521878285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.322984026012576e-06, 0.0002825711681099264, 0.00012081513770211566, 0.0, 0.00035898348483850577, 0.00017582712449362893, 4.098569513964275e-05, 0.0004508073848668016, -1.0391262641673134e-05, -0.00024138228439390562, -0.0001563420662759655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02441330661351502, 0.035273239269888054, -0.0895558556720272, -0.005512862167700783, -0.013528558189413202, 0.04132151322387183, 0.08096730087792933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.039863141520829e-09, -5.459597199002481e-09, -0.00030663941683379875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922544348864547, 0.23486643055305054, 0.8410516600789181, 0.0, -0.12441531025423512, -0.24451022400760422, -2.608224252247095, -0.7133372533672377, -0.558095373430019, -1.198609123703882, -2.876573169694533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4945193854577599, 0.8871283156303824, 1.006497328144911, -1.1973645468070087, -2.2115924913823406, -0.388661482186963, 1.6545489860475655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095262447, -0.44034091601655695, 0.024215669123602613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.066344143356634e-06, 0.0002824606681536391, -6.931858703256564e-05, 0.0, 0.0003587094066402643, 0.00016845870335784188, 4.1644786232455846e-05, 0.00045073696631083623, -1.1221015042756142e-05, -0.00024112888918500513, -0.00015601022275316007, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02462953606578174, 0.035173733730543714, -0.08970920643110362, -0.00554312397321154, -0.014112514732550215, 0.041298928820095435, 0.0814437329527083, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0649334679944005e-09, -5.403621012739874e-09, -0.00030652796551343983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922510287796178, 0.23488054673289557, 0.8410453123797789, 0.0, -0.12439739345231203, -0.24450208979585292, -2.608222123215735, -0.7133147218632591, -0.5580959904178329, -1.198621169241677, -2.876580947616735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4932771206221174, 0.8888819200328602, 1.002004340587019, -1.1976431899810067, -2.2123277102860492, -0.38659778527636235, 1.658645250560513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196094961182, -0.44034091628382155, 0.02420034975651545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.812213673893282e-06, 0.00028232359690059553, -0.00012695398278336715, 0.0, 0.00035833603846176075, 0.00016268423502602524, 4.2580627199534485e-05, 0.00045063007957435767, -1.2339756277197146e-05, -0.00024091075590005698, -0.00015555844404097243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02484529671285001, 0.035072088049553814, -0.08985975115784277, -0.005572863479960354, -0.014704378074173489, 0.04127393821201264, 0.08192529025895022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0252987988901175e-09, -5.345292444117205e-09, -0.0003063873417432767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922477524753944, 0.23489465477246935, 0.8410452074994145, 0.0, -0.12437950954869476, -0.24449439493203598, -2.6082198931027345, -0.7132921961287746, -0.5580967194820536, -1.1986332144417962, -2.87658868200518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4920240985108147, 0.8906303281832448, 0.997503986963954, -1.1979232922787466, -2.2130929177335372, -0.38453546777582476, 1.6627658355278006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960946663445, -0.44034091654796714, 0.02418503883586631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.55260844684948e-06, 0.00028216079147531595, -2.0976072879545196e-06, 0.0, 0.0003576780723454631, 0.00015389727633898903, 4.460226001287e-05, 0.00045051468968865444, -1.4581284414749146e-05, -0.00024090400238012088, -0.00015468776889814983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025060442226055177, 0.03496816300769299, -0.0900070724612974, -0.005602045954796174, -0.015304148949760347, 0.0412463500107513, 0.08241169934575161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.896747979429786e-09, -5.282911832871913e-09, -0.0003062184129828008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922445995118852, 0.23490875335282946, 0.8410484974848362, 0.0, -0.12436162721644259, -0.2444862530313363, -2.6082177053556697, -0.7132696829483258, -0.5580974129435289, -1.1986452270616588, -2.876596425174763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49076035572194887, 0.8923734214703991, 0.9929964432129866, -1.198204825000671, -2.213888511169073, -0.38247466647819256, 1.6669109766511037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960943694733, -0.4403409168091144, 0.024169737799255797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.305927018371171e-06, 0.00028197160720243975, 6.57997084341371e-05, 0.0, 0.00035764664504322043, 0.00016283801399335354, 4.3754941293355606e-05, 0.00045026360897635297, -1.3869229504038548e-05, -0.0002402523972538747, -0.00015486339166848937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025274855777316755, 0.03486186574308656, -0.09015087501934801, -0.005630654438487442, -0.015911868710717047, 0.04121602595264391, 0.0829028224660603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.937423846599186e-09, -5.22294577457969e-09, -0.00030602073221025353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922415758091562, 0.2349228411724104, 0.8410526983818923, 0.0, -0.12434374248924537, -0.24447768873916056, -2.60821558440803, -0.7132471849890912, -0.5580980457685073, -1.19865720078781, -2.8766041854502538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4894859337370256, 0.8941110786251171, 0.9884818963113168, -1.1984877579817428, -2.214714887686934, -0.38041552288820757, 1.6710809034491936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960940678644, -0.4403409170672489, 0.02415444805994494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.047405458144199e-06, 0.0002817563916189022, 8.401794112132126e-05, 0.0, 0.0003576945439442653, 0.00017128584351477422, 4.241895279880636e-05, 0.0004499591846913434, -1.2656499568355628e-05, -0.00023947452302428265, -0.00015520550981206458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025488439698465194, 0.034753143094359555, -0.09029093803339643, -0.005658659621436673, -0.016527530357216394, 0.04118287179970025, 0.08339853596179836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.03217883464038e-09, -5.1626905210071585e-09, -0.00030579478621716805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922386825645328, 0.23493691690624557, 0.8410564512649941, 0.0, -0.1243258594111105, -0.24446889925952728, -2.6082135201018084, -0.7132247038994421, -0.5580986285853954, -1.1986691367474456, -2.8766119583016656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48820087632289133, 0.8958431793631576, 0.983960534776307, -1.1987720604255176, -2.2155724461756536, -0.3783581789414705, 1.6752758485502535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960937612354, -0.4403409173222983, 0.024139171052652106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786489246427161e-06, 0.0002815146767031294, 7.505766203420739e-05, 0.0, 0.00035766156269743726, 0.00017578959266584843, 4.1286124428578224e-05, 0.0004496217929827031, -1.1656337761063967e-05, -0.00023871919271227572, -0.00015545702823389334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025701148282685583, 0.03464201476081067, -0.09042723070019727, -0.005686048875495764, -0.017151169774387676, 0.04114687893474189, 0.08389890202119733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.132577920404379e-09, -5.1009871084421215e-09, -0.00030554014585668624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092235922605165, 0.23495097923899583, 0.8410519427358509, 0.0, -0.12430799797295512, -0.24446039171558423, -2.6082114331239783, -0.7132022392024135, -0.5580992433130904, -1.1986810509852375, -2.8766197135440503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4869052277139634, 0.8975696069788188, 0.9794325421284801, -1.1990577012557722, -2.2164615881936442, -0.37630277396989964, 1.679496053466264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960934548712, -0.4403409175740272, 0.024123908203004432]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.519918735469442e-06, 0.0002812466550050523, -9.017058286262138e-05, 0.0, 0.0003572287631076722, 0.00017015087886112826, 4.173955660569902e-05, 0.00044929394057188977, -1.2294553899290337e-05, -0.00023828475583984556, -0.00015510484769303776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025912972178559337, 0.034528552313223757, -0.09055985295653808, -0.005712816605088591, -0.017782840359812042, 0.04110809943141729, 0.08440409832021027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.127284994485085e-09, -5.034578465706776e-09, -0.0003052569929535026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922332950507752, 0.23496502672304753, 0.841047783413629, 0.0, -0.12429016966556214, -0.24445225590891467, -2.60820928186934, -0.7131797919809006, -0.5580999330293639, -1.1986929512033815, -2.8766274348355845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48559903131642573, 0.8992902496173529, 0.9748980930181969, -1.199344649530385, -2.2173827195828784, -0.3742494430608768, 1.6837417729196484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196093153261, -0.44034091782227236, 0.02410866107571083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.2551087796667704e-06, 0.0002809496810341711, -8.318644443892944e-05, 0.0, 0.00035656614785969763, 0.0001627161333910628, 4.3025092769582105e-05, 0.0004489444302589652, -1.3794325470608606e-05, -0.0002380043628809906, -0.000154425830679982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02612392795075296, 0.03441285277068236, -0.09068898220566399, -0.005738965492258566, -0.018422627784678763, 0.04106661818045598, 0.08491438906769068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0322003801230195e-09, -4.964903312858732e-09, -0.0003049425458720436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922307991070202, 0.23497905786820408, 0.8410556573019119, 0.0, -0.12427237387831729, -0.2444442940500671, -2.608207077567316, -0.7131573652116887, -0.5581006863642975, -1.1987048335720254, -2.8766351253435607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4842823300878567, 0.9010049998697255, 0.9703573543408388, -1.1996328745291291, -2.2183362506259474, -0.3721983176407974, 1.6880132741548193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960928754658, -0.44034091806592374, 0.024093431277851397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.991887509777812e-06, 0.0002806229031311392, 0.00015747776565822725, 0.0, 0.0003559157448970038, 0.00015923717695157525, 4.408604048309066e-05, 0.00044853538423953636, -1.5066698673928943e-05, -0.00023764737287945692, -0.00015381015952641166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026334024571381103, 0.0342950050474507, -0.09081477354716017, -0.005764499974883995, -0.01907062086137703, 0.041022508401587915, 0.08543002470341639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.555908666280711e-09, -4.8730279323739366e-09, -0.00030459595718869284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922284323115387, 0.23499307108162593, 0.8410620224473074, 0.0, -0.12425458744531685, -0.24443588510526554, -2.608204929517324, -0.7131349647765528, -0.5581013908433606, -1.1987166731633414, -2.8766428246415074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48295516731288507, 0.9027137532260882, 0.9658104886496258, -1.1999223453926828, -2.219322595734824, -0.37014952706588417, 1.6923108338763249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960925990926, -0.4403409183058999, 0.024078220512936645]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.7335909628940805e-06, 0.00028026426843671655, 0.00012730290790996507, 0.0, 0.00035572866000864066, 0.00016817889603117935, 4.296099983475214e-05, 0.00044800870271772164, -1.408958126273807e-05, -0.0002367918263207148, -0.00015398595893936561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02654325549943236, 0.034175067127253114, -0.09093731382426007, -0.005789417271074297, -0.019726902177531216, 0.040975811498265485, 0.08595119443011036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527463615746055e-09, -4.799523095846143e-09, -0.0003042152982949902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922261997224498, 0.2350070647912494, 0.8410577045336366, 0.0, -0.12423681243828566, -0.24442719122016499, -2.6082028373758583, -0.7131125929317202, -0.5581020469926288, -1.1987284688445206, -2.876650531726507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48161758806816896, 0.904416406601707, 0.9612576589459293, -1.2002130305739471, -2.2203421712282, -0.36810320061496893, 1.696634732660511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196092317279, -0.44034091854252083, 0.024063030469186026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.465178177833702e-06, 0.00027987419246927657, -8.635827341689408e-05, 0.0, 0.00035550014062387086, 0.00017387770201113094, 4.184282931522522e-05, 0.000447436896650261, -1.3122985361760713e-05, -0.0002359136235845094, -0.0001541416999878178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026751584894322514, 0.034053067512376585, -0.09105659407393087, -0.005813703625287087, -0.020391509867517234, 0.04092652901830437, 0.08647797568372015, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.636273932491716e-09, -4.732419414340443e-09, -0.00030380087501240055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922241016812146, 0.23502103740905048, 0.8410463694385787, 0.0, -0.12421905333043677, -0.24441836995158422, -2.608200790619741, -0.7130902517633231, -0.5581026658436722, -1.198740221602538, -2.8766582417647193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48026963952599694, 0.9061128577303539, 0.9566990298493572, -1.20050489804106, -2.221395396086243, -0.36605946817557733, 1.700985254766309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960920279746, -0.44034091877582304, 0.024047862863995576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.1960824706491225e-06, 0.0002794523560217615, -0.0002267019011576197, 0.0, 0.00035518215697770964, 0.00017642537161540508, 4.0935122353427696e-05, 0.0004468233679431487, -1.2377020867531316e-05, -0.00023505516034913785, -0.00015420076425019393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026958970843440316, 0.03392902257293763, -0.09117258193144308, -0.005837349342256303, -0.02106449716086064, 0.04087464878783213, 0.08701044211595904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786086760284027e-09, -4.666044771786301e-09, -0.00030335210380902497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922221440887018, 0.23503498739762702, 0.841036886455467, 0.0, -0.1242013481825966, -0.24441026653189415, -2.608198632835657, -0.7130679387372286, -0.5581034088108263, -1.1987519639596742, -2.876665895865233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4789113717793767, 0.9078030043511358, 0.9521347702517232, -1.200797914844916, -2.222482690370258, -0.3640184612869564, 1.7053626847014656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196091741422, -0.4403409190052954, 0.024032719370823248]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.915185025717901e-06, 0.0002789997715310093, -0.0001896596622333224, 0.0, 0.00035410295680355535, 0.0001620683938012719, 4.315568167552039e-05, 0.0004462605218899997, -1.4859343083454556e-05, -0.0002348471427225327, -0.00015308201027994006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027165354932404285, 0.03380293241563895, -0.09128519195267903, -0.005860336077119565, -0.021745885680302154, 0.04082013777241842, 0.08754859870313353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.731050726891179e-09, -4.58944610775106e-09, -0.0003028698634465459]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922203164538525, 0.23504891307276912, 0.841032541842507, 0.0, -0.12418366740896726, -0.24440192084839657, -2.6081965020990285, -0.7130456612191032, -0.5581041338020172, -1.1987636644722774, -2.876673544051086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4775428382354116, 0.9094867432162603, 0.9475650547121593, -1.2010920480404839, -2.223604478160592, -0.3619803142765615, 1.7097673090060426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960914598313, -0.4403409192310516, 0.02401760180827296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.655269698775106e-06, 0.00027851350284206105, -8.689225920218913e-05, 0.0, 0.00035361547258678437, 0.00016691366995180907, 4.2614732565614394e-05, 0.00044555036250906017, -1.4499823817667592e-05, -0.00023401025206547227, -0.0001529637170595984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027370670879302096, 0.033674777302491084, -0.09139431079127737, -0.005882663911359049, -0.022435755806672526, 0.04076294020789779, 0.08809248609153901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.631816940030336e-09, -4.515125428379149e-09, -0.0003023512510057976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218624636338, 0.23506281281421168, 0.8410356756575126, 0.0, -0.12416600432264169, -0.24439321694763538, -2.608194436426376, -0.7130234228233399, -0.5581048018148895, -1.1987753136380845, -2.876681199480581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47616409798292436, 0.9111639678647261, 0.9429900709564467, -1.2013872631601683, -2.224761182138141, -0.3599451670496676, 1.7141994056720824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960911738547, -0.44034091945324066, 0.024002511926413173]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383635029025387e-06, 0.00027799482885125325, 6.26763001119526e-05, 0.0, 0.00035326172651137423, 0.0001740780152235415, 4.131345304538199e-05, 0.00044476791526665467, -1.3360257447749238e-05, -0.00023298331614080524, -0.0001531085898994188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027574805049744477, 0.03354449296931504, -0.09149967511425215, -0.005904302393688978, -0.023134079550981332, 0.04070294453787818, 0.08864193332079673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.719530654727784e-09, -4.443781211465503e-09, -0.0003017976371957132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922170704203732, 0.23507668502075083, 0.8410423074849374, 0.0, -0.1241483623155468, -0.244384310557527, -2.6081924300125126, -0.7130012257667365, -0.5581054190160493, -1.1987869114340584, -2.876688859076571, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47477521540227136, 0.9128345692861699, 0.9384100182269607, -1.20168352459866, -2.225953224315494, -0.35791316440846443, 1.7186592461985255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960908809377, -0.44034091967180033, 0.02398745145288188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1084319293768643e-06, 0.00027744413078277237, 0.0001326365484943806, 0.0, 0.00035284014189772793, 0.00017812780216790056, 4.01282772728635e-05, 0.00044394113206605953, -1.2344023195454017e-05, -0.00023195591947688265, -0.00015319191979646822, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02777765161305974, 0.033412028428875376, -0.09160105458971957, -0.0059252287698322425, -0.02384084354705729, 0.04064005282406402, 0.08919681052886042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.858339466261557e-09, -4.371193406864528e-09, -0.00030120947062583256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922156543450052, 0.23509052810004516, 0.8410492694389827, 0.0, -0.12413074689682618, -0.24437535618911002, -2.6081904678915984, -0.712979072046481, -0.5581060010212636, -1.1987984597786585, -2.8766965163409224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47337625952659734, 0.9144984368578705, 0.9338251048857156, -1.2019807958468574, -2.2271810265116145, -0.3558844549669417, 1.7231470978947316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960905813695, -0.44034091988659374, 0.023972422108249798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8321507362843026e-06, 0.00027686158588654494, 0.00013923908090758875, 0.0, 0.00035230837441229307, 0.00017908736833938907, 3.9242418287363135e-05, 0.0004430744051094812, -1.1640104287746735e-05, -0.00023096689200289316, -0.00015314528703072957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02797911751348016, 0.03327735143401081, -0.09169826682490159, -0.00594542496394866, -0.024556043922417028, 0.0405741888304541, 0.08975703392412263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.99136182881903e-09, -4.295868409399808e-09, -0.00030058689264164613]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092214376950768, 0.2351043404631002, 0.841055000947925, 0.0, -0.12411316316685755, -0.24436644803037927, -2.6081885369185116, -0.7129569637734708, -0.5581065615745155, -1.1988099601669355, -2.8767041654304397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4719673035386995, 0.916155459116594, 0.9292355465253229, -1.2022790396236822, -2.228445010501852, -0.3538591902620027, 1.7276632254874882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196090276409, -0.44034092009746506, 0.023957425614455224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.554788474152601e-06, 0.00027624726110047753, 0.00011463017884518368, 0.0, 0.0003516745993725979, 0.000178163174614961, 3.861946173756925e-05, 0.0004421654602037304, -1.1211065038467111e-05, -0.00023000776553994804, -0.0001529817903483625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02817911975795758, 0.033140445174471, -0.09179116720785228, -0.005964875536498757, -0.025279679804751456, 0.04050529409878031, 0.0903225518551289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.099211472283008e-09, -4.217426245952425e-09, -0.00029992987589149664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132402106286, 0.23511812054038544, 0.8410520894025295, 0.0, -0.12409562383109912, -0.2443578314158735, -2.608186590890484, -0.712934902017406, -0.5581071484951111, -1.1988214212369817, -2.8767117882556934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47054842423382764, 0.9178055245993192, 0.9246415639932796, -1.202578217928743, -2.229745597925077, -0.3518375237867856, 1.7322078925422681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196089970556, -0.4403409203040926, 0.023942463678312494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2734802787669106e-06, 0.00027560154570521126, -5.8230907909955594e-05, 0.0, 0.000350786715168619, 0.0001723322901152663, 3.892056055380001e-05, 0.00044123512129748107, -1.1738411910820731e-05, -0.0002292214009220766, -0.0001524565050773675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028377586097436923, 0.033001309654503014, -0.09187965064086771, -0.0059835661012142315, -0.02601174846449523, 0.0404333295043409, 0.09089334109560107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.1170619527525975e-09, -4.1325504136064795e-09, -0.00029923872285463716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922122434115142, 0.23513186671753447, 0.8410480627601596, 0.0, -0.12407813314545002, -0.24434945545829273, -2.608184620574443, -0.7129128891496048, -0.5581077715045112, -1.198832843569758, -2.8767193803773026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4691197012732411, 0.9194485226447213, 0.9200433810360168, -1.2028782923185342, -2.2310832111884804, -0.34981960999287814, 1.7367813640484877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960896649155, -0.44034092050638907, 0.02392753805860094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.993598228687448e-06, 0.0002749235429804493, -8.053284739664491e-05, 0.0, 0.00034981371298213994, 0.00016751915161527365, 3.9406320815882495e-05, 0.0004402573560225493, -1.2460188001387484e-05, -0.00022844665552575148, -0.00015184243218659447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028574459211730487, 0.032859960908041684, -0.09196365914525552, -0.006001487795825586, -0.026752265268074542, 0.04035827587814968, 0.09146943012439056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.112808490593471e-09, -4.045929541332256e-09, -0.00029851239423111863]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211389827854, 0.23514557736365363, 0.8410578585477725, 0.0, -0.12406070988152301, -0.24434158934098602, -2.608182553769859, -0.7128909254979008, -0.5581085052234442, -1.1988442413850604, -2.8767269140492373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4676812169158026, 0.9210843438719359, 0.9154412233761499, -1.2031792237209296, -2.2324582726969604, -0.3478056037279826, 1.741383906369289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960893591872, -0.44034092070432945, 0.023912650529372945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7071673205114855e-06, 0.00027421292238309636, 0.00019591575225744434, 0.0, 0.00034846527854018143, 0.000157322346134472, 4.133609168080293e-05, 0.0004392730340808338, -1.4674378662152341e-05, -0.00022795630604805403, -0.00015067343869631415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02876968714876997, 0.032716424544291745, -0.09204315319733973, -0.006018628047907992, -0.027501230169602837, 0.0402801252979109, 0.09205084641602652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.114568185997018e-09, -3.958807443717854e-09, -0.0002977505845598786]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210672469882, 0.23515925083401482, 0.8410652320488057, 0.0, -0.12404332566823896, -0.24433336627992613, -2.608180522997439, -0.7128690180598636, -0.5581092132659031, -1.1988555845615416, -2.876734437299029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46623305579286745, 0.9227128804080058, 0.9108353175470177, -1.2034809732727259, -2.2338712072731286, -0.3457956600814619, 1.7460157904635891, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960890519567, -0.44034092089783095, 0.02389780286694324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4347159446389079e-06, 0.00027346940722347367, 0.00014747002066334785, 0.0, 0.0003476842656809194, 0.00016446122119761613, 4.0615448397339356e-05, 0.0004381487607450033, -1.4160849177094524e-05, -0.00022686352962361731, -0.00015046499583523993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896322245870369, 0.03257073072139712, -0.09211811658264313, -0.00603499103592687, -0.028258691523363376, 0.04019887293041388, 0.09263768188600079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.144607672069865e-09, -3.870029836860596e-09, -0.0002969532485941604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210100400509, 0.23517288551398433, 0.8410664138041404, 0.0, -0.1240259996089749, -0.24432528532443024, -2.608178454395147, -0.7128471669546982, -0.5581099719448497, -1.198866887773201, -2.8767419218274246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4647753056448859, 0.9243340253193703, 0.9062258936717704, -1.2037835010299036, -2.235322437674143, -0.3437899350125588, 1.750677285561212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960887517417, -0.44034092108648143, 0.023882996819733292]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1441387459766836e-06, 0.0002726935993901465, 2.3635106694689962e-05, 0.0, 0.00034652118528124735, 0.0001616191099181937, 4.1372045842379415e-05, 0.0004370221033072508, -1.5173578930017302e-05, -0.0002260642331865976, -0.00014969056791598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029155002959631346, 0.03242289822728867, -0.09218847750494656, -0.006050555143554061, -0.029024608020289562, 0.04011450137806245, 0.09322990195245989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.004299680337448e-09, -3.7730098884789655e-09, -0.0002961209441989173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092209669726632, 0.23518647970489048, 0.8410609226416369, 0.0, -0.12400872906868333, -0.24431719191532206, -2.608176369004111, -0.7128253755692321, -0.5581107597717642, -1.1988781450453656, -2.876749374387809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4633080561386832, 0.9259476735196431, 0.9016131818317626, -1.2040867669585253, -2.236812388228808, -0.34178858417897373, 1.7553686651971052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960884538656, -0.44034092127040986, 0.023868234227515342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.613477534914119e-07, 0.00027188381812338203, -0.00010982325006922625, 0.0, 0.000345410805831185, 0.00016186818216330927, 4.170782071484811e-05, 0.0004358277093212305, -1.575653829063398e-05, -0.00022514544329536624, -0.0001490512076832327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029344990124054126, 0.03227296400545834, -0.09225423680015506, -0.006065318572435898, -0.02979901109329317, 0.0400270166717004, 0.09382759271786134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.957524940023932e-09, -3.6785690750768175e-09, -0.0002952518443589767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093822929072, 0.2352000317341201, 0.8410524181684602, 0.0, -0.12399151746904731, -0.24430910863530028, -2.608174261444083, -0.7128036463850764, -0.5581115824848359, -1.1988893561534155, -2.876756791973215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46183139963036696, 0.9275537212519152, 0.8969974141792522, -1.2043907305783736, -2.238341482998964, -0.3397917636906221, 1.7600902039997306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960881578726, -0.4403409214495698, 0.0238535169087839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.748674497860114e-07, 0.0002710405845922016, -0.00017008946353326963, 0.0, 0.0003442319927206149, 0.0001616656004355191, 4.215120056168994e-05, 0.00043458368311318613, -1.645426143494226e-05, -0.0002242221609999945, -0.00014835170811919904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029533130166324435, 0.03212095464544021, -0.09231535305020915, -0.006079272396967082, -0.030581895403125385, 0.039936409767033054, 0.09443077605250862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.91986084688446e-09, -3.5831994274456708e-09, -0.0002943463746288033]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373323128, 0.23521353992827793, 0.8410438725266971, 0.0, -0.12397436044111262, -0.244300887496518, -2.6081721601693726, -0.7127819829808627, -0.558112410947662, -1.1989005135506143, -2.876764184099484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4603454313905481, 0.9291520657795702, 0.8923788256592536, -1.204695351075815, -2.239910145922031, -0.33779963049762673, 1.7648421773105925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960878624786, -0.4403409216239188, 0.023838846682848473]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8992118888876934e-07, 0.0002701638831565353, -0.00017091283526128758, 0.0, 0.0003431405586938345, 0.00016442277564585636, 4.202549420018781e-05, 0.00043326808427352663, -1.6569256520598532e-05, -0.00022314794397777974, -0.0001478425253884784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029719364796376244, 0.03196689055310157, -0.09237177039997145, -0.006092409948825406, -0.031373258461334215, 0.03984266385990679, 0.09503946621723514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907879199330411e-09, -3.486980077253522e-09, -0.00029340451870856404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373722798, 0.23522700262504698, 0.8410374403757168, 0.0, -0.12395726578111037, -0.24429269050492022, -2.6081700407288655, -0.7127603871926259, -0.5581132705496118, -1.1989116211622244, -2.8767715407119447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.458850249996433, 0.9307426050694383, 0.8877576552539141, -1.2050005870186693, -2.2415187994729133, -0.3358123427934258, 1.7696248590278236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196087569427, -0.4403409217933179, 0.023824225354744655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.993361838705048e-11, 0.0002692539353811438, -0.00012864301960679008, 0.0, 0.0003418932000452387, 0.00016393983195510124, 4.2388810139131095e-05, 0.0004319157647347982, -1.719203899706572e-05, -0.00022215223220196987, -0.00014713224921229104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029903627882302698, 0.03181078579736128, -0.09242340810678894, -0.006104718857087361, -0.03217307101764898, 0.039745754084018536, 0.09565363434462144, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.861033564134219e-09, -3.387982440439172e-09, -0.0002924265620763873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093803793915, 0.23524041814845156, 0.8410374906842297, 0.0, -0.12394022730095001, -0.2442843307062041, -2.6081679394647272, -0.712738862857545, -0.558114124022187, -1.198922669739127, -2.8767788742441045, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4573459573374052, 0.9323252377254454, 0.8831341459157536, -1.2053063966618953, -2.2431678654292573, -0.33383006012496247, 1.7744385224039096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960872769383, -0.4403409219577329, 0.02380965473961995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.860142235474362e-07, 0.0002683104680918212, 1.0061702575075656e-06, 0.0, 0.0003407696032069348, 0.00016719597432282023, 4.202528276281991e-05, 0.00043048670161862127, -1.706945150298024e-05, -0.0002209715380559683, -0.0001466706431985636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03008585318055555, 0.031652653120141615, -0.09247018676321055, -0.00611619286451865, -0.032981319126879634, 0.039645653369266835, 0.09627326752172037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.849774123333481e-09, -3.2882997372638714e-09, -0.0002914123024940956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922096657396688, 0.2352537848481625, 0.8410424879608319, 0.0, -0.12392323099804707, -0.24427550322994218, -2.608165926451545, -0.7127174147928246, -0.5581148993177725, -1.1989336427949417, -2.876786209655038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4558326592403161, 0.9338998624960788, 0.8785085463058647, -1.2056127377883856, -2.2448577636846556, -0.3318529440691488, 1.7792834377311177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960869837198, -0.44034092211708964, 0.023795136622358486]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.707205544453632e-07, 0.00026733399421898104, 9.99455320436035e-05, 0.0, 0.00033992605805876916, 0.00017654952523818242, 4.026026364787405e-05, 0.00042896129440782137, -1.550591171088359e-05, -0.0002194611162937864, -0.000146708218664564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030265961941782726, 0.03149249541266861, -0.09251199219777764, -0.0061268225298059045, -0.03379796510796265, 0.039542321116274225, 0.09689830654416252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.86437310864071e-09, -3.187134913313221e-09, -0.00029036234522933065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922100965552448, 0.23526710107514773, 0.8410490640684287, 0.0, -0.12390627994451152, -0.2442664026430487, -2.60816399756591, -0.7126960453592284, -0.5581156008578939, -1.198944539937928, -2.8767935444610173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4543104655338203, 0.9354663782831726, 0.8738811111354717, -1.2059195673919778, -2.246588910859805, -0.3298811581868147, 1.7841598707715598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960866898349, -0.4403409222713018, 0.023780672785392188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.616311522513805e-07, 0.0002663245397044324, 0.0001315221519361624, 0.0, 0.000339021070711086, 0.0001820117378696219, 3.857771269517252e-05, 0.0004273886719234314, -1.4030802428831007e-05, -0.00021794285972423394, -0.0001466961195899939, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030443874129915626, 0.031330315741874865, -0.09254870340785973, -0.006136592071843622, -0.03462294350299033, 0.039435717646682064, 0.09752866080883925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.877696582075045e-09, -3.0842428966251893e-09, -0.00028927673932593894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210673237465, 0.235280365187046, 0.8410550975979828, 0.0, -0.12388938100491373, -0.24425724891563522, -2.608162132255566, -0.7126747564615128, -0.5581162500032212, -1.1989553642943187, -2.8768008700700447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4527794894455337, 0.9370246848142204, 0.8692520991614596, -1.2062268420164741, -2.2483617212788136, -0.3279148672301889, 1.7890680851332526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960863958802, -0.4403409224202819, 0.023766265007226756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1533644406949973e-06, 0.00026528223796546833, 0.00012067059108091881, 0.0, 0.00033797879195573256, 0.00018307454826957186, 3.73062068809094e-05, 0.00042577795431106595, -1.2982906544877191e-05, -0.0002164871278149365, -0.00014651218054448473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030619521765731874, 0.031166130620956245, -0.09258023948024134, -0.006145492489924126, -0.03545620838017727, 0.03932581913251551, 0.09816428723385391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.879091789393594e-09, -2.979601671892309e-09, -0.0002881555633086335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211398984335, 0.2352935755878579, 0.8410555050831465, 0.0, -0.12387255996124569, -0.24424862974986714, -2.6081602276898908, -0.7126535474193972, -0.5581169529252559, -1.198966136758033, -2.8768081474179703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4512398472649066, 0.9385746831577152, 0.8646217720329866, -1.20653451772497, -2.2501766065511055, -0.32595423653796046, 1.7940083427031794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960861098235, -0.4403409225636437, 0.023751915023692883]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.451493739797756e-06, 0.0002642080162376779, 8.149703274743813e-06, 0.0, 0.0003364208733607873, 0.00017238331536136223, 3.809131350543452e-05, 0.00042418084231146783, -1.4058440694780964e-05, -0.00021544927428580668, -0.00014554695851592048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03079284361254177, 0.030999966869896325, -0.0926065425694596, -0.00615351416991691, -0.036297705445837984, 0.03921261384456869, 0.09880515139853736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.721133778020836e-09, -2.8672360332484574e-09, -0.00028699967067747945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221227393265, 0.23530673061450377, 0.8410565945129704, 0.0, -0.12385584263010913, -0.24424086611527335, -2.608158181332645, -0.7126324177743517, -0.5581178155082985, -1.1989768780505843, -2.8768153374764402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4496916576505383, 0.9401162761748174, 0.8599903925518251, -1.2068425503342475, -2.252033976608772, -0.3239994313693354, 1.798980905793647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960858334568, -0.4403409227013466, 0.02373762464347082]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.749896630280465e-06, 0.0002631005329173592, 2.1788596477419196e-05, 0.0, 0.00033434662273115046, 0.00015527269187593876, 4.092714491516038e-05, 0.0004225929009102559, -1.7251660853081745e-05, -0.0002148258510234415, -0.00014380116939687583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030963792287366225, 0.03083186034204511, -0.09262758962322996, -0.006160652185548577, -0.037147401153326536, 0.0390961033725009, 0.09945126180934931, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527332100915927e-09, -2.7540586281405656e-09, -0.0002858076044412479]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132919391548, 0.23531982864719386, 0.841063223931719, 0.0, -0.1238392122362804, -0.24423321920061875, -2.6081560758377376, -0.7126113735463446, -0.5581187527877131, -1.1989875685837716, -2.8768224695965015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44813504236501883, 0.941649368224787, 0.8553582259425409, -1.2071508962014381, -2.2539342407502954, -0.3220506177501416, 1.8039860375006576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196085635504, -0.44034092283093423, 0.023723395630806134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.03601300906797e-06, 0.0002619606538019357, 0.0001325883749712573, 0.0, 0.0003326078765743858, 0.000152938293091898, 4.210989814999217e-05, 0.0004208845601416009, -1.8745588290554045e-05, -0.00021381066374907771, -0.00014264240122127474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031132305710390124, 0.030661840999390497, -0.09264333218568391, -0.006166917343814103, -0.03800528283046801, 0.038976272383875785, 0.10010263414021117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.959053397238659e-09, -2.5917525910362977e-09, -0.00028458025329374653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922144519139135, 0.2353328680869434, 0.8410676669346647, 0.0, -0.12382263726512502, -0.24422491913739267, -2.6081540567514145, -0.7125904214700881, -0.5581196148820815, -1.1989981758353803, -2.8768295968508615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4465701270552781, 0.9431738636921824, 0.8507255432224222, -1.207459510790999, -2.2558778039573784, -0.3201079635102819, 1.8090239953968683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960854533182, -0.4403409229545072, 0.023709229726479042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199495176391782e-06, 0.00026078879499084965, 8.886005891627416e-05, 0.0, 0.0003314994231077098, 0.00016600126452181964, 4.038172646392046e-05, 0.00041904152513015484, -1.7241887368174105e-05, -0.0002121450321726098, -0.00014254508720348415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03129830619481516, 0.030489909347908482, -0.09265365440237223, -0.006172291791215753, -0.03887126414166291, 0.038853084797193384, 0.1007591579242136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.643715639193411e-09, -2.4714595723696988e-09, -0.00028331808654188023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922157604694372, 0.23534584736592495, 0.8410668504909772, 0.0, -0.12380612670554354, -0.24421636926187285, -2.6081520936769205, -0.7125695627130906, -0.5581204332535905, -1.1990087053101475, -2.8768367071660017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4449970414885467, 0.94468966757663, 0.8460926213960657, -1.2077683487512805, -2.2578650650041974, -0.3181716381099931, 1.8140950299117282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960852664008, -0.44034092307275113, 0.023695128639661108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6171110473867365e-06, 0.0002595855796310719, -1.6328873750977248e-05, 0.0, 0.0003302111916294966, 0.00017099751039630092, 3.9261489880747366e-05, 0.0004171751399507709, -1.636743018040559e-05, -0.0002105894953461487, -0.00014220630280115963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146171133462829, 0.030316077688951552, -0.09265843652713089, -0.006176759205631756, -0.0397452209363828, 0.038726508005776, 0.1014206902972002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.738346712078653e-09, -2.3648780842152937e-09, -0.00028202173635868386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922172187093444, 0.235358764914175, 0.8410654898822433, 0.0, -0.12378970357889556, -0.24420812020919186, -2.608150095496031, -0.7125487967681349, -0.5581213019711135, -1.1990191755044783, -2.8768437658949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4434159178476597, 0.9461966869587102, 0.8414597384723083, -1.2080773645313565, -2.2598964193485593, -0.31624181071038876, 1.8191993904816701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960850686543, -0.4403409231858745, 0.023681094082104545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.916479814417497e-06, 0.00025835096500088103, -2.721217467799101e-05, 0.0, 0.0003284625329597579, 0.00016498105361986836, 3.996361778996376e-05, 0.00041531889911317413, -1.7374350460272283e-05, -0.00020940388661766464, -0.00014117457796544163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03162247281773904, 0.03014038764160504, -0.09265765847514915, -0.006180315601519984, -0.040627086887241, 0.038596547992087005, 0.10208721139883624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.954931207271424e-09, -2.2624669460461017e-09, -0.00028069115113125986]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218820509567, 0.2353716191701673, 0.8410633476626547, 0.0, -0.1237733545919424, -0.24419974024874178, -2.6081481290056185, -0.7125281285220432, -0.5581221523588407, -1.1990295706059233, -2.8768507967261296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44182689050891993, 0.9476948312002192, 0.8368271724979245, -1.2083865130951508, -2.2619722611590123, -0.31431865007858156, 1.824337328212959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960848777775, -0.44034092329331354, 0.02366712775352238]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2036004456094876e-06, 0.0002570851198458028, -4.28443917725028e-05, 0.0, 0.00032697973906325436, 0.00016759920900176153, 3.932980824228668e-05, 0.000413364921835116, -1.7007754542764683e-05, -0.00020790202889795674, -0.0001406166245909901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03178054677479595, 0.02996288483018038, -0.09265131948767472, -0.006182971275886583, -0.04151683620905522, 0.038463212636144044, 0.10275875462577573, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.817535953222311e-09, -2.1487807233846523e-09, -0.00027932657164330354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221916360722, 0.23538440877937317, 0.84113623431204, 0.0, -0.12375716825404547, -0.24419305877140782, -2.608145824566453, -0.7125075583188882, -0.5581233419857754, -1.1990400234739393, -2.87685766726029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44024420765108996, 0.9491709563510456, 0.832235792593017, -1.208693270166394, -2.2640751584080365, -0.31229657903902314, 1.829464531952495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960847210564, -0.4403409233974491, 0.023653231142714507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.861953054122794e-07, 0.000255792184117114, 0.0014577329877055664, 0.0, 0.00032372675793870207, 0.00013362954667919574, 4.6088783318532606e-05, 0.0004114040630983184, -2.3792538695589267e-05, -0.0002090573603190461, -0.0001374106832015365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03165365715659935, 0.02952250301652904, -0.0918275980981496, -0.006135141424863823, -0.04205794498048291, 0.04044142079116874, 0.10254407479071907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1344232765148914e-09, -2.0827119200966643e-09, -0.00027793221615745386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922201868250198, 0.23539634306990492, 0.8412314006554471, 0.0, -0.12374207508064684, -0.24418789206263306, -2.6081432812967753, -0.7124882530489969, -0.5581248514787112, -1.1990499100341336, -2.8768639699113385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43850370439191116, 0.9507742115167876, 0.8272174784440234, -1.209027128457125, -2.266421303994671, -0.30998379134964577, 1.8351043704068524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846727415, -0.44034092351037646, 0.02364019598329647]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0464356000538463e-06, 0.00023868581063525855, 0.0019033268681426727, 0.0, 0.00030186346797247786, 0.00010333417549517549, 5.0865393554811415e-05, 0.0003861053978273925, -3.0189858715893594e-05, -0.00019773120388399588, -0.00012605302097634758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.034810065183576266, 0.03206510331484076, -0.10036628297987271, -0.006677165814621422, -0.0469229117326932, 0.04625575378754693, 0.11279676908714747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.66298946820811e-10, -2.2585461717950393e-09, -0.0002607031883607115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922216437310262, 0.2354080849464401, 0.8413213449530466, 0.0, -0.12372725721475548, -0.24418254640448694, -2.6081406111655814, -0.7124692442472988, -0.5581265156307138, -1.1990596621045952, -2.8768701100452763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43673363940883975, 0.9523871568461224, 0.8221391334650482, -1.2093648423795467, -2.26884706203803, -0.30766750998431247, 1.840851733829424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846677342, -0.44034092362250954, 0.023627366179124365]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.913812013021153e-06, 0.00023483753070400228, 0.00179888595198974, 0.0, 0.0002963573178272846, 0.00010691316292219053, 5.340262387741816e-05, 0.0003801760339596849, -3.328304005376323e-05, -0.00019504140923134718, -0.00012280267875417538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03540129966142834, 0.03225890658669601, -0.10156689957950295, -0.006754278448434319, -0.0485151608671812, 0.046325627306666436, 0.11494726845142962, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0014635555554529e-10, -2.242661711052622e-09, -0.00025659608344215124]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922230828349167, 0.23542179120280785, 0.8413961196175765, 0.0, -0.1237101320622456, -0.2441748125719034, -2.608137768907168, -0.7124473589817228, -0.5581281884138987, -1.1990708510518875, -2.8768772695111755, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4350979902425157, 0.9538648375688505, 0.8174609802263084, -1.2096783122332178, -2.271137094484585, -0.305621782567045, 1.846191036079717, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960845977244, -0.4403409237343511, 0.02361258903531463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8782077809993562e-06, 0.0002741251273545041, 0.0014954932906001, 0.0, 0.00034250305019766023, 0.0001546766516706125, 5.684516826768007e-05, 0.0004377053115208709, -3.3455663696616285e-05, -0.00022377894584475218, -0.0001431893179887565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03271298332648065, 0.029553614454562817, -0.09356306477479633, -0.006269397073421333, -0.04580064893110514, 0.04091454834535009, 0.10678604500586072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4001961193872394e-09, -2.236830667351529e-09, -0.0002955428761946808]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922243783393282, 0.23543903852997633, 0.8414513434500096, 0.0, -0.12368880508011355, -0.24416378984995993, -2.60813464483527, -0.7124202454252593, -0.5581298364460988, -1.1990846663697565, -2.876886296613515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4336623984435202, 0.9551532708001835, 0.8133606711026311, -1.209957272600563, -2.273199334011333, -0.3039200237919479, 1.850916595958042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196084406267, -0.44034092384720275, 0.023594268486829852]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.591008822977664e-06, 0.0003449465433696476, 0.001104476648661621, 0.0, 0.0004265396426407557, 0.00022045443886932763, 6.248143796103482e-05, 0.0005422711292714019, -3.296064400230728e-05, -0.0002763063573822093, -0.00018054204678421757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02871183597991043, 0.02576866462665916, -0.08200618247354668, -0.00557920734690619, -0.041244790534955666, 0.034035175501941975, 0.09451119756650121, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8291438123780864e-09, -2.2570332791828863e-09, -0.00036641096969553655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922255106794738, 0.23546013123742882, 0.8414867720698173, 0.0, -0.12366286242224352, -0.24414972837577267, -2.6081311939056873, -0.7123873802711952, -0.558131470146458, -1.1991013861642983, -2.876897373484767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43242675695397453, 0.9562573128632461, 0.8098307629874593, -1.2102024622712715, -2.2750240339463406, -0.30252510162345925, 1.8550265512441675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960840910455, -0.44034092395784474, 0.023572049757173866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.26468029088339e-06, 0.0004218541490494525, 0.0007085723961537018, 0.0, 0.0005188531574006369, 0.00028122948374484466, 6.901859164659148e-05, 0.0006573030812827114, -3.267400718439803e-05, -0.0003343958908373568, -0.00022153742504650204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02471282979091402, 0.022080841261251077, -0.07059816230343761, -0.004903793414171123, -0.036493998700152935, 0.027898443369773075, 0.0821991057225074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.304433286892409e-09, -2.2128403986714446e-09, -0.000444374593119745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922265159170025, 0.23548434886488395, 0.8415061255847035, 0.0, -0.1236330840946502, -0.24413351552177873, -2.608127454022146, -0.7123497254554765, -0.5581331059967973, -1.19912053705499, -2.8769101520880205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43135851539591985, 0.9572093754222624, 0.8067750353053372, -1.2104195732844663, -2.276643595151556, -0.3013598281014676, 1.8586187114510089, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960836810974, -0.44034092406159986, 0.023546586131306835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.010475057647412e-06, 0.0004843525491029461, 0.00038707029772529206, 0.0, 0.0005955665518662969, 0.0003242570798786655, 7.479767081710877e-05, 0.0007530963143733585, -3.2717006786872644e-05, -0.00038301781383230676, -0.00025557206506673664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021364831161093535, 0.01904125118032559, -0.06111455364244099, -0.00434222026389549, -0.032391224104307406, 0.023305470439832707, 0.07184320413682947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.19896031598218e-09, -2.0751025149419598e-09, -0.000509272517340654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922274555400075, 0.23551049919664788, 0.8415149219583403, 0.0, -0.12360081504552632, -0.24411619699799172, -2.6081235111311813, -0.712308950582451, -0.5581347560571188, -1.1991412817206182, -2.876924034508455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4304134333681977, 0.9580505897866057, 0.8040671225441811, -1.2106158703853926, -2.2781080914157794, -0.30034361325339415, 1.861827325592487, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960832140596, -0.44034092415520626, 0.023519010503724798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8792460097681025e-06, 0.0005230066352782863, 0.00017592747273691278, 0.0, 0.000645380982477355, 0.00034637047574014696, 7.885781929856352e-05, 0.0008154974605094604, -3.3001206429091666e-05, -0.00041489331256218425, -0.0002776484086882363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018901640554443433, 0.016824287286867967, -0.05415825522312133, -0.003925942018529482, -0.029289925284466382, 0.020324296961469136, 0.06417228282956303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.340756875042724e-09, -1.8721281955298883e-09, -0.0005515125516407263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922283902802277, 0.23553740499180734, 0.8415182253375447, 0.0, -0.12356741262006192, -0.244098656648433, -2.6081194585706613, -0.7122667452605677, -0.5581364278203959, -1.1991627663390112, -2.876938417438849, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295475700577736, 0.9588204602625764, 0.8015834397600468, -1.2107984291261271, -2.2794706522647883, -0.2994086858988451, 1.8647869579812928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960827229942, -0.4403409242374828, 0.02349046859225637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8694804402221444e-06, 0.0005381159031892923, 6.606758408896761e-05, 0.0, 0.000668048509288048, 0.00035080699117424197, 8.105121039951375e-05, 0.0008441064376684413, -3.3435265540814266e-05, -0.0004296923678604655, -0.000287658607876933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01731726620848244, 0.015397409519414065, -0.04967365568268607, -0.003651174814689638, -0.027251216980177163, 0.01869854709098071, 0.059192647776113216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.821306158070047e-09, -1.6455303699486633e-09, -0.0005708382293685547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092229362213521, 0.23556419214109076, 0.8415193673058253, 0.0, -0.12353391477712479, -0.24408145874473222, -2.608115372253596, -0.7122244048578634, -0.5581381237752528, -1.1991843319310758, -2.8769528395699946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42872445430342665, 0.9595510565704616, 0.7992223359452336, -1.2109731199137916, -2.280777720365814, -0.2985065236544123, 1.8676104953770492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196082231266, -0.4403409243088011, 0.02346183822581013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9438665863407815e-06, 0.0005357429856686259, 2.283936561278392e-05, 0.0, 0.0006699568587426542, 0.0003439580740157031, 8.17263413041995e-05, 0.000846808054083768, -3.39190971396814e-05, -0.0004313118412897082, -0.000288442622914387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01646231508693933, 0.01461192615770454, -0.04722207629626339, -0.003493815753291094, -0.026141362020514175, 0.018043244888655965, 0.056470747915129293, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.83456558593435e-09, -1.426367202242299e-09, -0.000572607328924798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922303880110799, 0.23559038168015178, 0.8415199852882396, 0.0, -0.1235009259124147, -0.24406483268837104, -2.6081113018315367, -0.7121826869037292, -0.5581398408669545, -1.1992055894462346, -2.876967032815702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42791895589001544, 0.9602641198930109, 0.7969141609822934, -1.2111440345584141, -2.2820628385253374, -0.2976091306509349, 1.8703766996585587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960817519064, -0.4403409243703063, 0.02343363234899367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0515951175859435e-06, 0.0005237907812203649, 1.2359648284266457e-05, 0.0, 0.0006597772942017476, 0.000332521127223907, 8.140844119091067e-05, 0.0008343590826838142, -3.4341834033013567e-05, -0.0004251503031771353, -0.00028386491415034406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016109968268223928, 0.014261266450985874, -0.04616349925880549, -0.0034182928924479396, -0.02570236319046215, 0.017947860069547936, 0.055324085630191866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.587193975638144e-09, -1.2301036995276342e-09, -0.00056411753632922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922314643975465, 0.23561584225978577, 0.8415206281416071, 0.0, -0.12346865914893124, -0.24404875443383964, -2.6081072718949243, -0.7121418622418272, -0.5581415717556476, -1.1992263960601717, -2.8769809036549896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4271176920472807, 0.9609710640627841, 0.7946219475397546, -1.2113134147462656, -2.2833449298152786, -0.29670604552711033, 1.8731283167796038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960812893364, -0.44034092442329237, 0.023406033978459983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152772933227082e-06, 0.0005092115926796831, 1.2857067350550212e-05, 0.0, 0.0006453352696690721, 0.0003215650906277757, 8.059873225149452e-05, 0.0008164932380410139, -3.461777386295665e-05, -0.00041613227874423325, -0.0002774167857476666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016025276854695188, 0.014138883395464165, -0.045844268850776165, -0.0033876037570306798, -0.025641825798819465, 0.018061702476492185, 0.05503234242090225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.251399377513169e-09, -1.0597212265636223e-09, -0.0005519674106737503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092232580107623, 0.23564067171667163, 0.8415212349419124, 0.0, -0.1234370605731956, -0.24403306406223987, -2.608103288474411, -0.7121018685308353, -0.5581433072688579, -1.1992467787880954, -2.87699447765998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42631633281947695, 0.9616754935931877, 0.792333738387956, -1.2114820654238903, -2.2846310717664897, -0.29579816557776584, 1.8758799956162546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960808423015, -0.4403409244688435, 0.023379000395382613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2314201529564266e-06, 0.0004965891377175496, 1.2136006107188386e-05, 0.0, 0.0006319715147126685, 0.0003138074319952333, 7.966841026668133e-05, 0.000799874219836588, -3.4710264206142476e-05, -0.0004076545584751738, -0.0002714800998085875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016027184556074832, 0.014088590608071366, -0.045764183035973204, -0.003373013552493929, -0.025722839024224495, 0.01815759898688995, 0.055033576733016905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.940694945966608e-09, -9.110227440188435e-10, -0.000540671661547411]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209223372539627, 0.23566506806782841, 0.8415217812975562, 0.0, -0.12340594956291107, -0.24401758090343914, -2.6080993451677648, -0.7120624836986472, -0.5581450407705657, -1.1992668474692554, -2.8770078362267806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42551557505713944, 0.9623767297213253, 0.7900514091170274, -1.2116499838904833, -2.2859214864877115, -0.29489107317242, 1.8786305914415817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960804069877, -0.44034092450770895, 0.023352380809571575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2905772941065556e-06, 0.00048792702313550185, 1.0927112874049084e-05, 0.0, 0.0006222202056907677, 0.00030966317601457835, 7.88661329248291e-05, 0.0007876966437629345, -3.4670034157743676e-05, -0.0004013736231996911, -0.00026717133601586484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01601515524674981, 0.014024722562751344, -0.045646585418570494, -0.003358369331861143, -0.0258082944244407, 0.018141848106916394, 0.055011916506542455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.706274311049773e-09, -7.773093037112224e-10, -0.0005323917162207316]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922348953618178, 0.23568922979927492, 0.8415222566785925, 0.0, -0.123375129465284, -0.24400216448610904, -2.608095430822606, -0.712023463875547, -0.5581467688719711, -1.1992867246130448, -2.8770210672879366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42471767050002407, 0.9630727822489621, 0.7877811163116816, -1.2118169029211905, -2.28721408021122, -0.29399025899148507, 1.8813739028142424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960799793762, -0.4403409245403216, 0.023326009828649293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3399310956571104e-06, 0.00048323462893022737, 9.507620725404603e-06, 0.0, 0.0006164019525410937, 0.00030832834660205323, 7.828690317029863e-05, 0.000780396462003816, -3.456202810875578e-05, -0.0003975428757877269, -0.00026462122312433816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015958091142307503, 0.013921050552737518, -0.045405856106917414, -0.003338380614145172, -0.02585187447017159, 0.018016283618698822, 0.05486622745321367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.552228758823872e-09, -6.522531359252474e-10, -0.000527419618445673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092236089442465, 0.2357133007651516, 0.8415226672037902, 0.0, -0.12334445117290906, -0.24398673651659994, -2.6080915348528966, -0.7119846230807773, -0.5581484910085028, -1.199306504474441, -2.877034237148521, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42392436326708854, 0.9637620898156535, 0.785527656721029, -1.2119826123190947, -2.2885072294691815, -0.29309891318302905, 1.8841050985136476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196079556518, -0.4403409245668912, 0.023299761418517764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.388161294365743e-06, 0.0004814193175336523, 8.210503954310316e-06, 0.0, 0.0006135658474991242, 0.00030855939018207835, 7.791939418756594e-05, 0.0007768158953953921, -3.4442730633713985e-05, -0.0003955972279284372, -0.00026339721168615413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015866144658710776, 0.013786151333827379, -0.045069191813052134, -0.003314187958082865, -0.02586298515922863, 0.01782691616911975, 0.054623913988103075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.457162595218221e-09, -5.313923472491648e-10, -0.0005249682026306076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922373096431715, 0.2357373554602591, 0.8415230305637231, 0.0, -0.12331383313096314, -0.24397127446279795, -2.6080876499174175, -0.71194585879409, -0.5581502083641651, -1.1993262395279525, -2.8770473817984348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4231361474736072, 0.9644441377747965, 0.7832924464386829, -1.2121470755077381, -2.2898008375515504, -0.292217667083622, 1.8868230698752826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960791368715, -0.44034092458751367, 0.023273566174345575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4404014132461273e-06, 0.00048109390215006183, 7.267198659375373e-06, 0.0, 0.0006123608389183291, 0.00030924107603955115, 7.769870958462718e-05, 0.0007752857337444723, -3.4347113243743554e-05, -0.00039470107022578484, -0.0002628929982758232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015764315869626497, 0.013640959182861963, -0.04470420564692132, -0.003289263772868496, -0.025872161647381108, 0.017624921988140904, 0.05435942723269867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.392931709869209e-09, -4.124487802740948e-10, -0.0005239048834437878]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092238558825656, 0.23576141053205174, 0.8415233686300534, 0.0, -0.12328325243654976, -0.2439557920151657, -2.6080837724010726, -0.7119071414159466, -0.5581519227870049, -1.199345945387338, -2.8770605110628282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4223523698543891, 0.9651193702015691, 0.7810737984948897, -1.2123104169868437, -2.2910962516623736, -0.29134533396449097, 1.8895301632215622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960787200638, -0.4403409246022554, 0.023247404124884127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4983649688536877e-06, 0.0004811014358528989, 6.761326606055589e-06, 0.0, 0.0006116138882675735, 0.00030964895264502747, 7.755032689620944e-05, 0.0007743475628682688, -3.4288456795332206e-05, -0.00039411718771227295, -0.0002625852878715163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015675552384362555, 0.013504648535452373, -0.04437295887586491, -0.0032668295821129466, -0.02590828221646176, 0.017446662382620555, 0.054141866925591864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.336152004959027e-09, -2.9483383204032195e-10, -0.0005232409892289644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922398394839423, 0.23578544723407127, 0.8415237008592102, 0.0, -0.12325272323726047, -0.2439403182548261, -2.608079901591061, -0.7118684876951991, -0.5581536360211438, -1.1993656140432984, -2.8770736183330112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42157170330215116, 0.9657887980086253, 0.7788682009049951, -1.2124728538313292, -2.292395659042311, -0.2904799007452496, 1.8922307511121659, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960783064311, -0.44034092461119667, 0.023221286690121322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5613165727152883e-06, 0.00048073404039043435, 6.644583136598058e-06, 0.0, 0.0006105839857859857, 0.0003094752067921484, 7.741620023622234e-05, 0.0007730744149506638, -3.426468277858962e-05, -0.00039337311920644867, -0.00026214540366160043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01561333104475981, 0.013388556141123548, -0.04411195179789197, -0.003248736889710461, -0.025988147598741438, 0.01730866438482799, 0.054011757812075435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.272654326006525e-09, -1.788258857433844e-10, -0.0005223486952560803]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092241153103414, 0.23580943343363525, 0.8415240404833962, 0.0, -0.1232222746465587, -0.24392488207649005, -2.608076038413205, -0.7118299333489168, -0.5581553493164322, -1.1993852276726218, -2.8770866904437438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42079265955417344, 0.9664535785191612, 0.7766716961082093, -1.212634621195772, -2.293701407394966, -0.2896193457177761, 1.8949296662867212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960778965756, -0.440340924614439, 0.02319523811198458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.627238943820995e-06, 0.000479723991279697, 6.792483720689729e-06, 0.0, 0.0006089718140354803, 0.0003087235667211426, 7.726355711621118e-05, 0.000771086925645637, -3.426590576893101e-05, -0.00039227258646606824, -0.0002614422146470036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015580874959554462, 0.013295610210719745, -0.04393009593571532, -0.003235347288853942, -0.02611496705310561, 0.017211100549470552, 0.05397830349110793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.197111136692185e-09, -6.484728093278991e-11, -0.0005209715627347895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092242500054431, 0.23583333917995253, 0.8415243937262556, 0.0, -0.12319193475318685, -0.24390950385004634, -2.6080721843085497, -0.7117915131284361, -0.5581570633418861, -1.1994047687729104, -2.8770997147905937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4200139636292416, 0.9671147104640737, 0.7744808856812928, -1.2127959181453245, -2.295015497776658, -0.28876212112143645, 1.8976310505495397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960774910598, -0.4403409246120918, 0.02316928194668761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6939020335182154e-06, 0.00047811492634575376, 7.064857187734985e-06, 0.0, 0.0006067978674369437, 0.00030756452887392905, 7.70820931088602e-05, 0.0007684044096126242, -3.428050907739793e-05, -0.0003908220057691243, -0.0002604869369985441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015573918498637348, 0.013222638898248726, -0.043816208538330355, -0.00322593899105221, -0.026281807633830957, 0.017144491926792838, 0.05402768525636815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.110315293499276e-09, 4.6944804177953823e-11, -0.0005191233059394407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922438798573534, 0.2358571444272394, 0.8415247611308359, 0.0, -0.12316172246009313, -0.24389419335789833, -2.608068340507095, -0.7117532505645536, -0.558158778287458, -1.199424225430224, -2.8771126829367297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41923473532055916, 0.9677728866796532, 0.7722934161990574, -1.212956881883158, -2.2963393354168686, -0.2879073096273501, 1.9003377944197228, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960770902595, -0.4403409246042542, 0.023143434124516634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7596058447164707e-06, 0.000476104945737298, 7.348091605041611e-06, 0.0, 0.0006042458618744598, 0.00030620984296020646, 7.687602909510037e-05, 0.0007652512776494267, -3.429891143800084e-05, -0.0003891331462746232, -0.00025936292271699256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0155845661736487, 0.013163524311589642, -0.04374938964470688, -0.0032192747566692206, -0.02647675280421163, 0.017096229881726443, 0.054134877403664294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.01600633038393e-09, 1.5675137198967494e-10, -0.0005169564434195082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922452916000858, 0.2358808403621116, 0.8415251397821107, 0.0, -0.12313164583970654, -0.24387895172115687, -2.6080645077163536, -0.711715155813482, -0.5581604940444943, -1.1994435924773454, -2.87712559131105, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41845450336903484, 0.9684284818251855, 0.7701080173027351, -1.2131175865810657, -2.2976737120383386, -0.2870545511453888, 1.9030514941192362, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196076694342, -0.4403409245910031, 0.02311770150108781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8234854651376114e-06, 0.0004739186974440934, 7.573025496729262e-06, 0.0, 0.0006015324077317446, 0.00030483273482931615, 7.66558148236624e-05, 0.0007618950214334908, -3.4315140727767546e-05, -0.0003873409424277983, -0.0002581674864028675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015604639030486773, 0.01311190291064501, -0.043707977926445755, -0.0032140939581541406, -0.026687532429398322, 0.01705516963922575, 0.054273993990267506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.918348766056197e-09, 2.650229335057428e-10, -0.000514652468576475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922467343183218, 0.2359044269142091, 0.8415255254644389, 0.0, -0.12310170444313419, -0.24386377493927877, -2.608060686115852, -0.7116772284471309, -0.5581622103830651, -1.1994628701224501, -2.8771384401500866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4176731159377752, 0.9690816227511331, 0.7679242635833511, -1.2132780573832522, -2.299018936029712, -0.28620385908414797, 1.9057727319204802, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960763033183, -0.440340924572389, 0.023092083757146897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8854364718654023e-06, 0.0004717310419500043, 7.713646564592234e-06, 0.0, 0.0005988279314469956, 0.00030353563756180154, 7.643201002834777e-05, 0.0007585473270231177, -3.4326771416632615e-05, -0.00038555290209570716, -0.00025697678073433646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015627748625193033, 0.013062818518951868, -0.043675074387681916, -0.003209416043731131, -0.02690447982746789, 0.017013841224816428, 0.05442475602487812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.820471259658485e-09, 3.7228274721579084e-10, -0.0005123548788182946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922482072344842, 0.2359279089154134, 0.841525914222004, 0.0, -0.1230718930598605, -0.24384865728966337, -2.608056875514007, -0.7116394620836728, -0.55816392708018, -1.1994820616189485, -2.8771512318041363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4168906142633456, 0.9697322875982185, 0.7657422392854535, -1.2134382896662679, -2.3003750177240807, -0.28535542471059344, 1.90850147292552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960759171188, -0.4403409245484401, 0.023066576541881698]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9458323249921477e-06, 0.00046964002408588835, 7.775151300331361e-06, 0.0, 0.000596227665474031, 0.00030235299230778275, 7.621203690126238e-05, 0.0007553272691621398, -3.433394229827986e-05, -0.0003838299299675208, -0.0002558330809954987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015650033488590995, 0.01301329694170914, -0.043640485957952946, -0.003204645660315158, -0.027121633887366898, 0.016968687471091107, 0.05457482010079753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.723991917998616e-09, 4.789779770359519e-10, -0.0005101443053039941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922487188422875, 0.2359512926173417, 0.8414798981621372, 0.0, -0.12304217007769358, -0.2438328025892432, -2.608053233455713, -0.7116018612972712, -0.5581654649798811, -1.1995011740929382, -2.87716403092832, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41622679897001835, 0.9702865401809379, 0.763883358433907, -1.2135778829397672, -2.3015461478541615, -0.284671909354924, 1.9108411860728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075585609, -0.44034092452713464, 0.023041174375794907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0232156067228836e-06, 0.0004676740385663791, -0.0009203211973347449, 0.0, 0.0005944596433383856, 0.0003170940084034714, 7.284116588084856e-05, 0.0007520157280314512, -3.0757994020575036e-05, -0.0003822494797954897, -0.000255982483672668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013276305866545001, 0.011085051654385976, -0.03717761703092988, -0.002791865469985349, -0.023422602601618707, 0.013670307113389343, 0.04679426294614361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.630193781554256e-09, 4.2610865232925507e-10, -0.0005080433217358516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092248984882419, 0.235974268389336, 0.8414506529541362, 0.0, -0.1230129407403171, -0.24381756337189522, -2.6080496259565082, -0.7115648801886544, -0.5581669870332563, -1.199520018068767, -2.87717661581652, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4157054495725053, 0.970726134875539, 0.7624113404522476, -1.2136924119698704, -2.302488665425653, -0.28416729112142136, 1.9127088918606323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960753270093, -0.44034092451105267, 0.02301618802811448]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.320802629738785e-07, 0.00045951543988579204, -0.0005849041600194818, 0.0, 0.0005845867475296946, 0.00030478434695945265, 7.214998409164552e-05, 0.0007396221723374655, -3.044106750547131e-05, -0.00037687951657553657, -0.00025169776400109383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010426987950260405, 0.00879189389202301, -0.02944035963318739, -0.00229058060206577, -0.018850351429836387, 0.010092364670052284, 0.03735411575610158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.171997670780403e-09, 3.216397380081335e-10, -0.0004997269536085335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922491494170983, 0.23599624983988501, 0.8414483496448353, 0.0, -0.122984921306867, -0.24380364302824198, -2.608046030740962, -0.7115293881312232, -0.5581685710940243, -1.1995381647932162, -2.8771886485782794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4153133445449481, 0.9710617032434499, 0.7612911261863405, -1.2137835548633018, -2.303218483848184, -0.2838093796255577, 1.9141429507514227, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751444154, -0.4403409245013862, 0.022992208098654425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2906935816892777e-07, 0.00043962901098051926, -4.606618601843708e-05, 0.0, 0.0005603886690020853, 0.0002784068730651544, 7.19043109229564e-05, 0.0007098411486224862, -3.1681215360431484e-05, -0.0003629344889806832, -0.00024065523518950488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007842100551144033, 0.006711367358216193, -0.022404285318141592, -0.0018228578686265181, -0.014596368450615259, 0.007158229917273065, 0.02868117781580587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.651877703104973e-09, 1.933301689856042e-10, -0.00047959858920105706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492437373727, 0.23601658623147476, 0.8414590466242347, 0.0, -0.12295889779171289, -0.2437913255747105, -2.608042497371656, -0.7114963632547027, -0.5581702289630247, -1.1995551136100802, -2.8771997770817075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41502627397516445, 0.9713122651738108, 0.760458530364623, -1.2138548491255416, -2.303770441791338, -0.2835593787138501, 1.9152187220931172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119607504069, -0.44034092450048995, 0.02296989711802654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8864054873582224e-07, 0.000406727831794947, 0.0002139395879865806, 0.0, 0.0005204703030823638, 0.00024634907062953237, 7.066738611790935e-05, 0.0006604975304108868, -3.315738000833834e-05, -0.0003389763372812621, -0.0002225700685628714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005741411395673626, 0.005011238607218407, -0.016651916434352116, -0.0014258852447985985, -0.011039158863079185, 0.005000018234151651, 0.02151542683389112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0745040033420788e-09, 1.7924738970382162e-11, -0.00044621961255772425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492933419876, 0.23603475577432742, 0.8414750227616592, 0.0, -0.1229355231945582, -0.2437809814534243, -2.6080390312703785, -0.7114666078848317, -0.5581720073977583, -1.1995704589743537, -2.877209698784248, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4148198000911033, 0.9714968972861152, 0.7598487496944001, -1.2139100078181488, -2.304181407589278, -0.2833847366983969, 1.9160138213012863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960750336107, -0.4403409245145704, 0.02294979900678752]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.920922989975184e-08, 0.00036339085705321047, 0.00031952274849119864, 0.0, 0.00046749194309373803, 0.0002068824257242287, 6.932202555167622e-05, 0.000595107397419589, -3.5568694672535596e-05, -0.00030690728546846455, -0.00019843405081240186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004129477681223238, 0.0036926422460890037, -0.012195613404458027, -0.0011031738521428088, -0.008219315958802705, 0.003492840309064276, 0.015901984163380244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4158986410701592e-10, -2.8160915053321025e-10, -0.0004019622247804496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493099129635, 0.23605046525805473, 0.8414448279092318, 0.0, -0.12291510482198442, -0.2437709778967978, -2.608035990795053, -0.7114406115277784, -0.5581735692497372, -1.1995838798835885, -2.877218364229198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4146730376185007, 0.9716318981989475, 0.7594062208513683, -1.2139523496896159, -2.304484103164397, -0.28326203612539763, 1.916595816208237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751141298, -0.44034092454431645, 0.022932238233061203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.314195200306826e-08, 0.00031418967454627315, -0.0006038970485487139, 0.0, 0.0004083674514753187, 0.0002000711325302667, 6.0809506508185485e-05, 0.0005199271410681618, -3.123703957631058e-05, -0.000268418184694739, -0.0001733088989992726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002935249452052032, 0.0027000182566449277, -0.008850576860634755, -0.0008468374293380021, -0.006053911502375485, 0.0024540114599855816, 0.011639898139017498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6103848084768415e-09, -5.949203318875397e-10, -0.0003512154745262834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493104040848, 0.23606365717311636, 0.8413724547795586, 0.0, -0.12289772275178933, -0.2437611459551833, -2.6080335107422443, -0.711418514534015, -0.5581747862028298, -1.199595274141099, -2.8772257708797935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41456955499475034, 0.9717301605493174, 0.7590869279578832, -1.213984645147714, -2.3047052786869795, -0.2831748818362176, 1.9170190087748016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075219521, -0.4403409245856499, 0.022917307953974907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0" + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21405007691131805, 0.04188077202253695, -0.36111200186744086, 0.0, -1.004733782777196, 0.48736018039340784, -0.9487478790977968, -1.392377789199791, -2.3294660300946273, -0.4548700950082352, 0.11575516878897756, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8799811840759517, 0.01162710877305629, 1.7383064794236054, -2.0301529420491278, -1.4865011013621898, -0.10361483364873676, 0.2211701008918833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.6074844303731284, -0.7273603211352454, 0.013367732054879625]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21402839575309973, 0.04938077106361105, -0.34949996513697584, 0.0, -1.0011652823484956, 0.49111018039268434, -0.9524978790974004, -1.3961277892001054, -2.333216030094612, -0.45713842380556585, 0.11200516878892969, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762311840758314, 0.015377108772934429, 1.7420564794229674, -2.0280055433823345, -1.4902511013621702, -0.1039161082788246, 0.2174201008919637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.6068674451073257, -0.7279932343850507, 0.012742732054806746]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0004336231643662778, 0.14999998082148203, 0.23224073460930056, 0.0, 0.07137000857401192, 0.07499999999988681, -0.07499999999997856, -0.07499999999998418, -0.07499999999969256, -0.045366575946612815, -0.07499999999996639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999998275, 0.07499999999996271, 0.07499999999992144, 0.042947973335866495, -0.07499999999960884, -0.006025492601756743, -0.07499999999839187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012339705316053159, -0.012658264996105478, -0.01250000000003011]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21401091393802746, 0.06766867523493247, -0.3294428440896994, 0.0, -0.9956442654321376, 0.502355417572033, -0.9637478790973795, -1.4073777892001187, -2.3418636346680195, -0.46002599815828366, 0.10075516878893027, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8649811840758328, 0.026627108772930754, 1.7533064794229591, -2.0211558895334654, -1.4979906583964677, -0.10650015306691515, 0.21178046007110707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.605012932428605, -0.7298885002567542, 0.01086773205480565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003496363014453439, 0.36575808342642835, 0.40114242094552827, 0.0, 0.1104203383271599, 0.22490474358697282, -0.2249999999999549, -0.22499999999996995, -0.17295209146814824, -0.05775148705435569, -0.22499999999993303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2249999999999659, 0.22499999999992545, 0.22499999999984277, 0.1369930769773847, -0.15479114068595232, -0.05168089576181112, -0.11279281641713287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03709025357441372, -0.03790531743406946, -0.037500000000022335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21399824442986745, 0.09312164414909241, -0.3051588885308801, 0.0, -0.9900963067571215, 0.5190262759670525, -0.9843706590441835, -1.4280027891915854, -2.3532703363165997, -0.4622819430092069, 0.08027458571902919, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8445032906656067, 0.046876564013675945, 1.7697961234994897, -2.0072100977975302, -1.507338359997853, -0.11211891265943025, 0.20725821734621477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.601601068542692, -0.7333514465709071, 0.0074302320501798726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0002533901631998896, 0.5090593782831986, 0.48567911117638723, 0.0, 0.11095917350032275, 0.3334171679003927, -0.4124555989360815, -0.4124999998293359, -0.22813403297160093, -0.04511889701846443, -0.4096116613980215, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.409557868204524, 0.40498910481490374, 0.3297928815306118, 0.2789158347187026, -0.18695403202770272, -0.1123751918503019, -0.09044485449784613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06823727771826336, -0.06925892628305809, -0.06875000009251553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139877768117349, 0.12248595152345859, -0.2792862844929731, 0.0, -0.9853782612343235, 0.5388035036973994, -1.012591094452177, -1.4563119322099296, -2.3656214652961167, -0.4637487071492661, 0.052293116171255406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8171106330909736, 0.07405882941916246, 1.7884271960872264, -1.9853347116067976, -1.5161648961629113, -0.12078305181055067, 0.20605355864698724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5968742549350132, -0.7381037652994843, 0.002690648713208975]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00020935236265099495, 0.5872861474873238, 0.5174520807581398, 0.0, 0.0943609104559585, 0.3955445546069373, -0.5644087081598685, -0.5661828603668827, -0.24702257959034035, -0.029335282801183842, -0.5596293909554757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5478531514926603, 0.5436453081097303, 0.37262145175473604, 0.43750772381465186, -0.17653072330116545, -0.17328278302240852, -0.024093173984550506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09453627215357363, -0.09504637457154319, -0.09479166673941794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21397802435603058, 0.15380762144525748, -0.25310087122878755, 0.0, -0.9818441002320552, 0.5599935383483494, -1.046980193862732, -1.49071613077541, -2.377858697666331, -0.4648162929822095, 0.01822707172262443, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.785720703700884, 0.10625365067461987, 1.8069219205748044, -1.9563299173892552, -1.523260762684021, -0.13211747957535364, 0.2093408053762992, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5911984996943036, -0.7438780183083025, -0.0030728878835797222]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0001950491140864607, 0.6264333984359775, 0.5237082652837104, 0.0, 0.0706832200453656, 0.4238006930189997, -0.687781988211096, -0.6880839713096081, -0.24474464740429208, -0.02135171665886833, -0.6813208889726194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.6277985878017921, 0.6438964251091479, 0.3698944897515589, 0.5800958843508487, -0.1419173304221958, -0.22668855529605958, 0.06574493458623955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.11351510481419054, -0.11548506017636315, -0.11527073193577393]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21396844228792683, 0.18558776993065917, -0.22710523577307629, 0.0, -0.9803929406200691, 0.5816833798156663, -1.0864125530418198, -1.5299378943534712, -2.389398472202879, -0.46601206345656865, -0.02066490135687067, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753523702431539, 0.14162037160127605, 1.8239729357636572, -1.9213747608853842, -1.528230776554355, -0.14561125569674876, 0.21746668728306562, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5851861066509967, -0.7504561062613002, -0.009235377740604352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00019164136207500801, 0.6356029697080336, 0.5199127091142255, 0.0, 0.029023192239720164, 0.43379682934633695, -0.7886471835817574, -0.7844352715612226, -0.23079549073095726, -0.023915409487183178, -0.7778394615899018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.6439400253868981, 0.7073344185331236, 0.34102030377705606, 0.6991031300774188, -0.09940027740667923, -0.2698755224279023, 0.16251763813532838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1202478608661397, -0.1315617590599544, -0.12324979713214648]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21395857080998235, 0.21684550491193783, -0.20143950516724243, 0.0, -0.9816867740571443, 0.6034240713205168, -1.1299584403861185, -1.572951694862709, -2.4001053203132714, -0.46798041613012126, -0.06343828223169613, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7224282583502917, 0.17835791249750033, 1.8389361854496946, -1.881474876166441, -1.5313409283697756, -0.16080054771325827, 0.23011195510298352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5794561143327635, -0.7576766728835327, -0.015171820856739151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00019742955888989508, 0.6251546996255728, 0.513314612116677, 0.0, -0.025876668741504273, 0.4348138300970095, -0.870917746885973, -0.8602760101847542, -0.21413696220785153, -0.03936705347105192, -0.8554676174965092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.6219088816249494, 0.7347508179244852, 0.2992649937207499, 0.7979976943788614, -0.06220303630841271, -0.30378584033019007, 0.2529053563983581, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.114599846364666, -0.1444113324446493, -0.1187288623285303]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139484132138488, 0.24684083020161507, -0.17609690972439307, 0.0, -0.9858794785686925, 0.6248616432386986, -1.1767951502615592, -1.6187744983143428, -2.410278280300332, -0.4715363713215314, -0.1093602727268847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6936153595555632, 0.21526890927503223, 1.851749371384, -1.8376374767776857, -1.5328497732157655, -0.17735993379142004, 0.2464317833395671, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5746349678776295, -0.7654259398241374, -0.02025721723346848]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00020315192267065572, 0.5999065057935448, 0.5068519088569873, 0.0, -0.08385409023096471, 0.42875143836363594, -0.9367341975088141, -0.9164560690326777, -0.203459199741212, -0.07111910382820372, -0.9184398099037714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5762579758945691, 0.7382199355506377, 0.2562637186861111, 0.8767479877751052, -0.030176896919796414, -0.33118772156323517, 0.32639656473167206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09642292910267965, -0.15498533881209364, -0.10170792752491885]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21393945768201375, 0.2751899760926101, -0.15102048413825206, 0.0, -0.9924345641541855, 0.6433835195064347, -1.226195642834585, -1.6663953054822753, -2.419027079696625, -0.4773992110967462, -0.15769574024147434, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6675588755981103, 0.25161570765851016, 1.8626080903300444, -1.7909626138931913, -1.5329583692274078, -0.19501229595158184, 0.26526197977983784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5709055129095209, -0.7736155380082226, -0.023866566877198982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00017911063670103568, 0.5669829178199, 0.5015285117228202, 0.0, -0.1311017117098605, 0.37043752535472024, -0.9880098514605158, -0.9524161433586481, -0.1749759879258602, -0.11725679550429555, -0.966709350291793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5211296791490558, 0.7269359676695591, 0.2171743789208871, 0.933497257689888, -0.0021719202328458476, -0.35304724320323616, 0.37660392880541504, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.074589099362174, -0.16379196368170296, -0.07218699272136953]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21393163484573074, 0.3019405327867023, -0.12614019254342373, 0.0, -1.0001417842267126, 0.6563727550087424, -1.2761956678898574, -1.7148804342151156, -2.425101802163615, -0.4863551745846885, -0.20769574024175413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.644140395956616, 0.2869140583740125, 1.8717787276891364, -1.7424381900071182, -1.5317902816703632, -0.21351291963175456, 0.2852343734515358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5678308673883008, -0.7821612920847926, -0.02537486977336057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00015645672566030807, 0.5350111338818441, 0.4976058318965663, 0.0, -0.15414440145054073, 0.25978471004615394, -1.000000501105448, -0.9697025746568062, -0.12149444933979288, -0.1791192697588464, -1.000000000005596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.46836959282988416, 0.7059670143100475, 0.18341274718184103, 0.9704884777214632, 0.023361751140889977, -0.3700124736034544, 0.3994478734339595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06149291042440318, -0.17091508153139914, -0.03016605791782337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21392428807420777, 0.3274065255250102, -0.10138570163291992, 0.0, -1.0076088117800528, 0.6620315557307538, -1.3261956929444743, -1.7632567293905932, -2.4275329085529544, -0.498819747645085, -0.2576957402465617, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.622918922296096, 0.32075450546047596, 1.8795969919878763, -1.692969490456383, -1.5293137461980844, -0.23266435174468078, 0.3048269130304959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5650538381252062, -0.7909918277271243, -0.024849747434561812]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00014693543045949433, 0.5093198547661579, 0.4950898182100763, 0.0, -0.1493405510668045, 0.11317601444022843, -1.0000005010923365, -0.9675259035095521, -0.04862212778679051, -0.24929146120792955, -1.0000000000961522, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4244294732104016, 0.676808941729269, 0.15636528597479976, 0.9893739910147035, 0.04953070944557823, -0.38302864225852423, 0.3918507915792028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.055540585261894745, -0.17661071284663327, 0.010502446775975172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21391694797866068, 0.35215643096103505, -0.07668975046886739, 0.0, -1.013557954009221, 0.6594337812627501, -1.37619571799973, -1.8109910506997415, -2.4254736145925144, -0.5147523332138069, -0.30769574024655544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6036436718074583, 0.35271137033029476, 1.8866082902618366, -1.643665393088377, -1.5251930821727566, -0.25239718306665804, 0.3223596927149609, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5624988499823724, -0.7999972782860758, -0.022782366697704184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00014680191094191595, 0.49499810872049677, 0.49391902328105064, 0.0, -0.11898284458336604, -0.05195548936007299, -1.000000501105113, -0.9546864261829683, 0.04118587920879917, -0.3186517113744366, -0.9999999999998745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38550500977275426, 0.6391372973963756, 0.14022596547920665, 0.9860819473601208, 0.08241328050655437, -0.3946566264395454, 0.35065559368929977, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.051099762856676605, -0.18010901117902983, 0.04134761473715254]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21390937851581235, 0.37678934480111875, -0.0519908533606013, 0.0, -1.0175438792060088, 0.6479326038266131, -1.4261957430549717, -1.8576788920611815, -2.4179288523576505, -0.5336362017647442, -0.3576957402382077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.586111805848065, 0.38267592473792694, 1.893699779229268, -1.5962533684513525, -1.5186516722194912, -0.2729355740088597, 0.3363025256254184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5602780353678474, -0.8085559116039884, -0.019750660472524627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00015138925696674824, 0.4926582768016743, 0.4939779421653217, 0.0, -0.07971850393575505, -0.23002354872273878, -1.0000005011048325, -0.9337568272288015, 0.15089524469727406, -0.3776773710187483, -0.9999999998330448, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3506373191878672, 0.5992910881526433, 0.14182977934862995, 0.948240492740489, 0.13082819906530938, -0.4107678188440336, 0.2788566582091495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044416292290499086, -0.17117266635825143, 0.060634124503591125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21390348515233687, 0.4013605571032425, -0.027240002396329798, 0.0, -1.0195495715612344, 0.6278724453736115, -1.4761957681102162, -1.9033812020400194, -2.4043279951571157, -0.5547897566566473, -0.4070369956816421, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5704403930796766, 0.409064963498223, 1.9007612389564281, -1.5533367474201625, -1.5095123328669755, -0.29387190868867213, 0.3448277078512635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5585795168429903, -0.816044491507389, -0.016338431616452126]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011786726950953425, 0.4914242460424742, 0.49501701928543007, 0.0, -0.04011384710451425, -0.4012031690600304, -1.000000501104892, -0.9140461995767553, 0.27201714401069454, -0.4230710978380612, -0.9868251088686868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3134282553677689, 0.5277807752059213, 0.14122919454320257, 0.8583324206237984, 0.18278678705031426, -0.41872669359624815, 0.1705036445169017, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03397037049714163, -0.14977159806801144, 0.06824457712145003]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139008002843461, 0.42587391948905007, -0.002383756091800287, 0.0, -1.019030222831308, 0.6002599125934656, -1.5247297433700846, -1.9486567690694414, -2.384910439932968, -0.578385857751574, -0.4554497542851375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569053119813665, 0.42986372792443556, 1.9076374125697164, -1.5169793925806894, -1.4978489260561323, -0.31444930644709984, 0.3461459429510867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.557535434154174, -0.8218362729487612, -0.012971208027627008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.3697359815104575e-05, 0.4902672477161514, 0.4971249260905902, 0.0, 0.010386974598526375, -0.5522506556029184, -0.9706795051973673, -0.905511340588439, 0.3883511044829535, -0.47192202189853527, -0.9682551720699084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2707016219662041, 0.4159752885242512, 0.13752347226576409, 0.7271470967894607, 0.23326813621686415, -0.41154795516855397, 0.02636470199646393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020881653776323585, -0.11583562882744404, 0.06734447177650237]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21390324077851916, 0.4503219123930196, 0.022637559817665468, 0.0, -1.0126398621347574, 0.5662669749693652, -1.5680476688345877, -1.9933604780451852, -2.3592127341671203, -0.6047976405701264, -0.5047255030643343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.545389363854257, 0.4439528244847452, 1.9147755620107882, -1.487513716959438, -1.4834903390150427, -0.3343323851700372, 0.3389193187873829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5570526276409673, -0.8258179263474436, -0.009908425023136016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.8809883461016935e-05, 0.48895985807939035, 0.500426318189315, 0.0, 0.1278072139310124, -0.6798587524820071, -0.86635850929006, -0.8940741795148782, 0.5139541153169536, -0.528235656371047, -0.9855149755839359, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23031896254218687, 0.28178193120619355, 0.14276298882143812, 0.5893135124250282, 0.28717174082179364, -0.397661574458747, -0.1445324832740761, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009656130264136024, -0.07963306797364726, 0.06125566008981982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21391005849020772, 0.47463853141052853, 0.047887785822635476, 0.0, -0.9967488064806366, 0.5270726248701981, -1.602399544503729, -2.0340737657447376, -2.3275368326998254, -0.634862848818934, -0.5547255030643333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5357966307703568, 0.4511417770454332, 1.9230681342774139, -1.4641759208311131, -1.4661449774296555, -0.3537088796674716, 0.32284937968903676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5570877676205952, -0.8284641425515393, -0.0072553578296703815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013635423377142704, 0.4863323803501789, 0.5050045200994003, 0.0, 0.31782111308241745, -0.7838870019833412, -0.6870375133828264, -0.8142657539910518, 0.6335180293459018, -0.6013041649761517, -0.9999999999999811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1918546616780042, 0.14377905121375925, 0.16585144533251409, 0.4667559225664967, 0.3469072317077424, -0.3875298899486874, -0.3213987819669225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007027995925557453, -0.05292432408191605, 0.053061343869312674]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139334483596116, 0.4985735739545678, 0.07343414614360294, 0.0, -0.9722562601021301, 0.4837171447906766, -1.626709680400141, -2.0675554018843925, -2.290431239422649, -0.6674370113949618, -0.6047255030643199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5280283841930167, 0.4525975589522735, 1.93301572291819, -1.4463920759289723, -1.446363343870087, -0.37267127423336777, 0.29964975088163814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5576876148255, -0.8299905434021891, -0.004873435638741116]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004677973880773713, 0.47870085088078507, 0.5109272064193494, 0.0, 0.48985092757013005, -0.86710960159043, -0.4862027179282442, -0.6696327227930992, 0.7421118655435227, -0.6514832515205565, -0.9999999999997315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15536493154680073, 0.02911563813680665, 0.1989517728155225, 0.3556768980428182, 0.395632671191371, -0.3792478913179226, -0.46399257614797196, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01199694409809998, -0.03052801701299591, 0.0476384438185853]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21398536586411634, 0.5218603873164371, 0.09934099531076732, 0.0, -0.9406622229990439, 0.43703276072690245, -1.6429754351139467, -2.090055386501394, -2.248746764801429, -0.7005154010433398, -0.654725503064307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5220610678566364, 0.4503702196531628, 1.9441203258076558, -1.43370204844071, -1.425817089746854, -0.3906657552567055, 0.2725585046140236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5588517035578984, -0.8305087429935376, -0.002615780531037931]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010383500900951598, 0.4657362672373859, 0.5181369833432873, 0.0, 0.6318807420617233, -0.9336876812754831, -0.3253150942761113, -0.4499996916500954, 0.8336894924244017, -0.66156779296756, -0.9999999999997403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1193463267276054, -0.04454678598221347, 0.22209205778931673, 0.25380054976524635, 0.41092508246465687, -0.3598896204667542, -0.5418249253522913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.023281774647963948, -0.010363991826969137, 0.04515310215406371]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21406087636472304, 0.5441227755977854, 0.1256305474195321, 0.0, -0.9033869933166002, 0.38768525347600363, -1.6537384360843654, -2.1013053789343266, -2.2033991851046246, -0.7331751349842528, -0.704725503064253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5179563418883333, 0.44662018038515844, 1.9551478846905694, -1.4255634753052067, -1.406497740091368, -0.40663333982728767, 0.24532564087073333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5605008954654052, -0.8302096620097952, -0.0004453158401527277]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015102100121340595, 0.4452477656269656, 0.5257910421752963, 0.0, 0.7455045936488732, -0.9869501450179762, -0.21526001940837552, -0.22499984865865247, 0.9069515939360875, -0.6531946788182611, -0.9999999999989202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08209451936606435, -0.07500078536008792, 0.22055117765827362, 0.16277146271006576, 0.38638699310972086, -0.3193516914116437, -0.5446572748658054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03298383815013396, 0.005981619674849062, 0.04340929381770406]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21415361433482594, 0.5651643770235749, 0.15232188970893384, 0.0, -0.8615668095710967, 0.33768522842081306, -1.6609998564528572, -2.105055379215468, -2.1551211213473445, -0.7655850000482245, -0.7547255030641845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5156493098808035, 0.44302241855683644, 1.9647891696918023, -1.4212491469066264, -1.3900333040962913, -0.4195688074900582, 0.22170115964814516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.562465039710131, -0.8293549872613308, 0.0015947485563835282]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018547594020580254, 0.42083202851579055, 0.5338268457880342, 0.0, 0.8364036749100711, -1.0000005011038111, -0.14522840736983644, -0.07500000562283285, 0.9655612751455993, -0.6481973012794343, -0.9999999999986303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04614064015059661, -0.07195523656644034, 0.19282570002465607, 0.08628656797160733, 0.32928871990153324, -0.2587093532554108, -0.47248962445176346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03928288489451463, 0.017093494969286232, 0.04080128793072513]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21428261667834597, 0.5849247623975713, 0.17944216393362122, 0.0, -0.8161106625748167, 0.28768520336558134, -1.6665909433991697, -2.1044235759741072, -2.1051211213473615, -0.797530116295248, -0.8047255030641636, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5148421791331945, 0.4405123573890369, 1.9722441476217358, -1.4198995341951057, -1.377356176760104, -0.4290171159111577, 0.20455584774453986, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.564527970584957, -0.8281877581507554, 0.0034457899274372493]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002580046870400827, 0.39520770747992795, 0.5424054844937473, 0.0, 0.9091229399255988, -1.0000005011046345, -0.1118217389262485, 0.012636064827217047, 0.9999999999996627, -0.6389023249404682, -0.9999999999995823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016142614952178325, -0.0502012233559915, 0.14909955859867183, 0.02699225423041226, 0.25354254672374865, -0.1889661684219901, -0.34290623807210596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.041258617496521634, 0.023344582211509656, 0.03702082742107442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21447326292951113, 0.6034049110196956, 0.2070271590539286, 0.0, -0.7677457449779825, 0.23768517831036837, -1.6722170466532966, -2.100228331180767, -2.055121121347368, -0.8284214556657017, -0.854725503064142, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5151331757713309, 0.4393703252172557, 1.977371276428664, -1.4206320234316392, -1.3684859952485824, -0.4351575593773576, 0.1940391974466647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5665153477234395, -0.8268940568848144, 0.005069559905532198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0038129250233031264, 0.36960297244248763, 0.5516999024061477, 0.0, 0.9672983519366839, -1.0000005011042596, -0.1125220650825393, 0.08390489586680734, 0.9999999999998701, -0.617826787409075, -0.9999999999995686, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005819932762726177, -0.02284064343562343, 0.10254257613856074, -0.01464978473066747, 0.17740363023043174, -0.12280886932399827, -0.21033300595750307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.039747542769646024, 0.025874025318819056, 0.032475399561898974]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2147528194391773, 0.6206211483447068, 0.23511967003349202, 0.0, -0.7177457199227378, 0.1876851532551317, -1.6793672214072184, -2.092700007942825, -2.005121121347293, -0.8573738332175487, -0.9047255030641406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5161169158600225, 0.43947959333426834, 1.980492935799108, -1.4226468487876465, -1.362846073037505, -0.43859338382985574, 0.1890053500882898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5683203736631777, -0.8255937378667552, 0.00645900155088425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005591130193322867, 0.34432474650022504, 0.5618502195912682, 0.0, 1.0000005011048934, -1.0000005011047333, -0.14300349507843493, 0.1505664647588354, 1.0000000000014964, -0.5790475510369404, -0.9999999999999714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.019674801773831265, 0.0021853623402527007, 0.06243318740887693, -0.04029650712014602, 0.11279844422154837, -0.06871648904996261, -0.10067694716749805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03610051879476411, 0.026006380361184803, 0.027788832907041046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21514133636079058, 0.6365907913430936, 0.26376742096181105, 0.0, -0.6677456948674612, 0.13768512820119255, -1.6891832883517202, -2.082107826374659, -1.9551211213472992, -0.8834409325670629, -0.9547255030641343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5174434848993956, 0.4405535647795303, 1.9821376505931925, -1.4252829236700009, -1.3596255108626238, -0.44009375945606505, 0.18790582525225283, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5698943533786944, -0.8243537738735832, 0.007630360135157746]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007770338432266037, 0.31939285996773437, 0.572955018566381, 0.0, 1.000000501105533, -1.000000501078783, -0.19632133889003536, 0.21184363136331272, 0.999999999999876, -0.5213419869902838, -0.9999999999998745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026531380787464323, 0.021479428905238712, 0.03289429588169204, -0.05272149764708777, 0.06441124349762345, -0.03000751252418639, -0.021990496720739716, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03147959431033582, 0.024799279863437995, 0.023427171685469924]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21559044202916097, 0.6513357323798745, 0.29302118231223295, 0.0, -0.6177456698126543, 0.08768510316302033, -1.7019055790544244, -2.068828731576044, -1.9051211213473214, -0.9068089690990174, -1.0047255030641231, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5188557769742803, 0.4422461276918362, 1.9828351633023416, -1.4280559071605006, -1.3580396766029565, -0.4403814382610352, 0.18926395754351613, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5712276850132962, -0.8232148701875811, 0.008607432107111174]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008982113367407861, 0.2948988207356192, 0.5850752270084375, 0.0, 1.0000005010961355, -1.0000005007634445, -0.25444581405408667, 0.2655818959723025, 0.9999999999995548, -0.4673607306390901, -0.9999999999997785, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.028245841497693436, 0.03385125824611803, 0.013950254182983832, -0.05545966980999485, 0.03171668519334534, -0.005753576099402899, 0.027162645825266146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02666663269203405, 0.022778073720041477, 0.019541439439068567]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2158857804279169, 0.6648754867996546, 0.32293285434492236, 0.0, -0.5677456447573406, 0.03846402269947199, -1.7168642462366164, -2.0533318626105665, -1.8551211213473224, -0.9288847806446873, -1.0547255030641085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5202471409464502, 0.4442362473220161, 1.982901356859925, -1.4308206897744993, -1.3575786316862317, -0.4398727900774998, 0.19208519730591841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5723440231000738, -0.8221846311049259, 0.009423193076419234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005906767975118453, 0.27079508839560135, 0.5982334406537876, 0.0, 1.0000005011062747, -0.9844216092709669, -0.2991733436438381, 0.3099373793095547, 0.9999999999999769, -0.44151623091339615, -0.9999999999997068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027827279443396007, 0.03980239260359849, 0.0013238711516685587, -0.05529565227997608, 0.00922089833449716, 0.010172963670708173, 0.05642479524804575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02232676173555257, 0.020604781653104857, 0.01631521938616118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159103248195618, 0.6772376315459074, 0.35355316376097023, 0.0, -0.5177456196985276, -0.00639525610091915, -1.7314351349267365, -2.036149538653221, -1.8051211254173727, -0.9534183672039404, -1.1047255030644998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5216018600201224, 0.4462535611173844, 1.9824899659772908, -1.43361410292211, -1.3579477328334828, -0.43876478772028976, 0.19575594476739241, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5732786927226692, -0.8212611096317783, 0.01010853533928399]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004908878328981764, 0.24724289492505763, 0.6124061883209581, 0.0, 1.0000005011762596, -0.8971855760078227, -0.29141777380240186, 0.3436464791469105, 0.9999999185989956, -0.4906717311850626, -1.000000000007826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027094381473443008, 0.040346275907366135, -0.008227817652685586, -0.05586826295221423, -0.0073820229450200295, 0.022160047144200914, 0.0734149492294799, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018693392451909194, 0.018470429462951684, 0.013706845257295135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21591809916144236, 0.6884761003342825, 0.38492938823153205, 0.0, -0.46774559464374815, -0.0436671758512217, -1.7433715699150971, -2.0174338524870175, -1.7584624532020252, -0.9841597287767223, -1.154725503064472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5228408878906328, 0.44809974032885524, 1.9818589262212907, -1.436251338766988, -1.3587889607064068, -0.4374069371815546, 0.19962133705716606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5740470912350104, -0.8204647393382132, 0.010673876235862679]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015548683761147848, 0.22476937576750178, 0.6275244894112364, 0.0, 1.0000005010955892, -0.745438395006051, -0.23872869976721, 0.3743137233240758, 0.9331734443069486, -0.6148272314556386, -0.9999999999994476, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024780557410206246, 0.036923584229417175, -0.012620795120002921, -0.052744716897559746, -0.016824557458479154, 0.02715701077470347, 0.07730784579547287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015367970246825116, 0.015927405871302838, 0.011306817931573763]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21610518259718742, 0.6986508393283996, 0.4171034029484536, 0.0, -0.41774556959183407, -0.07347218582437884, -1.7532301549983202, -1.9968895393400135, -1.7162870802035057, -1.0207528180342547, -1.2047255030644293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5238571573181845, 0.4496781097881178, 1.9813283647244933, -1.4384604484134897, -1.3597658449957826, -0.43622462878644236, 0.20313570828235272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5746620508184985, -0.8198066570943798, 0.011127560097199687]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0037416687149008704, 0.2034947798823411, 0.6434802943384312, 0.0, 1.000000501038282, -0.5961001994631429, -0.19717170166446063, 0.4108862629400797, 0.8435074599703899, -0.7318617851506478, -0.9999999999991428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020325388551032584, 0.031567389185251316, -0.010611229935948806, -0.04418219293003397, -0.019537685787518445, 0.023646167902244993, 0.070287424503733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0122991916697603, 0.013161644876666068, 0.009073677226740184]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162343033222278, 0.7078118452244335, 0.4501105671587205, 0.0, -0.36774554453626296, -0.09690134203580636, -1.761544700939211, -1.9721746062238763, -1.6748450072361283, -1.0620272894402405, -1.2547255030645281, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.524673001695444, 0.4510001492311551, 1.9809170383055825, -1.4402888447405928, -1.3607687126545345, -0.43524822566641097, 0.20622491514305752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5751522977154073, -0.8192603460384954, 0.011491936717635617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002582414500807392, 0.18322011792067883, 0.6601432842053381, 0.0, 1.0000005011114224, -0.46858312422855053, -0.16629091881781388, 0.49429866232274333, 0.828841459347548, -0.8254894281197187, -1.0000000000019789, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016316887545187387, 0.026440788860746276, -0.008226528378214592, -0.03656792654206047, -0.02005735317503829, 0.019528062400627478, 0.06178413721409572, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009804937938176241, 0.010926221117688293, 0.007287532408718606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162711890077621, 0.7160269801016663, 0.4863784252004865, 0.0, -0.31774551948096824, -0.11360226366310819, -1.7677712323515853, -1.9412527608613792, -1.6321713316739597, -1.1070468665649071, -1.3047255030645084, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5253242594531973, 0.4520665899648609, 1.9805905571586677, -1.441818579075301, -1.3617692391313345, -0.43443765474576707, 0.20890185798052224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5755380497716864, -0.8188085082057069, 0.011781101090047551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007377137106863599, 0.16430269754465562, 0.7253571608353208, 0.0, 1.0000005011058941, -0.3340184325460365, -0.1245306282474882, 0.6184369072499402, 0.8534735112433738, -0.9003915424933324, -0.9999999999996035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013025155155065297, 0.021328814674115106, -0.006529622938295442, -0.03059468669416693, -0.0200105295360013, 0.016211418412877703, 0.05353885674929457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007715041125582626, 0.009036756655768476, 0.005783287448238683]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159367506666766, 0.7233865153216565, 0.5251744528170496, 0.0, -0.26774549442831785, -0.12342146655364405, -1.771188601824272, -1.9045152845676274, -1.5903369380614212, -1.1550625282643645, -1.354725503058329, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.525899213414699, 0.45278801160362625, 1.980187198508186, -1.4432988786032843, -1.3629472452589293, -0.43357439586132634, 0.2113537761611685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5758347211539119, -0.8184474799087609, 0.012002327230215428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006688766821709505, 0.14719070439980478, 0.7759205523312611, 0.0, 1.0000005010530082, -0.19638405781071713, -0.06834738945373522, 0.7347495258750361, 0.83668787225077, -0.9603132339891487, -0.9999999998764122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011499079230032749, 0.014428432775307988, -0.00806717300963372, -0.029605990559664973, -0.0235601225518954, 0.017265177688813953, 0.049038363612924935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0059334276445095965, 0.007220565938920812, 0.004424522803357532]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2158916048919643, 0.7300199138168821, 0.565680859900154, 0.0, -0.2177454693738724, -0.1283063309782898, -1.7738704582208418, -1.8634470456714147, -1.553053998942496, -1.2023242745390155, -1.4009755030462177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.526351954915823, 0.45326620774519955, 1.979880082590455, -1.4445268224935641, -1.364050566137246, -0.4328866556453435, 0.21337136256767764, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576058041961036, -0.8181695539790187, 0.012163533554393306]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0009029154942464543, 0.13266796990451232, 0.8101281416620897, 0.0, 1.0000005010889093, -0.09769728849291497, -0.05363712793139592, 0.821364777924255, 0.7456587823785038, -0.9452349254930191, -0.9249999997577742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009054830022484882, 0.009563922831465552, -0.006142318354621725, -0.024558877805596468, -0.022066417566334734, 0.01375480431965618, 0.04035172813018302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0044664161424821935, 0.005558518594844598, 0.003224126483557547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589189919682666, 0.7361088754167711, 0.6074039117793574, 0.0, -0.16892147583361156, -0.12956225143849473, -1.7765674459585095, -1.820695993134153, -1.5233605592214299, -1.2450821053898335, -1.439725503032831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5266852958960513, 0.4535613280572647, 1.9797109718256964, -1.4454807088340924, -1.3650199245358223, -0.4324219235076778, 0.2149562932432828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576223948085373, -0.8179602140625281, 0.012276572207045667]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.88609724750343e-06, 0.1217792319977778, 0.8344610375840658, 0.0, 0.9764798708052171, -0.02511840920409865, -0.053939754753353844, 0.8550210507452309, 0.5938687944213256, -0.8551566170163605, -0.7749999997322676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006666819604565746, 0.0059024062413025, -0.0033822152951722296, -0.019077726810566825, -0.019387167971525624, 0.009294642753314968, 0.031698613512103596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0033181224867408015, 0.004186798329813272, 0.0022607730530471923]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589179049203364, 0.7419896101737604, 0.6499906929966629, 0.0, -0.12293056851496348, -0.12839912201660045, -1.7794324364527976, -1.7783894157666098, -1.5015766638851424, -1.2795860212549266, -1.4672255223888533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5269085793459622, 0.4536970573072909, 1.9796983819463954, -1.4461982755440874, -1.3658959765838994, -0.43218793955717316, 0.21618844913039548, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5763461840669706, -0.8178046273553017, 0.012354010113691537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.174095860320641e-06, 0.11761469513978803, 0.8517356243461112, 0.0, 0.9198181463729616, 0.02326258843788543, -0.0572998098857646, 0.8461315473508657, 0.4356779067257498, -0.6900783173018591, -0.5500003871204437, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004465668998217787, 0.002714585000523732, -0.0002517975860218875, -0.01435133419990044, -0.017521040961542503, 0.004679679010092371, 0.02464311774225373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024447196319503485, 0.00311173414452738, 0.0015487581329174274]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.215891300583474, 0.7492557013048864, 0.6960862303606239, 0.0, -0.08017595878416242, -0.12606001160848526, -1.7825971347798657, -1.7373062925934304, -1.486111230178705, -1.3047685187847757, -1.4848641171228292, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.527023775674254, 0.45366041774089694, 1.979881184598014, -1.4467323245553512, -1.3667866296224584, -0.4322087245552573, 0.21717654821202317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5764357684233186, -0.8176899617881661, 0.012406459950623996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.798171192739838e-06, 0.1453218226225197, 0.921910747279219, 0.0, 0.8550921946160212, 0.04678220816230391, -0.06329396654136117, 0.8216624634635894, 0.30930867412875174, -0.5036499505969823, -0.3527718946795181, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002303926565833962, -0.0007327913278783694, 0.0036560530323733686, -0.010680980225275452, -0.017813060771180934, -0.0004156999616818438, 0.019761981632554135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001791687126959772, 0.0022933113427117493, 0.0010489967386491615]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589173662226246, 0.759351261113381, 0.7430336148888977, 0.0, -0.04026912872065058, -0.1237878204342026, -1.786477301610424, -1.6974154790669336, -1.474585284131528, -1.321363987196231, -1.4957549757997157, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5270099956686989, 0.45337431814628315, 1.9803723159021267, -1.447137270124206, -1.3679050721537116, -0.4325829223975431, 0.2180583515044032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5765011963325737, -0.8176059127579575, 0.01244193810791947]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.720775769080022e-06, 0.20191119616989317, 0.9389476905654772, 0.0, 0.7981366012702368, 0.0454438234856532, -0.07760333661116693, 0.7978162705299348, 0.23051892094354293, -0.3319093682291082, -0.2178171735377326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00027560011110191324, -0.005721991892276191, 0.00982262608225562, -0.008098911377098809, -0.022368850625062584, -0.007483956845716114, 0.017636065847600378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001308558185101751, 0.0016809806041733, 0.0007095631459094907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589430115799504, 0.7732847017996285, 0.7876129632847731, 0.0, -0.002327587580490162, -0.12355871710289275, -1.7927925866216299, -1.6583658459876376, -1.4638333861573112, -1.3293772034657854, -1.5029898745044112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.526767110999636, 0.4525544660849843, 1.9815573384992808, -1.4474763615281996, -1.369826406076475, -0.43368371325002, 0.21908811276104348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5765488771991691, -0.8175445258402938, 0.012466102060951773]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.129071465156936e-05, 0.27866881372495017, 0.8915869679175081, 0.0, 0.7588308228032083, 0.004582066626196889, -0.1263057002241159, 0.7809926615859178, 0.21503795948433374, -0.16026432539108484, -0.1446979740939091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004857693381261481, -0.01639704122597763, 0.0237004519430849, -0.006781828079873515, -0.03842667845527177, -0.02201581704953777, 0.020595225132805525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0009536173319111582, 0.0012277383532731728, 0.0004832790606460757]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21590609631658084, 0.7900574840513496, 0.8240423854027401, 0.0, 0.03523287020506859, -0.12912270161455572, -1.805292989813483, -1.6198665217233719, -1.4501055362560549, -1.3250581675934394, -1.5095112286419894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5256104695071213, 0.44938487605488964, 1.9858700843775696, -1.4479332697632863, -1.3758855876505387, -0.4379331040685293, 0.22148334910696701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576583675118812, -0.8174996573283833, 0.012482754931288205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00023590317171581565, 0.3354556450344224, 0.7285884423593383, 0.0, 0.751209155711175, -0.11127969023325943, -0.2500080638370649, 0.769986485285313, 0.27455699802512457, 0.08638071744693857, -0.13042708275156265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023132829850290696, -0.06339180060189321, 0.08625491756577541, -0.009138164701733294, -0.12118363148127341, -0.08498781637018643, 0.04790472691847068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006959583928589584, 0.0008973702382113635, 0.0003330574067286343]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21591239160698106, 0.8065715201808511, 0.8494001141253666, 0.0, 0.07269977981555831, -0.13990672684877223, -1.8246258050487183, -1.5812186300344115, -1.4310302358916624, -1.3121568795791914, -1.51662712810651, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.524140281619032, 0.4454489033612587, 1.991197044132715, -1.4483993780003213, -1.3832021319099619, -0.44321845263029125, 0.2242202521301125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766090195596798, -0.8174669470106104, 0.012494043396536002]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012590580800439537, 0.33028072259003083, 0.5071545744525306, 0.0, 0.7493381922097945, -0.21568050468433003, -0.3866563047047031, 0.7729578337792077, 0.3815060072878471, 0.258025760284962, -0.14231798929041423, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029403757761788128, -0.07871945387261897, 0.10653919510290671, -0.009322164740701322, -0.14633088518846293, -0.10570697123523844, 0.0547380604629098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005068888173575506, 0.0006542063554582017, 0.00022576930495594148]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159163704083399, 0.8205090998338253, 0.8650613980892129, 0.0, 0.10656739377778013, -0.15369819438266474, -1.8470411303589107, -1.5456334884977432, -1.4093301464761927, -1.2944233394230389, -1.5245393743630447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5226919026162564, 0.4416296960259477, 1.9963609801742173, -1.448818667896878, -1.3901718883057692, -0.4483618399367749, 0.22673047492575288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766274551752486, -0.817443138320974, 0.012501034905632967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.957602717686654e-05, 0.27875159305948405, 0.31322567927692535, 0.0, 0.6773522792444362, -0.2758293506778502, -0.4483065062038499, 0.7117028307333694, 0.4340017883093956, 0.3546708031230489, -0.1582449251306935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896758005550831, -0.07638414670621974, 0.10327872083004798, -0.008385797931134292, -0.13939512791614628, -0.10286774612967307, 0.05020445591280705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00036871231137786917, 0.00047617379272641753, 0.00013983018193930766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21591846638433038, 0.8308267091968453, 0.8735532413427327, 0.0, 0.13460465274938582, -0.1673231784558116, -1.8693759873858737, -1.5155056574937162, -1.3876766768030777, -1.2756075469879022, -1.5328901572724403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5214092770187255, 0.43829550374891313, 2.0008710070916047, -1.449173336645027, -1.396145887793108, -0.45286870080990366, 0.22879928499548088, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576640854211947, -0.8174258264651038, 0.012504095352313446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.191951980910782e-05, 0.20635218726040166, 0.16983686507039716, 0.0, 0.5607451794321137, -0.2724996814629371, -0.44669714053925935, 0.6025566200805388, 0.43306939346229867, 0.37631584870273244, -0.16701565818791347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02565251195061844, -0.06668384554069101, 0.09020053834774705, -0.007093374962978895, -0.11947998974677948, -0.09013721746257458, 0.041376201394560115, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00026798073396736726, 0.00034623711740634864, 6.120893360955853e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.215919588922821, 0.8375202029258337, 0.8773169676153797, 0.0, 0.15628752455972358, -0.17903238903461943, -1.889774123183603, -1.49173645040255, -1.3677584926005861, -1.259459501159503, -1.5411219256484496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5203317788181698, 0.43553305940460224, 2.0046117283894684, -1.4494644123703038, -1.400999829049478, -0.45661849619583966, 0.23040781201872712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576650586858912, -0.8174132481648868, 0.01250339576930071]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2450769812901647e-05, 0.13386987457976823, 0.07527452545294017, 0.0, 0.43365743620675534, -0.2341842115761567, -0.4079627159545817, 0.4753841418233231, 0.39836368404983175, 0.32296091656798814, -0.1646353675201882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021549964011112532, -0.05524888688621789, 0.07481442595727661, -0.005821514505537173, -0.09707882512740067, -0.07499590771872015, 0.03217054046492456, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00019465293930204708, 0.00025156600433931715, -1.3991660254685949e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592028416743744, 0.8412076929133199, 0.8782851637975998, 0.0, 0.17219441942329763, -0.18838381922462513, -1.9074529453660065, -1.4741007150488583, -1.3503662981337086, -1.2472265785183194, -1.5487315660902718, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5194503203404521, 0.43330126572356464, 2.007638203136889, -1.449700224282889, -1.404843872631857, -0.45966122029341006, 0.2316219746546978, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766576531322427, -0.8174041143422259, 0.012499270388777595]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3904892328924762e-05, 0.07374979974972211, 0.019363923644401433, 0.0, 0.3181378972714808, -0.18702860380011424, -0.353576443648071, 0.3527147070738369, 0.3478438893375491, 0.24465845282366966, -0.152192808836446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0176291695543547, -0.044635873620752206, 0.060529494948413226, -0.004716238251705162, -0.07688087164758074, -0.06085448195140746, 0.02428325271941388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014132546661368788, 0.00018267645321861574, -8.250761046231589e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592080875722977, 0.8427448057043214, 0.8778145431288397, 0.0, 0.18339369966780433, -0.1956518856007628, -1.9223225653088494, -1.4617439120012894, -1.3356723184941723, -1.2382601369314048, -1.555396119876389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5187363714987747, 0.4315116777774094, 2.010068682137961, -1.4498909717613313, -1.4078683151679736, -0.462111079149444, 0.2325317153861216, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766627816127567, -0.8173974846632517, 0.012492327253483876]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0491795846399363e-05, 0.03074225582003097, -0.009412413375202367, 0.0, 0.22398560489013386, -0.14536132752275313, -0.297392398856859, 0.24713606095138038, 0.29387959279072645, 0.17932883173829212, -0.13329107572234478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0142789768335462, -0.03579175892310448, 0.04860958002144151, -0.0038149495688463075, -0.06048885072233197, -0.0489971771206786, 0.01819481462847594, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010256961028162241, 0.0001325935794857931, -0.0001388627058744008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592144623358347, 0.8429567723611886, 0.876766934215052, 0.0, 0.19101533016282285, -0.2014844810922375, -1.9345392921528537, -1.453567437051174, -1.3235930863131655, -1.2316585904370987, -1.560965063559079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5181554471802858, 0.43006568991592586, 2.012035269925368, -1.450046458769252, -1.4102724078066773, -0.4640975024317748, 0.23322298669636848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576666502537178, -0.8173926742470801, 0.012483378408803487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2749527073852692e-05, 0.004239333137342767, -0.020952178275752208, 0.0, 0.1524326099003705, -0.11665190982949397, -0.24433453688008688, 0.16352949900230987, 0.24158464362013726, 0.13203092988612086, -0.11137887365379968, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01161848636977806, -0.028919757229670433, 0.03933175574813183, -0.0031097401584169247, -0.04808185277407372, -0.03972846564661532, 0.013825426204937482, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.441848842412248e-05, 9.620832343191341e-05, -0.00017897689360777522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592207136732375, 0.8424985506961189, 0.8756467084427816, 0.0, 0.19610265931802137, -0.20632522305355458, -1.9446056578985407, -1.448494782146984, -1.3137019045711587, -1.2264961082123185, -1.5654865477704474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5176727895144926, 0.42886894358724215, 2.0136644755581936, -1.4501757241126365, -1.4122380278492914, -0.46574556114470866, 0.233768373574324, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576669201551716, -0.8173891847950254, 0.01247329796908276]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.250267480566886e-05, -0.009164433301393956, -0.022404515445408363, 0.0, 0.10174658310397038, -0.09681483922634204, -0.20132731491373773, 0.10145309808379763, 0.19782363484013826, 0.10324964449560496, -0.0904296842273688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009653153315865222, -0.02393492657367454, 0.03258411265651309, -0.0025853068676888018, -0.03931240085228328, -0.03296117425867807, 0.010907737559110448, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.398029076222452e-05, 6.978904109171216e-05, -0.00020160879441454436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592276667102406, 0.841815208425571, 0.8746818778104144, 0.0, 0.19950917726296824, -0.21058461093920003, -1.95311717483538, -1.4455991060348434, -1.3054556475814114, -1.2220420470146103, -1.5691231888959736, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5172549626536735, 0.4278346439823447, 2.0150730081056403, -1.4502869507262741, -1.4139250520492952, -0.4671715518737851, 0.23422642363032573, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766711589451656, -0.8173866540558294, 0.012462887843654128]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3906074006320027e-05, -0.013666845410958063, -0.01929661264734479, 0.0, 0.06813035889893718, -0.08518775771290872, -0.17023033873678506, 0.05791352224281087, 0.16492513979494575, 0.08908122395416296, -0.0727328225105235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008356537216378641, -0.020685992097948365, 0.028170650948937014, -0.002224532272752956, -0.033740484000075, -0.028519814581529038, 0.00916100112003444, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.914786899051769e-05, 5.0614783918740665e-05, -0.0002082025085726267]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592363281583407, 0.8411631461231693, 0.8739743485374111, 0.0, 0.2018913752727152, -0.21466387717629185, -1.9606882785656565, -1.444152850098053, -1.2982730206757522, -1.2177424343571432, -1.5720975586767845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.516869399914534, 0.42688127996717673, 2.0163708509166547, -1.4503878095286389, -1.4154772742120336, -0.46848581513436083, 0.23464506123575493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766725783174815, -0.8173848189166727, 0.012452789896708727]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.732289620053473e-05, -0.013041246048033497, -0.01415058546006677, 0.0, 0.04764396019493895, -0.08158532474183608, -0.15142207460553064, 0.028925118735807644, 0.14365253811318474, 0.08599225314934242, -0.05948739561621958, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007711254782791014, -0.019067280303360277, 0.02595685622028429, -0.0020171760472965953, -0.03104444325477014, -0.02628526521151416, 0.008372752108584354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.838744631771187e-05, 3.670278313388672e-05, -0.00020195893890803947]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592477667594878, 0.8406577130835283, 0.8735226834083538, 0.0, 0.20374254166865938, -0.21897056420877617, -1.9679482942235194, -1.443627838497016, -1.2915514948599816, -1.21314021080406, -1.5746601787676242, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5164828272274602, 0.4259277100762982, 2.017667829288331, -1.4504859646409984, -1.4170327057611107, -0.4697991077461509, 0.23506626840277056, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766736075232575, -0.817383488393567, 0.012443449818613044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2877202294066204e-05, -0.010108660792821005, -0.009033302581144181, 0.0, 0.03702332791888362, -0.08613374064968642, -0.14520031315725546, 0.010500232020739651, 0.13443051631541214, 0.09204447106166512, -0.05125240181679408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007731453741476311, -0.019071397817570584, 0.025939567433532294, -0.0019631022471926374, -0.031108630981543005, -0.0262658522358016, 0.008424143340312738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0584115520505476e-05, 2.6610462113848206e-05, -0.00018680156191364653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592632075994195, 0.8403241692890389, 0.8732743701294216, 0.0, 0.2054385467094953, -0.22393733246598, -1.9755598358118025, -1.4436694255958185, -1.2846606616430987, -1.2077988481117838, -1.5770747284452407, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5160595274596225, 0.4248882328976074, 2.019080213625286, -1.450589540676932, -1.4187333479159343, -0.4712290886333637, 0.2355301573373347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766743539716053, -0.8173825239153957, 0.01243512032532734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.0881679863520025e-05, -0.006670875889790261, -0.0049662655786444935, 0.0, 0.03392010081671844, -0.09933536514407672, -0.15223083176566451, -0.0008317419760473996, 0.13781666433765968, 0.1068272538455255, -0.04829099355232919, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008465995356754803, -0.020789543573815503, 0.028247686739097513, -0.0020715207186697256, -0.03401284309647063, -0.02859961774425593, 0.00927777869128266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4928966956951001e-05, 1.928956342612068e-05, -0.00016658986571407256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592837313759222, 0.8401399818720189, 0.8731745563741776, 0.0, 0.2072753417686052, -0.2300038506932905, -1.9842096390879937, -1.4440596654363946, -1.276954947687852, -1.2012731841826814, -1.5796078017330637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5155618918280447, 0.4236736009321645, 2.0207293173394536, -1.4507070522003822, -1.420724401049599, -0.47289879103111937, 0.23607546635694754, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766748960795607, -0.8173818247433609, 0.012427886678573266]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.10475530056903e-05, -0.0036837483403993143, -0.0019962751048792655, 0.0, 0.03673590118219847, -0.12133036454621018, -0.17299606552382382, -0.00780479681152317, 0.15411427910493397, 0.13051327858204945, -0.05066146575645986, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009952712631557798, -0.024292639308858496, 0.032982074283348234, -0.002350230469002594, -0.03982106267329322, -0.03339404795511332, 0.010906180392256867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0842159109250312e-05, 1.3983440697576432e-05, -0.00014467293508149443]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21593090915604493, 0.8400644754306554, 0.8731711105808895, 0.0, 0.20947300638217142, -0.23747315527226306, -1.9944781440869066, -1.4446748684738369, -1.267888536873459, -1.1931992518250587, -1.582495335368966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5149588180569578, 0.4222112042482151, 2.0227141431200466, -1.4508456205572675, -1.423121295141431, -0.4749088822705441, 0.23673063968469862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576675291477197, -0.8173813174321216, 0.012421701531268587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.072036905393115e-05, -0.0015101288272689334, -6.891586576328562e-05, 0.0, 0.043953292271324496, -0.14938609157945143, -0.20537009997825864, -0.012304060748844723, 0.18132821628785936, 0.16147864715245108, -0.057750672718043614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01206147542173898, -0.0292479336789873, 0.03969651561186048, -0.002771367137704609, -0.04793788183663858, -0.04020182478849534, 0.013103466555021596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.90795273015664e-06, 1.0146224784961677e-05, -0.00012370294609357957]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21593458542595576, 0.8400565276487061, 0.8732155072342905, 0.0, 0.21195611774069972, -0.24651320793852163, -2.005780787001844, -1.4453993079128558, -1.2579430956204947, -1.1841526882115823, -1.5856560986036354, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.514243799190956, 0.4204890296150937, 2.0250525489854976, -1.4510064027574883, -1.425937687052036, -0.4772781503751746, 0.237493967843305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766755822171956, -0.8173809486191156, 0.012416422839096742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.35253982162208e-05, -0.00015895563898790134, 0.0008879330680210279, 0.0, 0.04966222717056607, -0.1808010533251716, -0.22605285829874183, -0.014488788780377838, 0.19890882505928295, 0.18093127226952876, -0.06321526469338973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014300377320032542, -0.034443492662428424, 0.04676811730902393, -0.003215644004415444, -0.0563278382120984, -0.04738536209261056, 0.015266563172127922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.814799968591929e-06, 7.3762601198729884e-06, -0.00010557384343690711]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159377105050664, 0.8400830617014325, 0.8732754512898439, 0.0, 0.21470389616639007, -0.25604386349769387, -2.0178742870655078, -1.4461792230555628, -1.2473079523965982, -1.1744097539488378, -1.5890858194832187, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5134465284677285, 0.41858071846444683, 2.027645110789527, -1.4511837088736705, -1.429046657016919, -0.47990637707530426, 0.23832559787056715, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766757990824232, -0.8173806794225769, 0.012411842508808769]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.250158221312072e-05, 0.0005306810545285066, 0.0011988811110659446, 0.0, 0.05495556851380717, -0.19061311118344498, -0.24187000127328145, -0.015598302854141849, 0.21270286447793008, 0.19485868525488895, -0.0685944175916668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015945414464552568, -0.03816622301293802, 0.05185123608059011, -0.003546122323647246, -0.062179399297660566, -0.05256453400259258, 0.01663260054524279, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.337304552879942e-06, 5.383930773913741e-06, -9.160660575947477e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159401042072035, 0.8401214637842623, 0.8733258854014846, 0.0, 0.2176404747430788, -0.2650664053455912, -2.030355835872431, -1.4469771693295321, -1.2363190364920513, -1.1643540291278451, -1.5927166197570775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5126139262124012, 0.41659996207142724, 2.030337858477653, -1.4513680900137969, -1.432257544752325, -0.4826378721006799, 0.2391699375814941, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766759617707886, -0.8173804826240931, 0.01240772225928613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.787404274154579e-05, 0.000768041656595599, 0.0010086822328158646, 0.0, 0.058731571533774646, -0.1804508369579477, -0.24963097613846758, -0.015958925479386522, 0.2197783180909384, 0.2011144964198525, -0.07261600547717549, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016652045106548267, -0.0396151278603915, 0.05385495376251854, -0.003687622802525284, -0.06421775470812037, -0.05462990050751203, 0.016886794218539013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2537673107950513e-06, 3.935969675339722e-06, -8.240499045276278e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21594197441795052, 0.84015863685121, 0.8733572814594331, 0.0, 0.22065823596785175, -0.27305696764196996, -2.042752286947001, -1.4477627659410925, -1.2253801173615602, -1.154403534011897, -1.5964397100542411, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5117893052339886, 0.41465028947128185, 2.032990500177995, -1.4515506001072485, -1.4353993725434375, -0.4853305374358153, 0.2399793098458615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676083491778, -0.817380338914657, 0.012403825303958642]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7404214940475286e-05, 0.0007434613389519565, 0.000627921158970837, 0.0, 0.06035522449545908, -0.15981124592757517, -0.24792902149139728, -0.01571193223121016, 0.21877838260982452, 0.19900990231896143, -0.07446180594327372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01649241956825173, -0.03899345200290812, 0.053052834006838676, -0.003650201869034196, -0.06283655582225203, -0.053853306702708464, 0.016187445287347797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.434419785478593e-06, 2.874188722444224e-06, -7.79391065497722e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21594354553461037, 0.8401886364337162, 0.8733692803972181, 0.0, 0.22365660805189697, -0.27992594781047014, -2.054671589213391, -1.4485130572280134, -1.2148295008256054, -1.144891112663089, -1.6001495093296336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.511002082831931, 0.41280064598478106, 2.0355095100399567, -1.451725049944099, -1.4383605986887842, -0.4878894239456292, 0.24072458173168984, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766761739515076, -0.8173802342771437, 0.0123999487798776]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.142233319720339e-05, 0.0005999916501264072, 0.00023997875569772256, 0.0, 0.05996744168090451, -0.13737960337000357, -0.23838604532779534, -0.015005825738417735, 0.21101233071909675, 0.19024842697616257, -0.07419598550784838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015744448041149495, -0.036992869730015754, 0.05038019723924021, -0.0034889967370092738, -0.059224522906932454, -0.05117773019627771, 0.014905437716566855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.809194594560338e-06, 2.0927502673642333e-06, -7.753048162083476e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159449820297096, 0.8402101010810369, 0.8733679954901823, 0.0, 0.22656483244170594, -0.28584143386337596, -2.065879500033873, -1.4492141274173287, -1.2048719040331601, -1.1360081586679716, -1.603770258890877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5102665040534171, 0.4110829541548379, 2.0378514356700976, -1.4518883737617432, -1.4410920192881933, -0.49027018239967124, 0.24139504103846432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766762406808519, -0.8173801583820273, 0.012395952020772734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8729901984752316e-05, 0.00042929294641247693, -2.569814071482732e-05, 0.0, 0.05816448779617955, -0.11830972105811606, -0.22415821640964378, -0.014021403786305387, 0.19915193584890464, 0.17765907990234958, -0.07241499122487151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01471157557027697, -0.03435383659886264, 0.04683851260281737, -0.0032664763528811513, -0.05462841198818197, -0.04761516908084137, 0.013409186135489448, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3345868867553702e-06, 1.5179023284750687e-06, -7.99351820972933e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159470230481963, 0.8402241033428237, 0.873316473887058, 0.0, 0.22922145137901329, -0.2909324093961718, -2.0758262154002325, -1.4498335646532874, -1.19599881717931, -1.128182259202516, -1.6071054191225584, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5095845525926923, 0.4095002636860508, 2.0400124478410366, -1.452039623045926, -1.4435920631059063, -0.49246867263430294, 0.24199305364027823, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766762894499942, -0.81738010363057, 0.012391770596960651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.0820369733810705e-05, 0.0002800452357358271, -0.0010304320624853146, 0.0, 0.05313237874614665, -0.10181951065591664, -0.19893430732718959, -0.012388744719175039, 0.17746173707700288, 0.15651798930911226, -0.06670320463362689, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013639029214494468, -0.03165380937574211, 0.04322024341877805, -0.0030249856836570633, -0.05000087635425719, -0.043969804692634264, 0.0119602520362783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.75382847270955e-07, 1.0950291452706703e-06, -8.362847624165307e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159489966313008, 0.8402326395087604, 0.8732373272524211, 0.0, 0.23163421257495104, -0.2953353469309635, -2.084621671625861, -1.4503780018378793, -1.1881193894152526, -1.121314693473251, -1.6101627168502768, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5089502229199343, 0.4080363760371041, 2.04201412463679, -1.452180121586204, -1.445890341432157, -0.4945064492712407, 0.24252940036177964, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763248443838, -0.8173800643513706, 0.012387410277318217]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.947166208996519e-05, 0.00017072331873303499, -0.0015829326927375889, 0.0, 0.04825522391875479, -0.08805875069583459, -0.1759091245125729, -0.010888743691839047, 0.15758855528114588, 0.13735131458529704, -0.061145954554366375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012686593455158733, -0.029277752978934327, 0.04003353591507405, -0.0028099708055602177, -0.04596556652501308, -0.040755532738755665, 0.010726934430028246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.078877923232286e-07, 7.855839884439229e-07, -8.720639284867325e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21595099266389092, 0.8402377276484505, 0.8731588134762326, 0.0, 0.23385293871434631, -0.2992877995882791, -2.092528680289307, -1.450863810201461, -1.1810079601994896, -1.1151855044540675, -1.6129993417278743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5083525410696597, 0.4066639962342536, 2.0438931609506077, -1.452312269798413, -1.448033558718617, -0.4964204949428506, 0.24301856586222076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763503960346, -0.8173800363385021, 0.012382929481272998]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9920651802372225e-05, 0.00010176279380187969, -0.0015702755237693192, 0.0, 0.044374522787905706, -0.07904905314631136, -0.15814017326892033, -0.009716167271634019, 0.1422285843152585, 0.12258378038366921, -0.056732497551952116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011953637005493213, -0.027447596057010047, 0.037580726276351194, -0.002642964244178485, -0.04286434572920141, -0.038280913432198124, 0.009783310008822429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.110330139398487e-07, 5.602573691511586e-07, -8.961592090437526e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21595313419935216, 0.8402409797990021, 0.8730968281321149, 0.0, 0.23593649538374117, -0.30304366586495857, -2.099825670503527, -1.4513089452712393, -1.174423848655995, -1.1095649712731295, -1.6156834869333663, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.50777792089147, 0.40535053884177635, 2.045693645666361, -1.4524389672373113, -1.4500757684875984, -0.49825542700245756, 0.24347583941302972, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763688102383, -0.8173800164738938, 0.012378414707804826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.2830709225039965e-05, 6.504301103345072e-05, -0.0012397068823546441, 0.0, 0.04167113338789714, -0.0751173255335885, -0.14593980428440173, -0.008902701395564878, 0.131682230869891, 0.11241066361875963, -0.053682904109841674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492403563794468, -0.02626914784954481, 0.03600969431506262, -0.002533948777964499, -0.04084419537962833, -0.0366986411921391, 0.009145471016178991, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.682840762130365e-07, 3.972921648385109e-07, -9.029546936343603e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21595548564482472, 0.8402434860195173, 0.8730559524624514, 0.0, 0.23794557033661567, -0.3068162975717414, -2.1067756350848548, -1.4517309095845337, -1.1681377893609863, -1.1042395974801473, -1.6182869481125797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5072119585216643, 0.40406230439471447, 2.0474613881533763, -1.4525632553691452, -1.4520716127281788, -0.5000577335602894, 0.2439155470198356, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676382172261, -0.817380002440857, 0.012373956685973405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.702890945114864e-05, 5.012441030329155e-05, -0.0008175133932696904, 0.0, 0.040181499057489876, -0.07545263413565606, -0.13899929162655747, -0.008439286265888071, 0.12572118590017434, 0.1065074758596434, -0.0520692235842691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011319247396112711, -0.025764688941237786, 0.0353548497403109, -0.002485762636680195, -0.03991688481160455, -0.03604613115663642, 0.008794152136117582, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.672404536954776e-07, 2.806607361082081e-07, -8.916043662840314e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159580726693663, 0.840245869530659, 0.873033214046067, 0.0, 0.23993983923623685, -0.31075820973619334, -2.1136168834040268, -1.452145953540715, -1.1619398528599996, -1.099019626367877, -1.6208822700658403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5066410133885872, 0.40276800736201873, 2.0492390764378476, -1.4526880131809121, -1.4540708410689183, -0.5018708300377867, 0.24434983230168383, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676392108324, -0.817379992513634, 0.012369632043218578]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.17404908317958e-05, 4.7670222835896046e-05, -0.0004547683276874278, 0.0, 0.03988537799242344, -0.07883824328903885, -0.1368249663834378, -0.00830087912362951, 0.12395873001973316, 0.10439942224540322, -0.051906439065212674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011418902661540612, -0.025885940653914523, 0.03555376568942702, -0.0024951562353396394, -0.0399845668147919, -0.03626192954994639, 0.008685705636964716, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9872126240237643e-07, 1.9854445858287876e-07, -8.64928550965503e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159608841536071, 0.8402484111452629, 0.8730239800319247, 0.0, 0.24197393499607453, -0.3149554196906617, -2.120552158117975, -1.4525681878027377, -1.1556494082795836, -1.0937469963910538, -1.6235377347850863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.506053871567022, 0.4014424027175185, 2.051061273191534, -1.4528156270749337, -1.4561128408258919, -0.5037299362171452, 0.24478759693517918, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763998916629, -0.8173799854079904, 0.012365492236145767]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.622968481552113e-05, 5.0832292077428795e-05, -0.0001846802828468088, 0.0, 0.04068191519675366, -0.08394419908936741, -0.13870549427896434, -0.008444685240453125, 0.12580889160831923, 0.10545259953646562, -0.05310929438491979, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011742836431306334, -0.026512092890004155, 0.03644393507372888, -0.002552277880430158, -0.04083999513947152, -0.03718212358717131, 0.008755292669906762, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5566677781963244e-07, 1.421128725089157e-07, -8.27961414562238e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21596386743500362, 0.8402511803203537, 0.8730235011087707, 0.0, 0.24409181065568408, -0.31942508838161177, -2.127733127210675, -1.4530084586377217, -1.1491295454353578, -1.0883063992950341, -1.6263098983711688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5054434443751898, 0.4000699316727836, 2.0529493654191224, -1.452947644357068, -1.458221251668446, -0.5056568971369724, 0.24523357100384258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764064860321, -0.8173799801842342, 0.01236155953543708]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.9665627930762826e-05, 5.538350181546567e-05, -9.57846308060275e-06, 0.0, 0.042357513192191235, -0.08939337381900063, -0.14361938185399623, -0.008805416699680711, 0.13039725688451576, 0.10881194192039391, -0.05544327172165074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012208543836644697, -0.027449420894698887, 0.037761844551767114, -0.0026403456426838797, -0.04216821685108552, -0.03853921839654265, 0.008919481373267667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3188738514049965e-07, 1.0447512484759081e-07, -7.86540141737562e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21596791935933207, 0.8402541435701938, 0.8730988289298659, 0.0, 0.24611662478430685, -0.32334780789951073, -2.134547216497519, -1.4534297783224368, -1.1429342209444933, -1.0831630326458568, -1.628968556275335, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.504807760643504, 0.3986474695557953, 2.0549085975546424, -1.4530838697318595, -1.4603998765897372, -0.5076572448587156, 0.2456872916353901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764134359896, -0.8173799758642565, 0.012357826730312984]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.103848656920515e-05, 5.926499680215976e-05, 0.0015065564219046395, 0.0, 0.04049628257245506, -0.07845439035797905, -0.13628178573687688, -0.008426393694302361, 0.12390648981729102, 0.10286733298354611, -0.05317315808332461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012713674633719708, -0.02844924233976674, 0.03918464271039906, -0.0027245074958317174, -0.043572498425824675, -0.04000695443486381, 0.009074412630950702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3899915003731548e-07, 8.639955350694817e-08, -7.46561024819113e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21597193409023838, 0.8402572356730094, 0.8731385286506769, 0.0, 0.24803444972891642, -0.326734566813432, -2.1409460258204467, -1.4538288974523306, -1.1371066795213836, -1.078353146790863, -1.6314959066735615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5041516944992641, 0.3971863693134425, 2.056923364488729, -1.4532234661303138, -1.4626303382089374, -0.5097150993131078, 0.24614398878160565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764200682881, -0.8173799723988152, 0.012354263573504849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.02946181258546e-05, 6.184205631085905e-05, 0.0007939944162183162, 0.0, 0.03835649889219139, -0.06773517827842575, -0.12797618645855235, -0.007982382597875527, 0.11655082846219302, 0.09619771709987601, -0.05054700796452541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0131213228847984, -0.029222004847056036, 0.0402953386817301, -0.0027919279690843397, -0.04460923238400132, -0.04115708908784493, 0.00913394292431082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3264597061330337e-07, 6.930882429567642e-08, -7.126313616272932e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21597580098874633, 0.8402603979967255, 0.8731418168528109, 0.0, 0.24986017871290592, -0.32975468697718513, -2.1469838422511227, -1.4542080915877584, -1.131597685108248, -1.073834053765486, -1.6339115395295283, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5034837183596121, 0.3957057154866313, 2.0589672791372515, -1.4533649440652163, -1.4648826326779465, -0.5118035332713099, 0.24659672396577523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676426062618, -0.8173799696960767, 0.012350825882576735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.733797015885058e-05, 6.324647432168868e-05, 6.576404268071893e-05, 0.0, 0.036514579679790014, -0.060402403275062605, -0.1207563286135167, -0.0075838827085569814, 0.1101798882627073, 0.09038186050753894, -0.04831265711933672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013359522793037494, -0.029613076536222943, 0.04087829297045396, -0.0028295586980501266, -0.045045889380181066, -0.04176867916404165, 0.009054703683391337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1988659731255845e-07, 5.405476933653853e-08, -6.875381856227498e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21597954225161634, 0.8402635903566044, 0.8731254488513662, 0.0, 0.25160791712664754, -0.33254465266262534, -2.152714362834844, -1.4545694974777101, -1.1263590478165488, -1.0695629641483857, -1.6362336148536138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5028129464348694, 0.3942257812705339, 2.0610123159070524, -1.453506621352885, -1.4671253456031503, -0.513893917256438, 0.24703865045483375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764313287118, -0.8173799676451967, 0.01234746753808419]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.482525740014176e-05, 6.384719757821989e-05, -0.0003273600288930092, 0.0, 0.03495476827483247, -0.05579931370880366, -0.11461041167442258, -0.00722811779903413, 0.1047727458339869, 0.08542179234200462, -0.04644150648171211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013415438494855743, -0.029598684321947788, 0.04090073539601287, -0.002833545753377569, -0.04485425850407688, -0.04180767970256149, 0.00883852978117076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0532187457689919e-07, 4.1017600071540133e-08, -6.716688985091734e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21598317526017582, 0.840266791299757, 0.8731044743544452, 0.0, 0.2532882684028876, -0.3351873334458538, -2.15817977789227, -1.4549148855488858, -1.121353325258512, -1.0655057851441387, -1.6384753379862809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5021472193327972, 0.39276376854788075, 2.0630346788683083, -1.4536470029108424, -1.4693322243894469, -0.5159619122087167, 0.24746442436466015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764358902698, -0.8173799661363714, 0.012344148214609399]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.266017118958212e-05, 6.40188630539151e-05, -0.0004194899384202893, 0.0, 0.03360702552480073, -0.052853615664568754, -0.10930830114851764, -0.006907761423514851, 0.100114451160739, 0.08114358008494028, -0.04483446265334185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013314542041443191, -0.029240254453062893, 0.04044725922511563, -0.0028076311591443705, -0.04413757572593312, -0.041359899045575244, 0.008515478196527903, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.123115983403507e-08, 3.017650623789691e-08, -6.638646949578774e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21598672739051494, 0.840269992250373, 0.8730872023137283, 0.0, 0.2549104285903367, -0.33773279880183693, -2.1634168216463885, -1.4552461348917507, -1.1165481192412319, -1.061632874142527, -1.640647868333564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.50149207536764, 0.39133158096996906, 2.065017865470375, -1.4537850042771912, -1.4714855030519272, -0.5179906055149067, 0.24787081674601294, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.57667643981954, -0.8173799650703748, 0.012340838212088787]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.104260678254591e-05, 6.401901232016424e-05, -0.0003454408143366345, 0.0, 0.032443203748981714, -0.050909307119663155, -0.10474087508237638, -0.006624986857296179, 0.09610412034560263, 0.07745822003223508, -0.043450606945661906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013102879303143262, -0.028643751558233316, 0.03966373204133352, -0.0027600273269765625, -0.04306557324960674, -0.040573866123799825, 0.008127847627055679, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.858540390420901e-08, 2.1319932463373096e-08, -6.620005041224869e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21599023750996257, 0.8402731894558457, 0.8730550050672039, 0.0, 0.25648402088746197, -0.3402172483121448, -2.1684623994059233, -1.4555654926454147, -1.1119107872998688, -1.0579149537936885, -1.6427629300091413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5008504454907556, 0.38993525113043764, 2.066953463348415, -1.4539200289192935, -1.4735766204438343, -0.5199713373859122, 0.24825671024947876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764430115545, -0.8173799644444931, 0.012337521447530603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.020238895242379e-05, 6.394410945302479e-05, -0.0006439449304864127, 0.0, 0.031471845942505836, -0.049688990206156504, -0.10091155519069359, -0.006387155073278527, 0.09274663882726263, 0.07435840697677065, -0.04230123351154607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012832597537688306, -0.027926596790627947, 0.038711957560798545, -0.0027004928420482754, -0.04182234783814261, -0.03961463742010866, 0.0077178700693162836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.384028693777528e-08, 1.251763399971688e-08, -6.633529116367521e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21599436792287738, 0.840276380359421, 0.8730420980213279, 0.0, 0.2578895391027214, -0.3416664841205167, -2.172936067042996, -1.455848573189898, -1.1077918943715033, -1.054629909932421, -1.6446588832971125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5002227502550505, 0.3885757264048003, 2.068840631793639, -1.4540515275883104, -1.475604748825344, -0.5219032557865871, 0.24862234358366195, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764458231401, -0.8173799640801734, 0.012334193106299114]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.260825829634245e-05, 6.381807150572551e-05, -0.0002581409175194594, 0.0, 0.02811036430518823, -0.02898471616743855, -0.08947335274145043, -0.00566161088966712, 0.08237785856731027, 0.06570087722535108, -0.0379190657594234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0125539047141031, -0.02719049451274664, 0.03774336890447918, -0.0026299733803356296, -0.040562567630195535, -0.03863836801349951, 0.007312666683663661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.6231710857984e-08, 7.286394442834348e-09, -6.656682462979252e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21599866063315842, 0.8402795636406772, 0.8730938620570995, 0.0, 0.259097553415057, -0.3426145669272039, -2.1767513369243243, -1.456088966496512, -1.1042726720320097, -1.0518381684604678, -1.6462948852691983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4996083217108915, 0.38725115420539963, 2.0706819070538702, -1.4541795547559513, -1.4775734148598763, -0.5237888976132876, 0.24896909044128693, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764478667123, -0.8173799640733977, 0.01233085444364129]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.585420562091473e-05, 6.366562512438438e-05, 0.001035280715432305, 0.0, 0.024160286246712848, -0.01896165613374361, -0.07630539762657003, -0.004807866132278067, 0.07038444678987046, 0.05583482943906325, -0.03272003944171398, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01228857088317776, -0.026491443988014115, 0.036825505204626394, -0.002560543352818697, -0.03937332069064297, -0.03771283653400949, 0.006934937152499552, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.087144508140631e-08, 1.355139631199785e-10, -6.677325315645922e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21600307339291597, 0.840282734001734, 0.8731659135291623, 0.0, 0.26011534975836104, -0.34341307283754824, -2.1799411942776503, -1.4562881774004632, -1.101325095723957, -1.0495119630429142, -1.6476789159860632, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.499005411520749, 0.3859572817526361, 2.072483020804953, -1.4543044935007026, -1.4794897108490765, -0.5256340583182608, 0.249298999931896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764492357568, -0.8173799643597911, 0.012327514131730749]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.825519515100636e-05, 6.3407221136733e-05, 0.0014410294412551528, 0.0, 0.02035592686608015, -0.015970118206887558, -0.06379714706651891, -0.0039842180790242675, 0.05895152616105247, 0.04652410835107346, -0.027680614337299514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012058203802852795, -0.025877449055270896, 0.0360222750216538, -0.002498774895027, -0.03832591978400594, -0.03690321409946335, 0.006598189812181653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.738088705416519e-08, -5.727866627791286e-09, -6.680623821083274e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21600760338122116, 0.8402858825873146, 0.8732385858225742, 0.0, 0.2609701602257557, -0.3441911960270135, -2.1826016870499947, -1.4564524741393363, -1.0988631688833257, -1.04757764847458, -1.6488454918094053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.498411550258241, 0.38468835538758583, 2.0742517559829716, -1.4544269147593014, -1.4813628551412743, -0.5274466383675188, 0.24961440522961895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676450246775, -0.8173799647898277, 0.012324185414873703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.059976610381864e-05, 6.297171161136526e-05, 0.0014534458682382834, 0.0, 0.017096209347893337, -0.015562463789304428, -0.05320985544688826, -0.0032859347774625114, 0.049238536812628096, 0.03868629136668215, -0.023331516466843925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011877225250161955, -0.025378527301005448, 0.035374703560374206, -0.0024484251719773874, -0.037462885843955684, -0.03625160098516035, 0.006308105954459039, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0220363943462078e-08, -8.60073087623746e-09, -6.657433714093033e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160122445337358, 0.8402889989928035, 0.8733009456660552, 0.0, 0.2616977288434556, -0.34498275287142993, -2.1848537555118566, -1.456590172296587, -1.0967774997819122, -1.0459441837108503, -1.6498408388495722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4978240479556264, 0.38343825185320335, 2.0759964275033207, -1.4545474428541498, -1.4832024623658167, -0.5292350955943539, 0.2499175531111112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676451176323, -0.8173799652363248, 0.012320882836493928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.282305029296259e-05, 6.232810977676406e-05, 0.00124719686962106, 0.0, 0.01455137235399849, -0.015831136888329354, -0.045041369237240614, -0.0027539631450126017, 0.041713382028270976, 0.032669295274594445, -0.01990694080333951, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011750046052288134, -0.025002070687649536, 0.034893430406978954, -0.002410561896967367, -0.03679214449084485, -0.03576914453670107, 0.006062957629844768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8590958226394474e-08, -8.929943478964784e-09, -6.605156759550462e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21601699218016002, 0.8402920735607735, 0.8733489383788298, 0.0, 0.2623339291974208, -0.34579319365451033, -2.186816046239905, -1.4567095075502066, -1.094960083260173, -1.044523151000005, -1.650711965459393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.497240461511184, 0.38220149284385857, 2.077724497583437, -1.4546666432961515, -1.4850170323032812, -0.5310070292665925, 0.25021032616603434, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676452201198, -0.8173799656177889, 0.01231761942606625]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.495292848439846e-05, 6.149135939904885e-05, 0.0009598542554910823, 0.0, 0.012724007079304326, -0.016208815661607735, -0.039245814560968637, -0.0023867050723895295, 0.03634833043478584, 0.028420654216906416, -0.017422532196413994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011671728888848383, -0.024735180186895512, 0.03456140160232337, -0.0023840088400339326, -0.036291398749291756, -0.03543867344477241, 0.005855461098463357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0497502775466458e-08, -7.629282107061982e-09, -6.526820855354412e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21602183941226855, 0.8402950991718837, 0.873382124216459, 0.0, 0.2629099031404904, -0.346621715289843, -2.1885897644570163, -1.456817440087771, -1.093318276094908, -1.0432397089362135, -1.6515001744638835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.496658951463837, 0.38097398870123533, 2.0794415447589887, -1.4547849452465569, -1.4868128741748357, -0.5327681219783683, 0.2504940820448552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764534156281, -0.8173799658912186, 0.012314404807096944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.694464217079713e-05, 6.051222220448142e-05, 0.0006637167525854425, 0.0, 0.01151947886139131, -0.01657043270665271, -0.03547436434222365, -0.0021586507512861273, 0.03283614330529753, 0.025668841275832008, -0.015764180089812084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01163020094693851, -0.024550082852464464, 0.03434094351103029, -0.0023660390081064295, -0.035916837431089366, -0.03522185423551743, 0.005675117576417374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4288600571100832e-08, -5.468593945376315e-09, -6.429237938610368e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21602677451575514, 0.8402980721587655, 0.8734029313021023, 0.0, 0.26345012878626733, -0.3474663496811826, -2.1902531890173953, -1.4569192424176018, -1.091780016976992, -1.0420363776868344, -1.6522383330187072, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4960784811732752, 0.37975342663267037, 2.081150713265234, -1.4549026027541647, -1.4885935768130218, -0.5345215712854419, 0.25076961092939415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676454860548, -0.8173799660385457, 0.012311244373383835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.870206973198153e-05, 5.9459737636686745e-05, 0.0004161417128669426, 0.0, 0.010804512915538847, -0.016892687826792274, -0.03326849120758313, -0.0020360465966165094, 0.030765182358321614, 0.024066624987581543, -0.01476317109647452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011609405811235193, -0.02441124137129899, 0.034183370124907304, -0.0023531501521568896, -0.0356140527637217, -0.035068986141470186, 0.005510577690779668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8898400057527212e-08, -2.9465414857049456e-09, -6.320867426219298e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21603178234914075, 0.8403009923225342, 0.8734150935761278, 0.0, 0.2639723650067338, -0.34832476728485945, -2.191862173258034, -1.4570185622514165, -1.090293565209582, -1.0408724463435228, -1.6529506093452302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4954988408677532, 0.37853928166827056, 2.0828526826187206, -1.455019693178047, -1.490360041910831, -0.5362680539157356, 0.25103719587470413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764565446336, -0.81737996605679, 0.012308139423165202]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010015666771249617, 5.840327537439549e-05, 0.00024324548050988937, 0.0, 0.010444724409329486, -0.017168352073536272, -0.03217968481277232, -0.0019863966762911625, 0.029729035348200178, 0.023278626866232197, -0.014245526530462198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01159280611044039, -0.024282899287996162, 0.034039387069728345, -0.002341808477644138, -0.03532930195618059, -0.03492965260587574, 0.005351698906199745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.3681711148251684e-08, -3.648867031866524e-10, -6.209900437266995e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21603684772938933, 0.8403038622652894, 0.8734221584040455, 0.0, 0.2644885620347491, -0.3491945748809529, -2.1934535836974383, -1.4571177040232528, -1.0888245052572514, -1.0397212770954807, -1.6536535267366221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4949205193629742, 0.37733251037935706, 2.0845460804273266, -1.4551361454075298, -1.4921109794083756, -0.5380061450473197, 0.25129674433100896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764584575443, -0.8173799659518832, 0.012305087974689108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010130760497157876, 5.7398855103869964e-05, 0.00014129655835455363, 0.0, 0.010323940560304902, -0.017396151921869198, -0.031828208788085774, -0.001982835436724865, 0.029381199046611402, 0.023023384960844166, -0.014058347827838082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011566430095577701, -0.024135425778270072, 0.033867956172122377, -0.002329044589656098, -0.035018749950894525, -0.03476182263168082, 0.005190969126096845, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.825821562923392e-08, 2.098134770857365e-09, -6.10289695218573e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160419586015939, 0.840306686355978, 0.8734267264056708, 0.0, 0.2650061321049504, -0.3500736969376522, -2.1950497117297227, -1.4572179702760037, -1.087351806346736, -1.0385669539726834, -1.6543575483327677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4943444800744854, 0.3761350536637586, 2.0862281655538006, -1.455251785885099, -1.493843671021013, -0.5397330161048502, 0.25154794950320897, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764605788461, -0.8173799657345175, 0.012302085924466721]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010221744409101825, 5.648181377198899e-05, 9.136003250619738e-05, 0.0, 0.010351401404025936, -0.01758244113398611, -0.031922560645693265, -0.0020053250550186794, 0.029453978210307263, 0.023086462455943566, -0.014080431922910334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01152078576977829, -0.023949134311968937, 0.03364170252947782, -0.002312809551386046, -0.0346538322527477, -0.03453742115061156, 0.005024103444000692, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.2426037001831756e-08, 4.3473135950859515e-09, -6.004100444774419e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21604736366008312, 0.8403094697460571, 0.8734350252157219, 0.0, 0.2654753272598436, -0.35007369685073425, -2.1964948965858353, -1.457309016342181, -1.0860195784645676, -1.0375220401963547, -1.6549949366573575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4937718592315767, 0.3749493820320416, 2.0878956883176696, -1.4553662179367854, -1.4955546182532826, -0.5414453428277196, 0.2517902931139017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764629579977, -0.8173799653843985, 0.012299128130303778]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010810116978461577, 5.5667801582025265e-05, 0.00016597620102219325, 0.0, 0.009383903097863886, 1.7383589394348586e-09, -0.028903697122247954, -0.0018209213235435564, 0.026644557643368046, 0.02089827552657359, -0.012747766491794214, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011452416858172186, -0.023713432634340594, 0.03335045527738269, -0.00228864103372838, -0.03421894464539412, -0.03424653445738627, 0.004846872213854495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.7583032652669756e-08, 7.0023801632327565e-09, -5.9155883258873476e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21605292192902004, 0.8403122195777611, 0.8734372103487635, 0.0, 0.2658630306423856, -0.35007369672056887, -2.197685934968483, -1.4573835881858568, -1.0849233377592336, -1.0366609872689547, -1.6555207844135031, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4932043641828499, 0.37377899526364156, 2.089543808521132, -1.4554790311330794, -1.4972389020885069, -0.5431381496677691, 0.25202317501417015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764642094635, -0.8173799654700676, 0.012296207289021099]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011116537873814752, 5.499663408062551e-05, 4.3702660832242995e-05, 0.0, 0.007754067650840075, 2.6033077414944466e-09, -0.02382076765295628, -0.0014914368735165844, 0.021924814106682906, 0.017221058548000885, -0.010516955122914125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011349900974535804, -0.023407735368000934, 0.0329624040692496, -0.0022562639258814454, -0.033685676704486515, -0.033856136800989305, 0.004657638005368282, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.502931740470178e-08, -1.713383830696593e-09, -5.841682565358139e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160585391291496, 0.8403149430445964, 0.8734345432742399, 0.0, 0.2661605267060515, -0.35007369661005544, -2.198596159025725, -1.4574397145003435, -1.0840878379201462, -1.036002827391036, -1.6559232247874403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4926437342621508, 0.37262730562338797, 2.091167678978915, -1.4555899048065803, -1.4988918082590552, -0.5448064351101257, 0.25224615709221154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764647153144, -0.8173799658462997, 0.012293315814647952]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011234400259109423, 5.446933670645957e-05, -5.3341490474560505e-05, 0.0, 0.005949921273318584, 2.2102689838432975e-09, -0.018204481144838934, -0.0011225262897345686, 0.01670999678174615, 0.013163197558374204, -0.00804880747874222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011212598413980085, -0.023033792805071538, 0.03247740915565266, -0.0022174734700178556, -0.0330581234109665, -0.03336570884713363, 0.0044596415608277335, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0117018351183196e-08, -7.524640491033929e-09, -5.782948746291969e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21606419019354017, 0.8403176449292039, 0.8734305242789671, 0.0, 0.2663754610526783, -0.3500736964995256, -2.1992499859923624, -1.4574789960140326, -1.0834905673230133, -1.0355296836080907, -1.656212565479602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4920912140342255, 0.3714966324890408, 2.0927639272914322, -1.4556986487309893, -1.500510253731467, -0.546446704393496, 0.2524591119138862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764647329032, -0.8173799664131799, 0.012290448418470734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011302128781127323, 5.403769214999374e-05, -8.037990545659056e-05, 0.0, 0.004298686932535316, 2.210597086556155e-09, -0.013076539332748138, -0.0007856302737820273, 0.011945411942659356, 0.009462875658903318, -0.005786813843234277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011050404558505105, -0.02261346268694326, 0.03192496625035007, -0.0021748784881772867, -0.03236890944823384, -0.032805385667405255, 0.004259096433493393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.517768428796712e-10, -1.1337603859675264e-08, -5.7347923544341295e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21606987954738943, 0.840320326936797, 0.8734276448856592, 0.0, 0.26652304696815105, -0.3500736963881574, -2.1996952462877326, -1.4575046552230122, -1.0830872961176365, -1.0352068357052098, -1.6564094350764715, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.491547393758524, 0.37038793125407254, 2.094331087745453, -1.4558051986136993, -1.5020931481849071, -0.5480574201944037, 0.2526622241944754, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764644351838, -0.8173799671016769, 0.012287602890487727]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011378707698513687, 5.364015186245173e-05, -5.7587866157467624e-05, 0.0, 0.002951718309455116, 2.227364387914466e-09, -0.008905205907407678, -0.0005131841795898658, 0.008065424107534932, 0.006456958057618456, -0.003937391937389303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010876405514030218, -0.02217402469936531, 0.031343209080416025, -0.0021309976541977766, -0.03165788906880445, -0.03221431601815558, 0.004062245611784706, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.954388377393999e-09, -1.3769940527717209e-08, -5.691055966015633e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21607561986259652, 0.8403229860092861, 0.8733679421681183, 0.0, 0.2666200465748417, -0.3500736963881574, -2.19998434780142, -1.4575202111349723, -1.0828294873825681, -1.0349963471155126, -1.656536646165338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4910123094358776, 0.36930103850648877, 2.095869280650176, -1.455909580758646, -1.5036410138327807, -0.5496386773336333, 0.25285589996621527, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764638727941, -0.8173799679481956, 0.012284781881987866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011480630414200897, 5.318144978099488e-05, -0.0011940543508174048, 0.0, 0.0019399921338127543, 1.3740920187555718e-16, -0.005782030273746158, -0.0003111182392027648, 0.005156174701367167, 0.004209771793941766, -0.002544221777326584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01070168645292897, -0.021737854951675163, 0.030763858094457613, -0.0020876428989337814, -0.03095731295746958, -0.03162514278459109, 0.0038735154347971103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1247793010478697e-08, -1.693037198530423e-08, -5.6420169997199354e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21608142335284938, 0.8403256344410629, 0.8732730221958629, 0.0, 0.26668154295241614, -0.3500736963839558, -2.2001642036429567, -1.4575287768314653, -1.082673630413205, -1.0348643288531616, -1.6566147878075357, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904856796610584, 0.36823511751602084, 2.097379596913235, -1.4560118803635589, -1.505155329693353, -0.5511915691808458, 0.2530406616816926, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764631558823, -0.8173799689462681, 0.012281972752968212]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001160698050575208, 5.296863553630828e-05, -0.001898399445107342, 0.0, 0.00122992755148914, 8.403191703895965e-11, -0.003597116830740637, -0.00017131392985822455, 0.003117139387265121, 0.002640365247018794, -0.0015628328439553064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010532595496385036, -0.021318419809358707, 0.030206325261178685, -0.0020459920982595424, -0.030286317211445653, -0.03105783694424939, 0.0036952343095461187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4338236692685037e-08, -1.9961450377687756e-08, -5.61825803930674e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160872984051237, 0.8403282667797484, 0.8731716360417939, 0.0, 0.2667196087252823, -0.35007369638384267, -2.200272256939825, -1.457532813973132, -1.0825849499114293, -1.0347837776716564, -1.6566604070221342, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.489967071199596, 0.3671890961826113, 2.098863473495817, -1.4561121874368386, -1.5066378879622007, -0.5527175506241686, 0.25321703907196536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764623632663, -0.8173799700592117, 0.012279180781709515]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011750104548601343, 5.264677370890524e-05, -0.00202772308137857, 0.0, 0.0007613154573232015, 2.2631267980748753e-12, -0.0021610659373615844, -8.074283333510929e-05, 0.0017736100355154186, 0.001611023630101886, -0.0009123842919704596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010372169229245363, -0.020920426668190953, 0.029677531651635544, -0.0020061414655956227, -0.029651165376951227, -0.0305196288664566, 0.0035275478054554174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5852319991075795e-08, -2.2258872788251025e-08, -5.58394251739441e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160932488153187, 0.8403308779965991, 0.8730823279819212, 0.0, 0.26674316270941384, -0.3500736963837715, -2.2003360671756718, -1.457534110427853, -1.0825378116015334, -1.0347348518687667, -1.6566857729405895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4894560877464096, 0.3661619989805257, 2.100322223965943, -1.4562105786354598, -1.5080903185381425, -0.5542179526663771, 0.2533855112554236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764615091486, -0.8173799712608908, 0.012276410891470036]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011900820389981708, 5.2224337015493136e-05, -0.0017861611974546309, 0.0, 0.00047107968263136035, 1.4238312115015279e-12, -0.0012762047169337133, -2.592909441932608e-05, 0.0009427661979174479, 0.0009785160577929358, -0.000507318369107171, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01021966906372807, -0.020541944041711672, 0.029175009402523246, -0.0019678239724255247, -0.029048611518836497, -0.03000804084416983, 0.003369443669164644, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7082353003507865e-08, -2.403358238480162e-08, -5.5397804789577385e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160992744817701, 0.8403334710729071, 0.8730135427216953, 0.0, 0.2667583740551514, -0.35007369638305663, -2.200374606950838, -1.4575338759986292, -1.0825145378411614, -1.0347039171936627, -1.6566994005773483, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4889524788008033, 0.36515314127144377, 2.1017567603936245, -1.4563071059086743, -1.5095138151665513, -0.5556936947745841, 0.25354647872089425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676460591319, -0.8173799725376257, 0.012273660069897706]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012051332902810702, 5.186152616093572e-05, -0.0013757052045178986, 0.0, 0.0003042269147510323, 1.4297265423870196e-11, -0.0007707955033258808, 4.688584476185251e-06, 0.0004654752074402101, 0.0006186935020791216, -0.00027255273517869203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010072178912127017, -0.02017715418163816, 0.028690728553633325, -0.0019305454642888316, -0.028469932568178005, -0.029514842164140225, 0.003219349309413864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.83565906542714e-08, -2.55346982010287e-08, -5.50164314466208e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21610537275161257, 0.8403360414840053, 0.8729653807567382, 0.0, 0.2667692445900187, -0.3500736963830547, -2.200400149442479, -1.4575328834282077, -1.082503670595127, -1.0346821701829645, -1.6567068414454744, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4884561543744583, 0.36416219559303303, 2.103167492401232, -1.456401784295093, -1.5109090443863868, -0.5571451824134597, 0.25370025404692825, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764596045464, -0.8173799738694202, 0.012270932877414415]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012196539684909367, 5.140822196302737e-05, -0.0009632392991409771, 0.0, 0.0002174106973457762, 3.8481185504686814e-14, -0.0005108498328159295, 1.9851408427501e-05, 0.00021734492068962004, 0.00043494021396335786, -0.0001488173625199674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009926488526898777, -0.019818913568214285, 0.028214640152143106, -0.0018935677283730557, -0.027904584396713096, -0.029029752777511048, 0.003075506520680302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9735451383059122e-08, -2.663588809662533e-08, -5.454384966581851e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161115398824826, 0.8403385948671653, 0.8729354664981931, 0.0, 0.2667782160040623, -0.3500736963830379, -2.200420124653131, -1.4575315875967711, -1.0824982538972692, -1.0346642957922623, -1.6567114951409836, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.487967199521145, 0.3631891652669818, 2.1045543647128153, -1.4564946035604835, -1.5122761919239986, -0.558572342725361, 0.2538470818587765, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676458560669, -0.8173799752472309, 0.012268223727074347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012334261740060763, 5.1067663199555634e-05, -0.0005982851709022802, 0.0, 0.00017942828087215402, 3.3576584864001144e-13, -0.0003995042130417084, 2.5916628733989853e-05, 0.00010833395715823283, 0.0003574878140449331, -9.307391018313635e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009779097066266451, -0.019460606521024448, 0.02773744623166859, -0.0018563853078117402, -0.02734295075223607, -0.028543206238027335, 0.0029365562369657295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.087755072302794e-08, -2.7556214804878894e-08, -5.418300680138068e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161177721217722, 0.8403411147161127, 0.87300668532155, 0.0, 0.266786643105313, -0.3500736962672246, -2.2004386800516786, -1.4575302451935308, -1.082494391749819, -1.0346473337344415, -1.656715274423275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4874857925305522, 0.36223430432296766, 2.1059169628096237, -1.4565855198617146, -1.51361507803542, -0.5599747369700196, 0.25398714890692364, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764575225438, -0.8173799765569176, 0.012265549234641975]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012464478579181433, 5.0396978948691604e-05, 0.0014243764671384288, 0.0, 0.0001685420250142293, 2.3162664219299105e-09, -0.00037110797094756396, 2.6848064808373916e-05, 7.724294899994321e-05, 0.0003392411564153651, -7.558564582898887e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00962813981185661, -0.019097218880283144, 0.027251961936164328, -0.0018183260246187492, -0.026777722228427503, -0.02804788489317157, 0.002801340962942834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.07625021711229e-08, -2.619373337895835e-08, -5.348984864744271e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161240663306556, 0.8403435967075659, 0.8731151839702143, 0.0, 0.26679521246506904, -0.3500736961816764, -2.2004578857608204, -1.4575289771546878, -1.082490126054409, -1.0346298154557136, -1.6567191572574416, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4870122050283865, 0.3612980198120377, 2.107254656452844, -1.4566744806635217, -1.5149253040899513, -0.5613517035106609, 0.2541206174655808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764564881472, -0.8173799777697793, 0.012262913826162802]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012588417766816042, 4.9639829063040445e-05, 0.00216997297328444, 0.0, 0.00017138719512064935, 1.7109641898255132e-09, -0.00038411418283296406, 2.536077686195136e-05, 8.531390820205297e-05, 0.00035036557455550696, -7.765668333469897e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009471750043313494, -0.01872569021859945, 0.026753872864405007, -0.0017792160361434699, -0.026204521090626456, -0.027539330812824794, 0.0026693711731425544, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.068793141869637e-08, -2.425723414656588e-08, -5.2708169583458215e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21613042019406994, 0.8403460416365942, 0.8732222651870635, 0.0, 0.26680421038560276, -0.3500736960877822, -2.200478580055263, -1.4575278267816014, -1.0824846516157092, -1.034611154154967, -1.656723559685289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4865467489198454, 0.3603807831248214, 2.1085667238490178, -1.4567614294729023, -1.5162063796774385, -0.562702486289889, 0.2542476407855931, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676455472514, -0.8173799788921401, 0.012260316885405777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012707726828716987, 4.8898580566280263e-05, 0.0021416243369831948, 0.0, 0.00017995841067440914, 1.877882879468442e-09, -0.00041388588885431585, 2.300746172472331e-05, 0.00010948877399771765, 0.000373226014934676, -8.804855694920412e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009309122170823981, -0.018344733744325242, 0.026241347923480242, -0.0017389761876118572, -0.025621511749744134, -0.02701565558456237, 0.0025404664002458047, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0312668165193254e-08, -2.2447216054389142e-08, -5.19388151404874e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21613683212671525, 0.8403484522277817, 0.8733131758198035, 0.0, 0.26681370326321546, -0.3500736959798418, -2.200500931710084, -1.4575267967998164, -1.0824777927862785, -1.0345912402469393, -1.6567285871452153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4860897388111172, 0.3594830631130394, 2.109852445919921, -1.4568463104930374, -1.5174578177651659, -0.5640263321947248, 0.25436837412553875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764544863876, -0.8173799799298933, 0.012257755898045612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012823865290587848, 4.821182374856682e-05, 0.0018182126547999684, 0.0, 0.00018985755225454256, 2.1588084305256643e-09, -0.00044703309642565934, 2.059963570073196e-05, 0.0001371765886106432, 0.00039827816055351684, -0.0001005491985291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009140202174562803, -0.017954400235639958, 0.025714441418061982, -0.001697620402700065, -0.02502876175454811, -0.026476918096716543, 0.002414666798913787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9722524922311807e-08, -2.075506356644679e-08, -5.1219747203297085e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.216143301041937, 0.8403508315962265, 0.8733821669122404, 0.0, 0.26682365098477906, -0.3500736958681432, -2.2005247904278065, -1.4575258717632138, -1.0824696764247497, -1.0345701899685655, -1.656734192899307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4856414687417157, 0.3586052840452168, 2.111111165789696, -1.4569290719229164, -1.518679193611367, -0.5653225524631456, 0.2544829806265226, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676453533335, -0.817379980892355, 0.01225522792711685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012937830443493078, 4.758736889649628e-05, 0.0013798218487375887, 0.0, 0.00019895443127199703, 2.2339714096155932e-09, -0.00047717435444466705, 1.8500732051897947e-05, 0.00016232723057524334, 0.00042100556747254043, -0.0001121150818314749, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00896540138803077, -0.01755558135645253, 0.025174397395500734, -0.0016552285975822614, -0.024427516924023472, -0.025924405368415324, 0.0022921300196770415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.906105230508192e-08, -1.9249234083103773e-08, -5.055941857524238e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21614982609436315, 0.8403531826270276, 0.8734290968079154, 0.0, 0.2668339731906955, -0.35007369575742936, -2.200549889718512, -1.4575250306311687, -1.0824605418055477, -1.0345482003307207, -1.6567402710533996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4852022007369134, 0.3577478051690608, 2.112342317837651, -1.4570096678581739, -1.519870172660985, -0.5665905526764778, 0.2545916332258039, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764526111552, -0.8173799817915721, 0.01225273019260172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013050104852282063, 4.7020616023293886e-05, 0.0009385979135000912, 0.0, 0.0002064441183293038, 2.214276373170689e-09, -0.0005019858141032637, 1.6822640904431993e-05, 0.00018269238403940255, 0.00043979275689449824, -0.0001215630818523779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008785360096044234, -0.01714957752311979, 0.024623040959094827, -0.0016119187051502424, -0.02381958099235605, -0.0253600042666449, 0.0021730519856269924, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.844359996236487e-08, -1.7984343722966888e-08, -4.995469030263457e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161564064609126, 0.8403555080192385, 0.8734003342907144, 0.0, 0.2668445849729883, -0.3500736957574293, -2.20057595392447, -1.457524252648341, -1.0824506395942282, -1.034525473171712, -1.6567467069203503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4847721617741512, 0.35691091563412036, 2.1135454349434464, -1.4570880588095008, -1.521030516191996, -0.5678298402732155, 0.2546945135113357, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764516686325, -0.8173799827283615, 0.012250260017818928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001316073309890999, 4.650784421713062e-05, -0.0005752503440191705, 0.0, 0.0002122356458555713, 1.3690306767768303e-15, -0.0005212841191629424, 1.5559656555270642e-05, 0.00019804422639098406, 0.0004545431801758431, -0.00012871733901407984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008600779255243768, -0.016737790698808347, 0.02406234211591552, -0.001567819026538241, -0.02320687062022235, -0.0247857519347533, 0.002057605710636302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.885045275272986e-08, -1.8735789247150882e-08, -4.9403495655821767e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21616304119064805, 0.8403578283195685, 0.8733227568791339, 0.0, 0.2668554293591316, -0.35007369575741104, -2.200602749705545, -1.4575235126061468, -1.0824401810461983, -1.0345021816681899, -1.6567534113964146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4843515704192272, 0.35609483877750825, 2.114720146021429, -1.4571642211122313, -1.522160077292626, -0.5690400196976713, 0.25479181707577636, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676450685136, -0.8173799837517991, 0.01224779675959477]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001326945947090395, 4.6406006600486334e-05, -0.0015515482316112467, 0.0, 0.0002168877228661647, 3.6541982649156954e-13, -0.0005359156215044303, 1.480084388386999e-05, 0.0002091709605956422, 0.000465830070440897, -0.00013408952128761707, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008411827098478748, -0.016321537132242107, 0.02349422155965223, -0.001523246054610437, -0.0225912220126032, -0.0242035884891148, 0.0019460712888126129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9669929697172616e-08, -2.046875192842132e-08, -4.9265164483132386e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21616972912605098, 0.8403601492680635, 0.873229801266869, 0.0, 0.266866452197949, -0.3500736957574084, -2.200630093232158, -1.4575227958606989, -1.0824293338024435, -1.0344784601684094, -1.6567603076729496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4839405956308274, 0.3552997404461769, 2.115866158405844, -1.4572381302344386, -1.5232587837281744, -0.5702207784178267, 0.25488373890977234, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764496600785, -0.8173799848663036, 0.01224533447354385]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013375870805833594, 4.6418969898814205e-05, -0.0018591122452974952, 0.0, 0.00022045677634823765, 5.31379893951386e-14, -0.0005468705322568123, 1.4334908956004658e-05, 0.00021694487509719046, 0.00047442999561092406, -0.00013792553070057228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00821949576799377, -0.015901966626626605, 0.02292024768830123, -0.0014781824441463473, -0.021974128710968467, -0.02361517440310962, 0.0018384366799193092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.050114990156679e-08, -2.2290088742771706e-08, -4.9245721018401214e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21617646887615644, 0.8403624705356598, 0.8731436069591917, 0.0, 0.26687761001675064, -0.35007369575740593, -2.2006578503144967, -1.457522094012375, -1.082418220195092, -1.0344544059986402, -1.6567673370358968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4835393726743205, 0.35452573745901694, 2.11698324755933, -1.4573097644086075, -1.5243266263439894, -0.5713718752445602, 0.25497047409740303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764486001876, -0.817379986059856, 0.012242873147517808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013479500210933771, 4.642535192656507e-05, -0.0017238861535451904, 0.0, 0.000223156376032, 4.895228593199059e-14, -0.0005551416467730762, 1.4036966479234635e-05, 0.00022227214702851136, 0.0004810833953844536, -0.00014058725894544548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008024459130137407, -0.015480059743198809, 0.022341783069722447, -0.001432683483376444, -0.021356852316299062, -0.023021936534671383, 0.0017347037526135593, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1197817673621e-08, -2.3871046680891627e-08, -4.92265205208221e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161832588304669, 0.8403647897328581, 0.8730745729855597, 0.0, 0.26688887094526603, -0.35007369575740366, -2.2006859283513758, -1.457521402424759, -1.0824069239252205, -1.0344300861656974, -1.656774457983389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4831480116771665, 0.35377290458905536, 2.118071248056229, -1.457379105985687, -1.5253636491656308, -0.5724931305632868, 0.2550522172808518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764475138673, -0.8173799873162869, 0.012240414790030038]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013579908620961706, 4.6383943964709526e-05, -0.001380679472639816, 0.0, 0.00022521857030810812, 4.5071657675653094e-14, -0.0005615607375801633, 1.3831752323282063e-05, 0.00022592539742926216, 0.0004863966588580893, -0.00014241894984100192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00782721994307996, -0.015056657399231677, 0.02176000993797567, -0.0013868315415940888, -0.020740456432828906, -0.02242510637452983, 0.001634863668975554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1726405242395093e-08, -2.512862009234994e-08, -4.916714975541814e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21619009719072538, 0.8403671041898227, 0.8730250905643239, 0.0, 0.2669002129526415, -0.3500736957574016, -2.2007142661292916, -1.457520718706625, -1.0823954991673763, -1.0344055451136152, -1.6567816429052544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4827666021021577, 0.35304127943698055, 2.119130047193072, -1.457446141847574, -1.526369942350554, -0.5735844195468944, 0.25512916185360757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676446408916, -0.8173799886202406, 0.012237961747109524]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013676720516968055, 4.628913929313686e-05, -0.000989648424715688, 0.0, 0.00022684014750957055, 4.139946710372635e-14, -0.0005667555583123272, 1.3674362677109127e-05, 0.00022849515688498203, 0.0004908210416440313, -0.00014369843730866554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0076281915001742695, -0.014632503041496717, 0.0211759827368599, -0.0013407172377381585, -0.020125863698462906, -0.021825779672152452, 0.001538891455115267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2099024503823366e-08, -2.6079074597011422e-08, -4.9060858410289703e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21619698201276316, 0.8403693909794897, 0.8729937033581576, 0.0, 0.26691160204574704, -0.3500736957574017, -2.2007428194324694, -1.457520050983257, -1.082383985994446, -1.0343808116950182, -1.6567888607993935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4823951864378662, 0.3523308655288564, 2.120159577273096, -1.4575108532534877, -1.5273456350290189, -0.574645666675701, 0.2552014917610943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764452909157, -0.8173799899352797, 0.01223553678668683]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001376964407554633, 4.573579333880957e-05, -0.0006277441233252185, 0.0, 0.00022778186211056117, -2.109375869847911e-15, -0.000571066063556301, 1.3354467358528965e-05, 0.00023026345860495946, 0.0004946683719399188, -0.00014435788277919421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007428313285832488, -0.014208278162483209, 0.02059060160048203, -0.0012942281182764291, -0.01951385356929853, -0.02122494257613246, 0.0014465981497341859, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2360008127984424e-08, -2.6300781364404818e-08, -4.849920845388949e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162039112411734, 0.840371644820046, 0.8730639432463851, 0.0, 0.2669230248884602, -0.3500736956413587, -2.2007715620317914, -1.457519400912203, -1.0823724055836264, -1.0343559048021562, -1.6567960982992833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.482033812558446, 0.3516416331967307, 2.1211598214982494, -1.4575732346920631, -1.528290899025163, -0.5756768470954169, 0.2552693950481004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764442140568, -0.8173799911583811, 0.012233145213829094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001385845682049067, 4.507681112581004e-05, 0.0014047977645508538, 0.0, 0.00022845685426318402, 2.3208602049703445e-09, -0.0005748519864364498, 1.30014210797661e-05, 0.00023160821639047431, 0.0004981378572369961, -0.00014474999779595136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007227477588400755, -0.013784646642514194, 0.020004884503069906, -0.001247628771506262, -0.018905279922881726, -0.020623608394317695, 0.0013580657401221635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1537177356203278e-08, -2.4462027476862274e-08, -4.7831457154721864e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21621088274620162, 0.8403738669217018, 0.8731719220750215, 0.0, 0.2669344771029387, -0.3500736955558908, -2.2008004782633654, -1.457518767498764, -1.0823607681610354, -1.0343308370930129, -1.656803350693136, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4816825179742432, 0.35097351968943674, 2.122130811829453, -1.4576332876541562, -1.5292059463657848, -0.5766779858890796, 0.25533305846220017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764431639753, -0.8173799922699669, 0.012230786048447333]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001394301005640464, 4.444203311580015e-05, 0.0021595765727271043, 0.0, 0.00022904428957079792, 1.7093579636436574e-09, -0.0005783246314790183, 1.2668268779095853e-05, 0.00023274845181627655, 0.0005013541828671755, -0.00014504787705052577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007025891684057212, -0.013362270145879145, 0.0194198066240681, -0.0012010592418629734, -0.018300946812435753, -0.020022775873255114, 0.00127326828199477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1001632099928954e-08, -2.2231717444065545e-08, -4.718330763523187e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21621789435531624, 0.8403760606830737, 0.8732789895881766, 0.0, 0.2669459579175962, -0.3500736954617103, -2.200829557757615, -1.4575181491149616, -1.082349078524741, -1.0343056178795946, -1.6568106169147763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4813413239651585, 0.35032642899860605, 2.1230726288615225, -1.4576910188724204, -1.530091029038877, -0.5776491584022576, 0.255392665969017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764421516621, -0.8173799932819799, 0.012228456203358872]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014023218229238042, 4.38752274369505e-05, 0.002141350263103352, 0.0, 0.00022961629314954948, 1.8836104224750254e-09, -0.000581589884989702, 1.2367676045935201e-05, 0.00023379272589137473, 0.0005043842683636384, -0.00014532443280766648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0068238801816956265, -0.012941813816614195, 0.01883634064139092, -0.0011546243652827367, -0.01770165346184227, -0.019423450263559926, 0.0011921501363370915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0246261464036967e-08, -2.024025854716612e-08, -4.659690176922159e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162249438777882, 0.8403782299517353, 0.8733700545444423, 0.0, 0.2669574677974045, -0.35007369535394567, -2.200858792657123, -1.4575175440741612, -1.0823373388890591, -1.034280254820286, -1.65681789742452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4810102329044057, 0.3497002315135996, 2.1239854022820985, -1.4577464395497446, -1.530946439347075, -0.5785904909309358, 0.2554483981079432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764411833685, -0.8173799942041735, 0.012226152107815197]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001409904494393686, 4.338537323242467e-05, 0.0018212991253138855, 0.0, 0.00023019759616600742, 2.155292887558666e-09, -0.0005846979901558906, 1.2100816007284737e-05, 0.00023479271363413404, 0.0005072611861713364, -0.00014561019487512866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006621821215055329, -0.012523949700129247, 0.018255468411517695, -0.0011084135464853324, -0.01710820616396064, -0.01882665057356482, 0.0011146427785238414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9365872725089407e-08, -1.8443872677305486e-08, -4.6081910873516656e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162320291271896, 0.8403803782385246, 0.8734393085536081, 0.0, 0.266969007335507, -0.3500736952423438, -2.2008881760827816, -1.4575169508345838, -1.082325550459439, -1.0342547548833303, -1.6568251930955942, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4806892269473408, 0.34909476375051446, 2.1248693113488164, -1.457799564963331, -1.5317725100909458, -0.5795021612993159, 0.25550043149378615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764402587001, -0.8173799950486483, 0.012223870429537109]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014170498802806397, 4.296573578796341e-05, 0.001385080183315985, 0.0, 0.00023079076205000402, 2.2320375956215015e-09, -0.0005876685131789278, 1.1864791549113498e-05, 0.00023576859240333442, 0.0005099987391157542, -0.00014591342148356242, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006420119141297368, -0.012109355261702811, 0.017678181334354774, -0.0010625082717283661, -0.016521414877413484, -0.018233407367599583, 0.0010406677168597442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8493367796060592e-08, -1.688949633950092e-08, -4.5633565561748545e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21623914793946816, 0.8403825084951195, 0.8734865919518376, 0.0, 0.2669805768156612, -0.3500736951316561, -2.2009177013357832, -1.4575163680436973, -1.0823137142658152, -1.0342291248610438, -1.6568325047003878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4803782676271664, 0.3485098284134123, 2.125724584975342, -1.4578504143167754, -1.5325696144135532, -0.5803843989639473, 0.2555489385405917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764393721133, -0.8173799958296586, 0.012221608280659255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001423762455711207, 4.2605131899019826e-05, 0.0009456679645907822, 0.0, 0.00023138960308379466, 2.213753978831219e-09, -0.000590505060034151, 1.1655817727825226e-05, 0.0002367238724716782, 0.0005126004457319495, -0.0001462320958729737, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006219186403488083, -0.011698706742042785, 0.017105472530507652, -0.0010169870688852792, -0.01594208645214642, -0.017644753292629135, 0.0009701409361103273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7731737294005717e-08, -1.5620204309337705e-08, -4.5242977557076816e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624629818664987, 0.8403846234902675, 0.87345820572641, 0.0, 0.2669921766958053, -0.350073695131656, -2.2009473619765845, -1.4575157940121628, -1.082301831024972, -1.0342033714905519, -1.6568398332761973, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4800772963401478, 0.3479451947391125, 2.126551501375257, -1.4578990105250764, -1.5333381649396705, -0.5812374846215507, 0.2555940868861796, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676438477542, -0.8173799966513855, 0.012219362857769665]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014300494363416418, 4.229990296101078e-05, -0.0005677245085536367, 0.0, 0.00023199760288298798, 1.7502593771009861e-15, -0.0005932128160236012, 1.1480630689381649e-05, 0.0002376648168646385, 0.0005150674098367783, -0.00014657151618922034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006019425740369467, -0.011292673485996394, 0.01653832799830158, -0.0009719241660202519, -0.015371010522344906, -0.017061713152066168, 0.0009029669117578904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7891426172238444e-08, -1.6434537952647496e-08, -4.4908457791772356e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162534777896728, 0.84038674533035, 0.8733810052153832, 0.0, 0.26700382529524774, -0.35007369513163805, -2.2009771557001807, -1.457515218653011, -1.0822898956831388, -1.034177501740425, -1.6568471922209316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.47978626160218, 0.34740059935009787, 2.127350390646015, -1.457945390288809, -1.53407861574216, -0.5820617504741658, 0.2556360471294591, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764375523916, -0.817379997567027, 0.012217111922259024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014359206045868843, 4.243680164729112e-05, -0.0015440102205358805, 0.0, 0.00023297198884819962, 3.5825932826912425e-13, -0.0005958744719222681, 1.1507183036155236e-05, 0.00023870683666071132, 0.0005173950025368957, -0.00014717889468489166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005820694759357955, -0.010891907780293053, 0.015977785415159144, -0.0009275952746526126, -0.014809016049790643, -0.01648531705230189, 0.0008392048655897554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.850300644222019e-08, -1.831282982562898e-08, -4.501871021283191e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162606847320401, 0.8403888798966405, 0.8732884197180647, 0.0, 0.26701552577237686, -0.35007369513163705, -2.2010070761431777, -1.4575146391687135, -1.0822779087823586, -1.034151522660421, -1.656854584175534, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.479505071018492, 0.3468757480561255, 2.1281216260494693, -1.4579895862484686, -1.5347914553860935, -0.5828575754929392, 0.25567497959908075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764365931054, -0.8173799985822928, 0.012214849324556423]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014413884734586837, 4.269132581105787e-05, -0.001851709946370481, 0.0, 0.0002340095425819217, 1.9756619549716515e-14, -0.0005984088599399577, 1.1589685948041597e-05, 0.0002397380156030742, 0.0005195816000830637, -0.00014783909204763132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005623811673760179, -0.010497025879448278, 0.015424708069089408, -0.0008839191931895187, -0.014256792878668989, -0.015916500375467234, 0.0007786493924336659, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9185725484062533e-08, -2.0305317313420505e-08, -4.5251954052001013e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21626791706948167, 0.8403910264403929, 0.8732025856999391, 0.0, 0.2670272751961376, -0.3500736951316361, -2.2010371153516917, -1.457514055683218, -1.0822658731634591, -1.0341254412782956, -1.6568620074325004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4792336051969313, 0.34637031735485774, 2.1288656236519317, -1.4580316314423525, -1.5354772060140072, -0.5836253838853016, 0.255711037498538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764356035399, -0.8173799996851648, 0.012212575412196055]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001446467488316652, 4.2930875048586925e-05, -0.0017166803625115505, 0.0, 0.00023498847521463188, 1.9407020630381917e-14, -0.0006007841702768923, 1.1669709910676003e-05, 0.00024071237798940046, 0.0005216276425056137, -0.00014846513933088523, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005429316431215983, -0.010108614025354337, 0.014879952049248229, -0.0008409038776750767, -0.013715012558274406, -0.015356167847249351, 0.000721157989145798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.979131161807006e-08, -2.2057441335881603e-08, -4.547824720736257e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21627517293827012, 0.8403931819642296, 0.8731339003273904, 0.0, 0.26703906859207655, -0.35007369513163517, -2.2010672649269503, -1.4575134693062741, -1.082253792468632, -1.0340992645137317, -1.6568694587982957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4789717245536087, 0.3458839563219697, 2.1295828404646935, -1.4580715611442439, -1.536136421338358, -0.5843656426499702, 0.2557443682226654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764345897009, -0.8173800008589348, 0.012210292758946093]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001451173757688937, 4.311047673543585e-05, -0.00137370745097668, 0.0, 0.00023586791877814578, 1.9057346083647097e-14, -0.000602991505171559, 1.172753887649855e-05, 0.00024161389654428348, 0.0005235352912777671, -0.00014902731590383473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005237612866450472, -0.009727220657760192, 0.0143443362552325, -0.0007985940378272056, -0.01318430648701565, -0.014805175293370889, 0.0006666144825478505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0276780086862394e-08, -2.347539834483577e-08, -4.5653064999251605e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21628245055890186, 0.8403953431658724, 0.8730847506870821, 0.0, 0.26705090069583065, -0.3500736951316342, -2.2010975165579345, -1.457512881304607, -1.0822416704686255, -1.0340729991094988, -1.6568769348381993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787192729774674, 0.34541628883814224, 2.1302737716550015, -1.458109413491254, -1.5367696839300513, -0.585078858464341, 0.25577511385138846, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764335575272, -0.8173800020875331, 0.012208004322530197]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014555241263466016, 4.322403285537107e-05, -0.000982992806165355, 0.0, 0.0002366420750825096, 1.8740026088367873e-14, -0.0006050326196848695, 1.1760033341855523e-05, 0.0002424400001269322, 0.0005253080846581279, -0.00014952079807030265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005049031522827549, -0.009353349676550046, 0.013818623806160665, -0.0007570469402051678, -0.012665251833866633, -0.014264316287417996, 0.0006149125744618328, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0643474121042637e-08, -2.4571967333877018e-08, -4.576872831792319e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21628974824240818, 0.8403974851172156, 0.8730537359592998, 0.0, 0.2670627459793237, -0.35007369513163433, -2.2011278569930184, -1.4575123026406043, -1.0822295180120352, -1.0340466515747007, -1.6568844178807645, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4784760498970229, 0.3449669164495067, 2.130938942786761, -1.4581452186198713, -1.5373775989389353, -0.5857655721844568, 0.2558034033557801, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764325119191, -0.8173800033313313, 0.012205734856029759]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001459536701264983, 4.283902686405334e-05, -0.0006202945556472497, 0.0, 0.00023690566986189158, -2.1713538163758635e-15, -0.000606808701674635, 1.1573280055271419e-05, 0.00024304913180895433, 0.0005269506959623978, -0.00014966085130392045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00486446160889306, -0.008987447772710738, 0.013303422635191447, -0.0007161025723463827, -0.012158300177678539, -0.013734274402315415, 0.00056579008783314, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0912162646873643e-08, -2.4875963631527022e-08, -4.538933000875017e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21629706438777901, 0.8403996018545109, 0.8731243073650127, 0.0, 0.2670745962583698, -0.3500736950157164, -2.2011582773873655, -1.457511736289721, -1.082217340158305, -1.0340202282584823, -1.6568919022261788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4782418671294015, 0.3445354203706928, 2.131578914157867, -1.4581790186976036, -1.5379607967230233, -0.5864263584889567, 0.2558293675355805, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764315005874, -0.8173800044857833, 0.012203490378713046]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014632290741666408, 4.233474590688757e-05, 0.0014114281142568934, 0.0, 0.00023700558092248922, 2.3183588758424726e-09, -0.0006084078869434338, 1.132701766742397e-05, 0.00024355707460373214, 0.000528466324367855, -0.0001496869082876438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004683655352424539, -0.008629921576278917, 0.01279942742211643, -0.000676001554645535, -0.01166395568175849, -0.013215726089998244, 0.0005192835960080346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0226633185663278e-08, -2.308903851348098e-08, -4.488954633424214e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21630439748619967, 0.8404016943610069, 0.8732325902621124, 0.0, 0.2670864500084269, -0.3500736949303083, -2.201188771287039, -1.4575111818230162, -1.0822051391365408, -1.0339937350457102, -1.656899387099385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.47801653359037, 0.3441213641530613, 2.1321942746466345, -1.4582108610075397, -1.5385199272259045, -0.5870618210244433, 0.25585313368914525, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764305057, -0.8173800055313815, 0.012201270189917056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014666196841298034, 4.18501299188691e-05, 0.0021656579419954388, 0.0, 0.00023707500114165074, 1.708161631123597e-09, -0.000609877993465055, 1.1089334095520644e-05, 0.00024402043528685044, 0.0005298642554411128, -0.00014969746412284165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0045066707806268565, -0.008281124352628821, 0.012307209775348856, -0.0006368461987208343, -0.01118261005762165, -0.012709250709730318, 0.00047532307129547667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.989775118302607e-08, -2.0911963833339505e-08, -4.440377591980377e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21631174612413442, 0.8404037659444155, 0.8733400399747198, 0.0, 0.2670983079575027, -0.3500736948358992, -2.201219333088103, -1.4575106378303866, -1.0821929163613722, -1.033967177525231, -1.6569068731630796, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4777998508672818, 0.3437242965305973, 2.132785636964021, -1.4582407957468173, -1.5390556559486657, -0.5876725879660186, 0.2558748243035173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676429540065, -0.8173800064800063, 0.012199071347080566]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014697275869504623, 4.143166817163784e-05, 0.0021489942521478005, 0.0, 0.0002371589815159808, 1.8881832788923155e-09, -0.0006112360212851207, 1.0879852590346034e-05, 0.0002444555033744088, 0.000531150409584982, -0.00014972127389383983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004333654461767229, -0.007941352449280998, 0.011827246347727177, -0.0005986947855518416, -0.010714574455222428, -0.012215338831507001, 0.00043381228744099164, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931269594944891e-08, -1.897249746363852e-08, -4.3976856729789664e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21631910898250323, 0.8404058203659344, 0.8734313942816181, 0.0, 0.2671101713915623, -0.35007369472823646, -2.2012499576498064, -1.4575101026923143, -1.0821806729780428, -1.0339405609707888, -1.65691436146373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4775916122503252, 0.34334375416759916, 2.133353633397984, -1.4582688748769361, -1.539568660395015, -0.5882593078441858, 0.2558945565993919, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764286114592, -0.8173800073414733, 0.01219689041088041]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014725716737626143, 4.108843037915216e-05, 0.001827086137965915, 0.0, 0.0002372686811908395, 2.1532540600196154e-09, -0.0006124912340656557, 1.0702761447333558e-05, 0.0002448676665861772, 0.0005323310888435015, -0.00014976601300870654, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004164772339131546, -0.0076108472599623386, 0.011359928679260192, -0.0005615826023763331, -0.010260088926983532, -0.011734397563344314, 0.0003946459174916378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8572119342267552e-08, -1.7229339607056864e-08, -4.36187240031449e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21632648483626604, 0.8404078610019264, 0.8735008633298548, 0.0, 0.2671220414651014, -0.35007369461671, -2.2012806401630662, -1.4575095748965508, -1.0821684100603033, -1.0339138903142895, -1.656921852965369, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4773916031237677, 0.34297926426414327, 2.133898911898631, -1.4582951514165798, -1.5400596266287203, -0.5888226455898563, 0.2559124422590564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764277208043, -0.8173800081279686, 0.01219472421722217]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000147517075256276, 4.0812719841546276e-05, 0.0013893809647326164, 0.0, 0.00023740147078158474, 2.230529526849804e-09, -0.0006136502651983383, 1.0555915271419436e-05, 0.00024525835479075465, 0.000533413129985177, -0.00014983003277980182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004000182531147696, -0.007289798069117633, 0.010905570012948866, -0.0005255307928758968, -0.009819324674107571, -0.011266754913410356, 0.00035771319329024845, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7813095886088723e-08, -1.5729905846717747e-08, -4.332387316480316e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21633387255182054, 0.8404098906112727, 0.8735483200046366, 0.0, 0.26713391900128314, -0.35007369450609876, -2.2013113760963816, -1.457509053135787, -1.0821561286823216, -1.0338871701475774, -1.6569293484056318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4771996020937377, 0.3426303470757356, 2.1344221323779666, -1.4583196790428843, -1.5405292460508637, -0.58936327873107, 0.2559285874167384, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676426863595, -0.8173800088538898, 0.012192570094637976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014775431109004844, 4.0592186925421987e-05, 0.0009491334956353416, 0.0, 0.00023755072363469516, 2.2122250946782595e-09, -0.0006147186663051112, 1.0435215275849966e-05, 0.0002456275596339105, 0.0005344033342436033, -0.00014990880525495503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00384002060060185, -0.006978343768154145, 0.01046440958671333, -0.0004905525260891201, -0.009392388442870377, -0.010812662824273412, 0.00032290315364010924, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7144184971665898e-08, -1.4518425130717686e-08, -4.308245168387653e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21634127108201104, 0.840411911773548, 0.8735200946912641, 0.0, 0.26714580514274827, -0.35007369450609865, -2.201342161611738, -1.4575085357847926, -1.0821438294007941, -1.033860404629491, -1.6569368488723941, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4770153828253616, 0.3422965181907837, 2.1349239633413792, -1.4583425117172015, -1.5409782121782185, -0.5898818938828616, 0.25594309240554947, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764259984554, -0.8173800096240316, 0.01219042544560096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001479706038099614, 4.04232455067057e-05, -0.0005645062674475476, 0.0, 0.0002377228293023912, 1.9278214615706745e-15, -0.0006157103071339759, 1.034701988989483e-05, 0.0002459856305474728, 0.0005353103617249062, -0.0001500093352458067, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003684385367522581, -0.006676577699036978, 0.010036619268252788, -0.0004566534863468154, -0.008979322547097449, -0.010372303035832545, 0.00029009977622171173, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.730279494064749e-08, -1.54028340240997e-08, -4.289298074033214e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21634867946193043, 0.8404139469105035, 0.8734430517980745, 0.0, 0.26715771953260353, -0.35007369450608117, -2.2013729976504215, -1.4575080126113116, -1.082131506488649, -1.0338335977309443, -1.6569443683163674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.476838742846336, 0.3419772906426626, 2.135405082440259, -1.4583637138790277, -1.5414072210828136, -0.5903791849483911, 0.2559560599639653, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764251035184, -0.8173800104929301, 0.012188267740580613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000" }, - "execution_count": 34, + "execution_count": 13, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "reset_giskard()\n", + "# reset_giskard()\n", "\n", "js = {\n", " # 'torso_lift_joint': 0.2999225173357618,\n", From 17f92bb22703774c01b3b00acd2cc6fb0abf4084 Mon Sep 17 00:00:00 2001 From: malte Date: Wed, 7 Aug 2024 09:29:57 +0200 Subject: [PATCH 13/43] added parent class for feature function goals --- src/giskardpy/goals/feature_functions.py | 107 ++++++++++------------- src/giskardpy/goals/pointing.py | 9 +- 2 files changed, 51 insertions(+), 65 deletions(-) diff --git a/src/giskardpy/goals/feature_functions.py b/src/giskardpy/goals/feature_functions.py index 00363b38c0..db24719ba6 100644 --- a/src/giskardpy/goals/feature_functions.py +++ b/src/giskardpy/goals/feature_functions.py @@ -10,10 +10,39 @@ from giskardpy.goals.pointing import Pointing from giskardpy.goals.align_planes import AlignPlanes -from typing import Optional, List, Dict +from typing import Optional, List, Dict, Union -class PerpendicularFeatureFunction(Goal): +class FeatureFunctionGoal(Goal): + def __init__(self, + tip_link: str, root_link: str, + world_feature: Union[PointStamped, Vector3Stamped], + robot_feature: Union[PointStamped, Vector3Stamped], + name: Optional[str] = None + ): + self.root = god_map.world.search_for_link_name(root_link, None) + self.tip = god_map.world.search_for_link_name(tip_link, None) + if name is None: + name = f'{self.__class__.__name__}/{self.root}/{self.tip}' + super().__init__(name) + world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) + root_world_feature = god_map.world.transform_msg(self.root, world_feature) + robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) + tip_robot_feature = god_map.world.transform_msg(self.tip, robot_feature) + + root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) + if type(robot_feature) == PointStamped: + self.root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) + elif type(robot_feature) == Vector3Stamped: + self.root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) + + if type(world_feature) == PointStamped: + self.root_P_world_feature = cas.Point3(root_world_feature) + if type(world_feature) == Vector3Stamped: + self.root_V_world_feature = cas.Vector3(root_world_feature) + + +class PerpendicularFeatureFunction(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, world_feature: Vector3Stamped, robot_feature: Vector3Stamped, @@ -24,21 +53,10 @@ def __init__(self, tip_link: str, root_link: str, hold_condition: cas.Expression = cas.FalseSymbol, end_condition: cas.Expression = cas.TrueSymbol ): - self.root_link = god_map.world.search_for_link_name(root_link, None) - self.tip_link = god_map.world.search_for_link_name(tip_link, None) - if name is None: - name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' - super().__init__(name) - world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) - root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) - robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) - tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name) - root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) - root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) - root_V_world_feature = cas.Vector3(root_world_feature) - - expr = cas.dot(root_V_world_feature[:3], root_V_robot_feature[:3]) + expr = cas.dot(self.root_V_world_feature[:3], self.root_V_robot_feature[:3]) task = self.create_and_add_task() task.add_equality_constraint(reference_velocity=max_vel, @@ -49,7 +67,7 @@ def __init__(self, tip_link: str, root_link: str, self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) -class HeightFeatureFunction(Goal): +class HeightFeatureFunction(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, world_feature: PointStamped, robot_feature: PointStamped, @@ -62,21 +80,10 @@ def __init__(self, tip_link: str, root_link: str, hold_condition: cas.Expression = cas.FalseSymbol, end_condition: cas.Expression = cas.TrueSymbol ): - self.root_link = god_map.world.search_for_link_name(root_link, None) - self.tip_link = god_map.world.search_for_link_name(tip_link, None) - if name is None: - name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' - super().__init__(name) - world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) - root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) - robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) - tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name) - root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) - root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) - root_P_world_feature = cas.Point3(root_world_feature) - - distance = root_P_robot_feature - root_P_world_feature + distance = self.root_P_robot_feature - self.root_P_world_feature height_vector = cas.Vector3([0, 0, 1]) @@ -93,7 +100,7 @@ def __init__(self, tip_link: str, root_link: str, self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) -class DistanceFeatureFunction(Goal): +class DistanceFeatureFunction(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, world_feature: PointStamped, robot_feature: PointStamped, @@ -106,22 +113,11 @@ def __init__(self, tip_link: str, root_link: str, hold_condition: cas.Expression = cas.FalseSymbol, end_condition: cas.Expression = cas.TrueSymbol ): - self.root_link = god_map.world.search_for_link_name(root_link, None) - self.tip_link = god_map.world.search_for_link_name(tip_link, None) - if name is None: - name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' - super().__init__(name) - world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) - root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) - robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) - tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) - - root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) - root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) - root_P_world_feature = cas.Point3(root_world_feature) + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name) # distance between the two feature points - distance = root_P_robot_feature - root_P_world_feature + distance = self.root_P_robot_feature - self.root_P_world_feature # normal vector defining the x-y plane height_vector = cas.Vector3([0, 0, 1]) @@ -206,7 +202,7 @@ def __init__(self, tip_link: str, root_link: str, end_condition=end_condition)) -class AngleFeatureFunction(Goal): +class AngleFeatureFunction(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, world_feature: Vector3Stamped, robot_feature: Vector3Stamped, @@ -219,21 +215,10 @@ def __init__(self, tip_link: str, root_link: str, hold_condition: cas.Expression = cas.FalseSymbol, end_condition: cas.Expression = cas.TrueSymbol ): - self.root_link = god_map.world.search_for_link_name(root_link, None) - self.tip_link = god_map.world.search_for_link_name(tip_link, None) - if name is None: - name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' - super().__init__(name) - world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) - root_world_feature = god_map.world.transform_msg(self.root_link, world_feature) - robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) - tip_robot_feature = god_map.world.transform_msg(self.tip_link, robot_feature) - - root_T_tip = god_map.world.compose_fk_expression(self.root_link, self.tip_link) - root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) - root_V_world_feature = cas.Vector3(root_world_feature) + super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, + robot_feature=robot_feature, name=name) - expr = cas.angle_between_vector(root_V_world_feature, root_V_robot_feature) + expr = cas.angle_between_vector(self.root_V_world_feature, self.root_V_robot_feature) task = self.create_and_add_task() task.add_inequality_constraint(reference_velocity=max_vel, diff --git a/src/giskardpy/goals/pointing.py b/src/giskardpy/goals/pointing.py index 824c91374a..71fbd27d2e 100644 --- a/src/giskardpy/goals/pointing.py +++ b/src/giskardpy/goals/pointing.py @@ -60,10 +60,11 @@ def __init__(self, self.tip_V_pointing_axis.vector.z = 1 root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) - root_P_goal_point = symbol_manager.get_expr(f'god_map.motion_goal_manager.motion_goals[\'{str(self)}\']' - f'.root_P_goal_point', - input_type_hint=PointStamped, - output_type_hint=cas.Point3) + # root_P_goal_point = symbol_manager.get_expr(f'god_map.motion_goal_manager.motion_goals[\'{str(self)}\']' + # f'.root_P_goal_point', + # input_type_hint=PointStamped, + # output_type_hint=cas.Point3) + root_P_goal_point = cas.Point3(self.root_P_goal_point) root_P_goal_point.reference_frame = self.root tip_V_pointing_axis = cas.Vector3(self.tip_V_pointing_axis) From 0b5610c9303aad93c080bda09114a075219666d0 Mon Sep 17 00:00:00 2001 From: malte Date: Wed, 7 Aug 2024 12:01:46 +0200 Subject: [PATCH 14/43] add feature function visualization for the notebook --- scripts/giskard_examples.ipynb | 72 +++++++++++++++++++----- scripts/iai_robots/pr2/pr2_standalone.py | 2 +- src/giskardpy/goals/feature_functions.py | 13 +++++ 3 files changed, 72 insertions(+), 15 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 5f06f5bb9e..b206244eee 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 2, + "execution_count": 1, "outputs": [ { "name": "stdout", @@ -62,7 +62,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 2, "outputs": [], "source": [ "rospy.init_node('giskard_examples')" @@ -76,7 +76,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 3, "outputs": [], "source": [ "gs = GiskardWrapper()" @@ -90,7 +90,7 @@ }, { "cell_type": "code", - "execution_count": 14, + "execution_count": 6, "outputs": [], "source": [ "def reset_giskard():\n", @@ -238,7 +238,8 @@ "# specify the cartesian pose goal to move 'l_gripper_tool_frame' towards goal_pose by using the kinematic chain between 'l_gripper_tool_frame' and 'map'\n", "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", "# specify monitor that is active when it is below the given thresholds and use it to end the motion\n", - "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01, orientation_threshold=0.01)\n", + "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01,\n", + " orientation_threshold=0.01)\n", "gs.monitors.add_end_motion(pose_monitor)\n", "# in the case that there is nos specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum\n", "# gs.add_default_end_motion_conditions()\n", @@ -296,7 +297,8 @@ "goal_pose.pose.position.y = 0\n", "goal_pose.pose.position.z = 0\n", "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", - "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01, orientation_threshold=0.01)\n", + "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01,\n", + " orientation_threshold=0.01)\n", "gs.monitors.add_end_motion(pose_monitor)\n", "gs.execute()" ], @@ -312,7 +314,19 @@ "source": [ "When using the cartesian goals all degrees of freedom of the link are fully constrained. One Advantage of constraint-based control is that one can only constrain neccessary constraints.\n", "The unconstrained DOF can then be exploited during the motion, for example in the collision avoidance or other secondary tasks.\n", - "To use this in the python interface one can use motion goals that constrain only a singualar value (sometimes called constraints on feature functions).|" + "To use this in the python interface one can use motion goals that constrain only a singualar value, here also called constraints on feature functions.\n", + "For a feature function constraint a feature (Point or Vector) related to the robot and one related to the world has to be defined.\n", + "The name of the function then defines how they will be combined and 0 or 2 constraint values can be provided.\n", + "Right now we support the following feature functions:\n", + "\n", + " - Perpendicular(world_vector, robot_vector)\n", + " - Height(world_point, robot_point, lower_limit, upper_limit)\n", + " - Distance(world_point, robot_point, lower_limit, upper_limit)\n", + " - Pointing(world_point, robot_vector)\n", + " - Align(world_vector, robot_vector)\n", + " - Angle(world_vector, robot_vector, lower_limit, upper_limit)\n", + "\n", + "Robot features will be visualized as red points or arrows and world features have the color green." ], "metadata": { "collapsed": false, @@ -323,9 +337,39 @@ }, { "cell_type": "code", - "execution_count": null, - "outputs": [], - "source": [], + "execution_count": 9, + "outputs": [ + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.0020876631136696375, 0.0037499998672351578, 0.00019471474162977202, -0.15000000164960314, 3.7829411969664335e-05, -0.10001000398503089, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006250370152481892, -5.90706498035983e-05, 0.0006249999081531167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04175326227339274, 0.07499999734470315, 0.00389429483259544, -3.299206281492319e-08, 0.0007565882393932866, -7.970061789824146e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012500740304963783, -0.001181412996071966, 0.012499998163062333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.005748831451660165, 0.014999911625644522, 0.0005366000919809209, -0.15000051009817622, 0.00010427796097227672, -0.1000111677480421, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0025002804358226684, -0.00017499404359716932, 0.0024987303825485373]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07322336675981056, 0.2249982351681873, 0.006837707007022976, -1.0168971461347905e-05, 0.0013289709800522478, -2.3275260224123218e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03750486841148958, -0.0023184678758714204, 0.037474609487908414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.009904069007649525, 0.03379389126350592, 0.0009249277825230434, -0.15000051010562018, 0.0001797763760935028, -0.10001116776407216, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.00589700329790533, -0.0003103470634419895, 0.004996191433763215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08310475111978717, 0.3758795927572279, 0.007766553810842451, -1.4887912588198147e-10, 0.0015099683024245216, -3.2060128409347596e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06793445724165324, -0.002707060396896403, 0.04994922102429357]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.01410062444050083, 0.0563819722997141, 0.0013173267313473843, -0.15000051020939031, 0.00025609163336437734, -0.10001116958089652, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010486404953052475, -0.0004477889050711366, 0.00766949351826411]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08393110865702608, 0.4517616207241637, 0.007847978976486817, -2.075402794784519e-09, 0.0015263051454174907, -3.6336487175869836e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0917880331029429, -0.002748836832582941, 0.05346604169001788]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.01820611048639602, 0.07949476306340346, 0.0017012579197973536, -0.15000051080969784, 0.0003307879202235581, -0.10001117114225146, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016040133286662362, -0.0005840742347895849, 0.010328598224828007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08210972091790388, 0.46225581527378706, 0.007678623768999387, -1.2006150345894164e-08, 0.0014939257371836142, -3.122709877801651e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11107456667219773, -0.002725706594368965, 0.05318209413127793]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.02222160407768684, 0.10079384271814296, 0.002076568320432928, -0.15000052789849957, 0.0004038361678194121, -0.10001120125286588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.02238328361038687, -0.0007245170569926648, 0.012935934463477185]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08030987182581635, 0.42598159309478995, 0.007506208012711485, -3.417760347815328e-07, 0.0014609649519170802, -6.022122884723246e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12686300647449014, -0.0028088564440615976, 0.05214672477298358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.026154883590617434, 0.11849253658389435, 0.002443676973187925, -0.15000052809148837, 0.0004753127237887259, -0.10001120154644538, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029355405072700992, -0.0008730655023351766, 0.015479823080700755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07866559025861192, 0.3539738773150278, 0.0073421730550999355, -3.8597758651328375e-09, 0.0014295311193862764, -5.871590070862548e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13944242924628247, -0.002970968906850236, 0.0508777723444714]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.02998010712069136, 0.13160423318446376, 0.002799938707498612, -0.15000054469388538, 0.0005446926211230858, -0.10001122598160703, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.036782145831624376, -0.0010270064993040718, 0.017920996815444352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07650447060147852, 0.2622339320113881, 0.007125234686213743, -3.320479400429139e-07, 0.0013875979466871978, -4.887032327669745e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1485348151784677, -0.0030788199393779027, 0.048823474694871916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.03366475220547315, 0.14002453785059119, 0.0031422259854090103, -0.15000054489276568, 0.0006113572399642135, -0.10001122623890712, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04449709635323544, -0.001180769148041398, 0.020216490094773523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07369290169563586, 0.1684060933225482, 0.006845745558207968, -3.977606023993649e-09, 0.0013332923768225526, -5.146001912908356e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15429901043222133, -0.0030752529747465267, 0.04590986558658338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.03719838560104596, 0.144182211038836, 0.0034695572139267694, -0.15000056813263796, 0.0006751094581425631, -0.10001125479342804, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0523366215352019, -0.0013325337044522941, 0.02235152988491964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07067266791145604, 0.08315346376489618, 0.006546624570355178, -4.6479744543194967e-07, 0.0012750443635669915, -5.710904181857254e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15679050363932925, -0.0030352911282179205, 0.04270079580292232]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.040588438496928794, 0.1447625993206287, 0.0037826722797508093, -0.15000106004769992, 0.0007360910530891141, -0.1000118404182472, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06018406121442206, -0.001483373465027545, 0.024333735555414654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06780105791765671, 0.011607765635854542, 0.0062623013164808, -9.838301239430676e-06, 0.0012196318989310198, -1.1712496383278903e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1569487935844032, -0.0030167952115050154, 0.03964411340990028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.04385419897749301, 0.14252076718587106, 0.004083446567852978, -0.15000118825626152, 0.00079466805741713, -0.10001199941485582, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06799119209285112, -0.0016359214961377082, 0.026185602914079162]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06531520961128422, -0.044836642695152897, 0.006015485762043373, -2.564171232208125e-06, 0.0011715400865603173, -3.1799321723204208e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1561426175685811, -0.0030509606222032656, 0.037037347173290186]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.04701995958635031, 0.13819763186467912, 0.004374245874515086, -0.15000127809192243, 0.0008513043820226777, -0.10001212265813088, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07575808814734845, -0.0017933469737392211, 0.027935965289999105]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06331521217714606, -0.08646270642383899, 0.0058159861332421564, -1.7967132180976775e-06, 0.0011327264921109537, -2.4648655010492274e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15533792108994673, -0.0031485095520302556, 0.03500724751839887]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.050109996950189896, 0.13248754523197742, 0.004657459986532812, -0.15000135611398183, 0.0009064703092848628, -0.10001224400721725, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08350877893487604, -0.0019587190318480245, 0.029613731024807924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06180074727679177, -0.1142017326540339, 0.005664282240354523, -1.560441188040712e-06, 0.0011033185452437022, -2.426981727638467e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15501381575055181, -0.003307441162176063, 0.033555314696176376]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.05314551553911133, 0.12602405055979307, 0.004935218357751498, -0.15000142748032838, 0.0009605864805969355, -0.10001236103313897, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09127281082911505, -0.00213464255214284, 0.03124410269990247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.060710371778428654, -0.12926989344368683, 0.005555167424373715, -1.4273269309871063e-06, 0.0010823234262414532, -2.3405184343630722e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15528063788478005, -0.003518470405896308, 0.03260743350189086]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.056143126500881026, 0.11936771293944992, 0.005209243336760879, -0.15000150389115868, 0.0010139946562518771, -0.10001248116316473, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09907392535431646, -0.0023230648461933083, 0.032846725949708]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05995221923539391, -0.1331267524068629, 0.00548049958018763, -1.5282166062362677e-06, 0.0010681635130988325, -2.4026005152752026e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15602229050402822, -0.003768445881009365, 0.032052464996110586]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.05911445981327309, 0.11299150178103126, 0.005480802424147435, -0.15000150479512453, 0.0010669477536916746, -0.10001248248545974, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10692487944556332, -0.002525202585451863, 0.03443523037490541]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05942666624784121, -0.12752422316837325, 0.005431181747731117, -1.8079317000552607e-08, 0.0010590619487959496, -2.6445900230735512e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1570190818249372, -0.0040427547851711, 0.031770088503948135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.062066632597567964, 0.10726599916336475, 0.005750735431581176, -0.15000150569347462, 0.0011196145403574596, -0.10001248372639389, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11482694147280874, -0.002741591129652345, 0.03601781006983567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05904345568589747, -0.11451005235333007, 0.005398660148674814, -1.7967001999891985e-08, 0.0010533357333157025, -2.4818682921246718e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15804124054490837, -0.004327770884009645, 0.03165159389860516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.06500323823486201, 0.10244980092596892, 0.0060195294129101505, -0.15000150673397622, 0.0011720937980546813, -0.10001248512057687, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12277257000221148, -0.002972219787345933, 0.037598421608252296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05873211274588096, -0.0963239647479166, 0.005375879626579483, -2.0810032242831352e-08, 0.0010495851539444334, -2.7883659592355694e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15891257058805494, -0.0046125731538717565, 0.03161223076833247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.06792555812652318, 0.09868905584532096, 0.00628741755669849, -0.1500016123604411, 0.0012244333790247207, -0.1000126276568153, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13074950943593966, -0.003216729678259439, 0.03917825314797849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.058446397833223335, -0.07521490161295905, 0.005357762875766789, -2.1125292978066464e-06, 0.0010467916194007902, -2.850724768721872e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1595387886745637, -0.004890197818270117, 0.031596630794523864]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07083367478634559, 0.0960269305807533, 0.006554474897015343, -0.1500017139107497, 0.0012766488578148613, -0.10001276717067617, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13874485715391177, -0.003474604929647466, 0.04075706853994019]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05816233319644805, -0.0532425052913533, 0.005341146806337053, -2.031006172216235e-06, 0.0010443095758028119, -2.790277217313188e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1599069543594422, -0.005157505027760538, 0.03157630783923401]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07372732439272076, 0.09442069071698626, 0.006820696164447082, -0.15000180303355806, 0.001328738860621185, -0.10001288854141732, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1467479276633926, -0.00374533832513258, 0.04233424517253666]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.057872992127503374, -0.03212479727534079, 0.005324425348634768, -1.7824561669068486e-06, 0.0010418000561264768, -2.427414823026788e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16006141018961662, -0.005414667909702285, 0.031543532651929336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07660640217247879, 0.09376274294577842, 0.007086046776707491, -0.15000188146490448, 0.0013806952456893464, -0.10001299367879939, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15475165440623598, -0.0040285337206670425, 0.043909390920544134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05758155559516072, -0.013158955424156734, 0.00530701224520818, -1.5686269281445476e-06, 0.0010391277013632272, -2.102747641271741e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16007453485686785, -0.0056639079106892525, 0.03150291496014951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07947115546784388, 0.09390221879460182, 0.007350488443897669, -0.15000195632460775, 0.0014325083581940427, -0.10001309321923099, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1627526712145131, -0.004323943241541222, 0.04548257866520635]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.057295065907301865, 0.0027895169764679296, 0.005288833343803562, -1.4971940654482357e-06, 0.0010362622500939259, -1.9908086322269075e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16002033616554232, -0.005908190417483597, 0.03146375489324434]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.08232215831429435, 0.09466479339877282, 0.007613986401722041, -0.1500020323830217, 0.0014841686903628753, -0.10001319422620963, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17075052372531938, -0.004631453279187666, 0.04705431070070234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05702005692900939, 0.01525149208341989, 0.005269959156487428, -1.5211682789370048e-06, 0.0010332066433766528, -2.020139572724712e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15995705021612586, -0.0061502007529288675, 0.031434640709919734]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.08516017384368171, 0.09586957923283822, 0.007876506833521207, -0.15000211314403042, 0.0015356666042063629, -0.10001330203683399, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17874651719427476, -0.004951040721145524, 0.04862534308998595]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05676031058774722, 0.024095716681308096, 0.00525040863598331, -1.6152201744217732e-06, 0.0010299582768697518, -2.1562124871216715e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15991986937910774, -0.006391748839157157, 0.031420647785672294]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.08798599248589298, 0.09734270814796529, 0.008138011731836335, -0.15000220138697695, 0.0015869915326211055, -0.10001342115158829, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.186742605188359, -0.005282720520976461, 0.050196479146461005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.056516372844225254, 0.029462578302541467, 0.005230097966302567, -1.7648589307398148e-06, 0.0010264985682948513, -2.3822950860616985e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1599217598816847, -0.006633595996618754, 0.031422721129501056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09080030259900418, 0.09892759325096909, 0.008398455808033363, -0.1500022994425874, 0.0016381315616010787, -0.10001355576572014, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1947405627691917, -0.005626500516171323, 0.051768403311781494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.056286202262224076, 0.031697702060075855, 0.005208881523940577, -1.9611122088593767e-06, 0.0010228005795994656, -2.692282636989708e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15995915161665356, -0.006875599903897247, 0.0314384833064098]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09360361876015387, 0.10049200312613894, 0.00865778731131385, -0.1500024010574014, 0.0016890737563265408, -0.10001369561928782, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20274152876472634, -0.005982352661385059, 0.05334158807929443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05606632322299371, 0.03128819750339707, 0.005186630065609744, -2.032296280306048e-06, 0.0010188438945092403, -2.797071353327598e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16001931991069326, -0.007117042904274718, 0.031463695350258634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09639626774279439, 0.1019321465187894, 0.008915952413463893, -0.15000250323279554, 0.0017398051575173107, -0.10001383568140829, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2107458898040053, -0.006350202287427256, 0.054916274542256525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.055852979652810324, 0.028802867853009177, 0.005163302043000864, -2.0435078829855017e-06, 0.0010146280238153996, -2.8012424093048454e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600872207855793, -0.0073569925208439284, 0.03149372925924195]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09917841710293, 0.10317404932740164, 0.00917290157888373, -0.15000260565919835, 0.001790314131360599, -0.10001397561361902, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21875340354721814, -0.006729932252852412, 0.056492507702740884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05564298720271227, 0.02483805617224464, 0.0051389833083967515, -2.0485280558458973e-06, 0.0010101794768657662, -2.798644214716896e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16015027486425687, -0.007594599308503119, 0.031524663209687165]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.10195012591569663, 0.10417261483113908, 0.009428596016540806, -0.15000270811669592, 0.0018405916939532405, -0.10001411522550832, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22676343982889113, -0.007121396377360576, 0.058070200708085454]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.055434176255332625, 0.019971310074748908, 0.0051138887531415175, -2.049149951576258e-06, 0.0010055512518528317, -2.79223778608895e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602007256334595, -0.007829282490163294, 0.03155386010689139]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.10471139871800485, 0.10490885952264604, 0.00968301262266311, -0.15000281046689043, 0.0018906324956189182, -0.10001425443557388, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2347752359528914, -0.007524435922369098, 0.05964920369459655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05522545604616425, 0.014724893830139283, 0.005088332122446073, -2.0470038903068266e-06, 0.0010008160333135538, -2.7842013110638597e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16023592248000548, -0.008060790900170433, 0.03158005973022196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.10746222948891189, 0.10538587556941209, 0.009936146494038864, -0.15000291263614787, 0.0019404352867358064, -0.10001439324360752, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24278809698318404, -0.007938894113816876, 0.061229360052086235]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05501661541814079, 0.00954032093532093, 0.00506267742751509, -2.0433851488248467e-06, 0.0009960558223377654, -2.7761606727253146e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16025722060585304, -0.008289163828955571, 0.03160312714979371]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11020262952693957, 0.10562406974997551, 0.01018801082078672, -0.15000301459049678, 0.0019900028339980857, -0.1000145316937579, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2508015110008898, -0.008364625799578364, 0.06281054189029536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.054808000760553637, 0.004763883611268485, 0.0050372865349571395, -2.0390869781037383e-06, 0.0009913509452455843, -2.7690030075937545e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602682803541154, -0.008514633715229772, 0.0316236367641825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11293263910242243, 0.1056561736197166, 0.010438634545635421, -0.15000311631227786, 0.0020393413724660125, -0.10001466984176427, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2588151814761437, -0.008801501478749588, 0.06439266432815272]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.054600191509657364, 0.0006420773948217738, 0.005012474496974011, -2.034435621507249e-06, 0.0009867707693585349, -2.7629601272238864e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027340950507718, -0.0087375135834245, 0.03164244875714719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11565232661690082, 0.10552242993791294, 0.010688058511064672, -0.1500032177831877, 0.0020884597457442662, -0.10001480773142808, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26682899863348464, -0.009249406569056356, 0.06597568335662803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05439375028956773, -0.002674873636073163, 0.00498847930858501, -2.0294181966086833e-06, 0.0009823674655650772, -2.7577932761261993e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027634314681902, -0.008958101806135335, 0.03166038056950626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11836178052850597, 0.10526625710164986, 0.010936330908741418, -0.15000331897616992, 0.002137368404785757, -0.10001494538288014, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2748429786823032, -0.009708237652476269, 0.06755958414850484]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05418907823210299, -0.005123456725261635, 0.004965447953534923, -2.023859644087188e-06, 0.0009781731808298146, -2.753029041045394e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027960097637037, -0.009176621668398268, 0.031678015837536336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1210610989938251, 0.10493059213367162, 0.01118350275716096, -0.15000341985480473, 0.0021860784171861005, -0.10001508279085179, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28285719706915874, -0.010177897593766385, 0.06914436638199215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05398636930638248, -0.0067132993595648074, 0.004943436968390851, -2.0175726963463243e-06, 0.000974200248006867, -2.7481594331319943e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16028436773711088, -0.009393198825802328, 0.031695644669746156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.12375038079690809, 0.10455502222364167, 0.011429623942267745, -0.1500035203779346, 0.002234600599319792, -0.1000152199302356, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2908717337874219, -0.010658291066705046, 0.07073003137889249]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.053785636061659696, -0.007511398200599033, 0.0049224237021357, -2.010462597635803e-06, 0.0009704436426738275, -2.742787676064544e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602907343652638, -0.009607869458773236, 0.03171329993800688]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.12642971942227485, 0.10417373820477834, 0.011674740134079896, -0.1500036205060456, 0.0022829448377889344, -0.10001535676470304, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2988866392571594, -0.011149321410316434, 0.07231657359768932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05358677250733544, -0.00762568037726677, 0.004902323836243018, -2.0025622198112902e-06, 0.0009668847693828508, -2.736689348874819e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16029810939474964, -0.009820606872227739, 0.031730844375936706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.12909920062064456, 0.1038142813062913, 0.011918890691698896, -0.15000372020677194, 0.0023311196248879695, -0.10001549325512123, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30690192120502396, -0.01165088910690919, 0.0739039769941741]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0533896239673944, -0.0071891379697407096, 0.004883011152379989, -1.994014526775476e-06, 0.0009634957419807043, -2.7298083638265085e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16030563895729083, -0.010031353931855115, 0.03174806792969542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13175890280009678, 0.10349700692651807, 0.012162107517795916, -0.15000381945822788, 0.0023791318009343887, -0.10001562936589996, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3149175477617597, -0.012162891684923644, 0.07549221536866349]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.053194043589044365, -0.006345487595464606, 0.004864336521940398, -1.985029118847568e-06, 0.0009602435209283887, -2.722215574728978e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031253113471383, -0.01024005156028909, 0.03176476748978784]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13440889911166298, 0.10323515578609144, 0.012404414729707488, -0.15000391824982176, 0.0024269864761138665, -0.1000157650685688, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3229334598600846, -0.012685224573635566, 0.07708125516054178]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05299992623132407, -0.005237022808532758, 0.004846144238231459, -1.975831877379156e-06, 0.0009570935035895583, -2.7140533767438286e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031824196649866, -0.010446657774238456, 0.03178079583756558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13704926009105978, 0.10303540317611057, 0.012645828971454411, -0.15000401658088752, 0.0024746870948140175, -0.10001590034270395, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33094958634329213, -0.013217782369081704, 0.07867105911465036]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05280721958793577, -0.003995052199617488, 0.004828284834938473, -1.966621315383495e-06, 0.0009540123740030161, -2.705482703031077e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032252966415117, -0.010651155908922754, 0.0317960790821716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13968005599678643, 0.10289875007253549, 0.012886360185752323, -0.15000411445759593, 0.0025222356036181956, -0.10001603517448816, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33896585699866766, -0.013760460057138527, 0.08026158960804541]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05261591811453283, -0.0027330620715015548, 0.004810624285958224, -1.957534168241165e-06, 0.0009509701760835617, -2.6966356842751498e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032541310751044, -0.010853553761136453, 0.031810609867901005]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.14230135837292215, 0.10282162387553041, 0.013126012682208414, -0.15000421188955856, 0.0025696326871641126, -0.10001616955450232, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3469822110270512, -0.014313153906979549, 0.08185281095266303]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.052426047522714375, -0.0015425239401015232, 0.0047930499291218434, -1.948639252903821e-06, 0.0009479416709183389, -2.6876002832324993e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032708056767095, -0.01105387699682044, 0.031824426892352264]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.14491324072588432, 0.1027970690815313, 0.013364786364548426, -0.15000430888651767, 0.00261687804133027, -0.1000163034751356, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3549986005094158, -0.01487576192769053, 0.08344469048998202]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05223764705924334, -0.0004910958799823689, 0.004775473646800229, -1.939939182292898e-06, 0.0009449070833231465, -2.6784126655474985e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603277896472922, -0.011252160414219602, 0.031837590746379596]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.147515778459514, 0.10281592665069528, 0.013602678007255217, -0.15000440545603017, 0.0026639706589021745, -0.10001643692874143, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.36301498982583513, -0.015448183924631567, 0.08503719865508186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05205075467259349, 0.00037715138327953717, 0.0047578328541358185, -1.93139024968456e-06, 0.0009418523514380869, -2.6690721166780173e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032778632838668, -0.011448439938820741, 0.03185016330199672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.15010904833780306, 0.10286792259337411, 0.013839682496059753, -0.15000450149935324, 0.0027109091080382633, -0.10001656977631, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3710313526255033, -0.01603032127127016, 0.08663030836443807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05186539756578117, 0.001039918853576738, 0.00474008977609071, -1.9208664614119633e-06, 0.0009387689827217774, -2.6569513714093516e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160327255993363, -0.011642746932771885, 0.03186219418712418]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.15269312776344712, 0.10294260908181223, 0.014075793966906997, -0.15000459698000315, 0.002757691788370953, -0.10001670196043576, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37904766795765293, -0.016622076559047433, 0.08822399413825294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05168158851288156, 0.0014937297687621703, 0.004722229416944879, -1.9096129980630864e-06, 0.0009356536066537995, -2.6436825151918284e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032630664299236, -0.01183510575554544, 0.03187371547629732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.15526809409616898, 0.10303012336622061, 0.014311006794281923, -0.15000469189564844, 0.002804317153345284, -0.10001683347076099, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.387063916788, -0.01722335324650534, 0.08981823126051386]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05149932665443709, 0.0017502856881675601, 0.004704256547498512, -1.8983129059466525e-06, 0.0009325072994866163, -2.630206504537499e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032497660694164, -0.012025533749158183, 0.031884742445218356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1578340241447835, 0.10312174956733564, 0.014545316394676069, -0.1500047862394967, 0.0028507838909023523, -0.10001696429444111, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.39508007958383323, -0.017834055389177036, 0.09141299516122561]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05131860097229048, 0.0018325240223005684, 0.004686192007882923, -1.8868769651933487e-06, 0.0009293347511413645, -2.6164736025186358e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603232559166643, -0.012214042853433896, 0.03189527801423514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.16039099387875008, 0.10321028513847601, 0.014778719825304428, -0.15000488000098455, 0.0028970910579823993, -0.10001709441650874, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.40309613514194387, -0.0184540874873721, 0.09300826108719261]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05113939467933149, 0.0017707114228074554, 0.004668068612567201, -1.8752297572542138e-06, 0.0009261433416009425, -2.6024413527010967e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032111116221281, -0.012400641963901258, 0.031905318519339816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.16293907833816565, 0.10329022693559496, 0.01501121617225754, -0.15000497316615874, 0.0029432381675868896, -0.10001722382012562, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4111120604695264, -0.019083354447213808, 0.0946040040322801]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05096168918831153, 0.0015988359423789796, 0.004649926939062258, -1.8633034837966203e-06, 0.0009229421920898092, -2.5880723375732797e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031850655165075, -0.01258533919683416, 0.03191485890174994]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1654783516844296, 0.10335780123988149, 0.01524280673576578, -0.15000506572064762, 0.002989225230216298, -0.10001735248807969, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.41912783134119036, -0.019721761624768727, 0.09620019884546158]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05078546692527899, 0.0013514860857304829, 0.004631811270164776, -1.8510897776065506e-06, 0.0009197412525881734, -2.573359081392818e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031541743327934, -0.012768143551098406, 0.03192389626362951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.16800888732471583, 0.10341086786448839, 0.015473495032315489, -0.1500051576494521, 0.0030350527542101075, -0.10001748040284295, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42714342313855763, -0.020369214913387158, 0.09779682042235331]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05061071280572483, 0.0010613324921380433, 0.004613765930994204, -1.8385760897522917e-06, 0.0009165504798761872, -2.5582952651828924e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031183594734527, -0.012949065772368635, 0.03193243153783478]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1705307580532344, 0.10344873098540215, 0.015703286642976298, -0.15000524893733921, 0.0030807217116472054, -0.10001760754655847, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.43515881165343523, -0.02102562083799346, 0.0993938439001995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05043741457037101, 0.0007572624182753398, 0.004595832213216189, -1.8257577420423889e-06, 0.0009133791487419609, -2.5428743106810666e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603077702975522, -0.013128118492126098, 0.031940469556923756]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.17304403617171873, 0.10347188906398222, 0.015932188943755282, -0.1500053395695857, 0.0031262334778758864, -0.1000177339015863, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.44317397366458217, -0.02169088663127147, 0.10099124480537151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.050265562369686774, 0.0004631615716014219, 0.0045780460155797, -1.8126449295723366e-06, 0.0009102353245736233, -2.5271005565511222e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603032402229392, -0.01330531586556015, 0.0319480181034405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.17554879357212447, 0.10348175376545704, 0.016160210756716153, -0.15000542953208593, 0.0031715897533633416, -0.10001785945037384, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4511888872247797, -0.022364920279907247, 0.10258899913299559]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05009514800811438, 0.00019729402949635635, 0.00456043625921739, -1.7992500044204525e-06, 0.0009071255097491021, -2.5109757506601937e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16029827120395065, -0.013480672972715567, 0.03195508655248156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.17804510178080624, 0.10348036374685363, 0.01638736196009529, -0.15000551881174337, 0.0032167924764168266, -0.10001798417576871, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45920353168969674, -0.023047630540533506, 0.10418708336258187]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.049926164173635455, -2.7800372068357215e-05, 0.004543024067582732, -1.7855931486566788e-06, 0.0009040544610697035, -2.4945078973837476e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16029288929834185, -0.013654205212525184, 0.031961684591725735]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.18053303197316722, 0.10347011419438958, 0.01661365309220967, -0.15000560739647148, 0.0032618437345468742, -0.10001810806096284, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46721788757183114, -0.023738926932461792, 0.10578547442777889]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04975860384721978, -0.00020499104928089752, 0.004525822642287584, -1.7716945620114073e-06, 0.0009010251626009576, -2.47770388269714e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160287117642688, -0.013825927838565726, 0.03196782130394042]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.183012654971167, 0.10345351758118154, 0.016839094978340474, -0.15000569527543056, 0.003306745680984454, -0.10001823108980991, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4752319363150039, -0.02443871971741958, 0.10738414966299131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0495924599599955, -0.00033193226416061684, 0.004508837722616096, -1.7575791813816841e-06, 0.000898038928751594, -2.4605769412409795e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16028097486345472, -0.013995855699155773, 0.031973504704248666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.18548404123481146, 0.10343300575341878, 0.017063698402856802, -0.15000578243924914, 0.0033515004613197713, -0.10001835324725894, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48324566006924347, -0.02514691987599346, 0.10898308674691021]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04942772527288892, -0.00041023655525519585, 0.004492068490326587, -1.7432763717618052e-06, 0.0008950956067063493, -2.443148980529404e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027447508479176, -0.01416400317147756, 0.03197874167837799]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1879472608550279, 0.10341077849955624, 0.01728747384145766, -0.1500058688798323, 0.003396110153584233, -0.10001847451921646, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49125904151653366, -0.02586343908780115, 0.11058226365644613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.049264392404328394, -0.0004445450772507193, 0.004475508772017207, -1.7288116631258034e-06, 0.0008921938452892325, -2.4254391504056314e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16026762894580424, -0.014330384236153841, 0.031983538190718606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1904023835510969, 0.1033886994713745, 0.017510431261273066, -0.15000595458983532, 0.0034405767235067986, -0.10001859489177588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49927206376709743, -0.02658818971898559, 0.1121816586371489]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.049102453921380504, -0.0004415805636348532, 0.004459148396308083, -1.7142000602500772e-06, 0.0008893313984513139, -2.407451188525968e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16026044501127573, -0.014495012623688824, 0.03198789961405549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.19284947867213184, 0.10336823686666416, 0.017732579990172585, -0.15000603960783235, 0.003484901995256173, -0.10001871435921601, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5072847103179591, -0.027321084823910848, 0.11378125019612272]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04894190242069861, -0.00040925209420674807, 0.004442974577990359, -1.700359940612609e-06, 0.0008865054349874861, -2.3893488027200186e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160252931017232, -0.014657902098505156, 0.03199183117947626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.19528861520026722, 0.10335044372075877, 0.017953928651477456, -0.15000612401254956, 0.003529087636818467, -0.10001883292458877, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5152969650615643, -0.028062038153902853, 0.11538101710832856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04878273056270739, -0.00035586291810782336, 0.004426973226097425, -1.6880943444734038e-06, 0.0008837128312458869, -2.371307455198067e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602450948721056, -0.014819066599840128, 0.03199533824411692]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.19771986175401954, 0.10333597097699894, 0.018174485156528267, -0.150006207798246, 0.0035731351583073124, -0.10001895057872319, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5233088123281033, -0.028810964150623924, 0.11698093841183672]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04862493107504653, -0.00028945487519659095, 0.004411130101016184, -1.6757139286449603e-06, 0.0008809504297769052, -2.353082688446571e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16023694533078126, -0.014978519934421407, 0.03199842607016335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20014328658872746, 0.10332510564698862, 0.01839425674461783, -0.15000629095935178, 0.003617045920889742, -0.10001906731283572, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5313202369234871, -0.02956777794732276, 0.11858099341127382]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.048468496694158286, -0.00021730660020653463, 0.0043954317617912785, -1.663222115502699e-06, 0.0008782152516485842, -2.3346822505692515e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160228491907675, -0.015136275933976664, 0.032001099988741906]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20255895759272344, 0.10331782622989841, 0.018613250058649052, -0.15000637349057583, 0.003660821153721014, -0.10001918311851406, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5393312241563296, -0.030332395372301445, 0.12018116168277192]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04831342007991974, -0.0001455883418041401, 0.004379866280624439, -1.6506244807590696e-06, 0.0008755046566254421, -2.3161135668965226e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16021974465684996, -0.015292348499573696, 0.03200336542996195]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2049669422773501, 0.1033138679862704, 0.018831471244400506, -0.15000645554894895, 0.0037044619761907537, -0.10001929820039597, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5473417598495662, -0.031104732964475353, 0.12178142308918284]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.048159693692533166, -7.916487256010157e-05, 0.004364423715029095, -1.6411674626802083e-06, 0.0008728164493947907, -2.301637638216595e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16021071386473268, -0.015446751843478167, 0.03200522812821858]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20736730776636728, 0.1033127915178504, 0.01904892606269705, -0.15000653717341306, 0.0037479694230460056, -0.100019412609588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5553518303348315, -0.031884707967505664, 0.12338175777267554]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.048007309780343656, -2.1529368399892335e-05, 0.004349096365930887, -1.6324892818649363e-06, 0.0008701489371050387, -2.288183840417323e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16020140970530578, -0.01559950006060615, 0.032006693669854175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20976012078340545, 0.10331404922073026, 0.019265620004060888, -0.15000661835563406, 0.0037913444700729175, -0.10001952633492237, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5633614224375337, -0.03267223832205153, 0.12498214614486355]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047856260340763464, 2.5154057597067764e-05, 0.0043338788272767916, -1.623644420283036e-06, 0.0008675009405382368, -2.2745066875558122e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601918420540452, -0.01575060709091739, 0.03200776744376017]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.21214544763836848, 0.10331704545761965, 0.019481558397456054, -0.1500066990872712, 0.0038345880584625277, -0.1000196393652088, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5713705234565156, -0.033467242661410164, 0.12658256887981856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047706537099260676, 5.992473778770339e-05, 0.004318767867903331, -1.6146327431952826e-06, 0.0008648717677921988, -2.2606057285836942e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601820203796373, -0.01590008678717264, 0.03200845469910025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.214523354214581, 0.10332118759211503, 0.019696746506841594, -0.15000677936017673, 0.00387770111644924, -0.10001975168958674, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5793791211419874, -0.03426964030839385, 0.1281830069082024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04755813152424989, 8.28426899076737e-05, 0.004303762187710815, -1.605458110199994e-06, 0.0008622611597342448, -2.246487558695672e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601719537094368, -0.016047952939673663, 0.0320087605676766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.21689390595778058, 0.10332592625129348, 0.019911189611223668, -0.15000685916625156, 0.003920684577254598, -0.10001986329730693, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5873872036752521, -0.03507935127277763, 0.1297834414122128]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0474110348639917, 9.477318356901133e-05, 0.004288862087641491, -1.5961214965137194e-06, 0.000859669216107161, -2.232154403898749e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601616506652927, -0.016194219287675567, 0.03200869008020809]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2192571678675089, 0.10333078426620629, 0.02012489306581871, -0.1500069384975424, 0.003963539392800279, -0.10001997417781891, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.595394759652164, -0.03589629624917731, 0.13138385382139514]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047265238194566676, 9.716029825608835e-05, 0.004274069091900832, -1.5866258167803704e-06, 0.0008570963109136047, -2.2176102395773785e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16015111953823954, -0.016338899527993667, 0.03200824818364714]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22161320449103558, 0.10333537463672725, 0.02033786234367572, -0.15000701734626684, 0.004006266543043353, -0.10002008432080574, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6034017780706572, -0.03672039661528834, 0.13298422580927458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04712073247053373, 9.180741041927896e-05, 0.004259385557140274, -1.5769744889082373e-06, 0.0008545430048614926, -2.2028597365723687e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16014036836986395, -0.016482007322220493, 0.03200743975758855]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22396207991964015, 0.10333940855415552, 0.02055010305856593, -0.15000709570486315, 0.0040488670411144055, -0.10002019371621192, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6114082483215768, -0.03755157443037732, 0.1345845392906191]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04697750857209155, 8.067834856550048e-05, 0.004244814297804152, -1.5671719259900302e-06, 0.0008520099614210539, -2.1879081234785065e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16012940501839243, -0.016623556301779634, 0.032006269626890335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22630385778689716, 0.10334269498793672, 0.02076162097108167, -0.15000717356601803, 0.004091341934693161, -0.10002030235426686, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6194141601815647, -0.03838975243387168, 0.1361847764190553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04683555734514031, 6.572867562404062e-05, 0.004230358250314796, -1.5572230978801982e-06, 0.0008494978715751032, -2.172761098905231e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16011823719975704, -0.016763560069887256, 0.032004742568724154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22863860126852809, 0.10334513361349326, 0.020972421980677322, -0.15000725092269504, 0.004133692304233598, -0.10002041022551572, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6274195038067542, -0.03923485404388815, 0.1377849195847638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04669486963261854, 4.87725111308398e-05, 0.004216020191912997, -1.5471335402288695e-06, 0.0008470073908087491, -2.157424977295874e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16010687250378855, -0.0169020322003294, 0.03200286331417026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.23096637308338197, 0.10334670294970959, 0.021182512106838868, -0.1500073277681514, 0.004175919258752189, -0.10002051732082845, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.635424269726342, -0.04008680335557255, 0.13938495141204849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.046555436297077916, 3.1386724326404114e-05, 0.004201802523230933, -1.5369091271096457e-06, 0.0008445390903718153, -2.1419062545396127e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16009531839175742, -0.01703898623368797, 0.03200063654569387]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2332872354951531, 0.10334744551794267, 0.021391897462718353, -0.1500074040959531, 0.004218023929926689, -0.1000206236314152, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6434284488355283, -0.04094552513917494, 0.14098485475666991]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04641724823542268, 1.4851364661654091e-05, 0.004187707117589671, -1.5265560337321164e-06, 0.0008420934234900004, -2.1262117349273296e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600835821837258, -0.0171744356720478, 0.03199806689242857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.23560125031450982, 0.10334745166423494, 0.021600584224459176, -0.15000747989998708, 0.004260007465228015, -0.10002072914885637, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6514320323877014, -0.04181094483783783, 0.14258461270292636]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04628029638713441, 1.2292584547088654e-07, 0.004173735234816468, -1.5160806800711904e-06, 0.0008396707060265139, -2.1103488235878295e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600716710434631, -0.017308393973257882, 0.031995158925128726]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.23790847890137787, 0.10334684343805581, 0.02180857859912628, -0.1500075551744723, 0.004301871020738212, -0.1000208338650932, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6594350119860194, -0.04268298856511886, 0.14418420856053016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.046144571737360925, -1.2164523582535762e-05, 0.004159887493342035, -1.5054897046058864e-06, 0.0008372711102039476, -2.0943247363514818e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600595919663592, -0.01744087454562057, 0.03199191715207618]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24020898216718775, 0.10334575962781317, 0.022015886793699892, -0.15000762991395247, 0.004343615754205344, -0.10002093777245358, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.66743737957467, -0.043561583102290906, 0.14578362586136095]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04601006531619754, -2.167620485271188e-05, 0.0041461638914723, -1.4947896030987316e-06, 0.0008348946693426383, -2.0781472075761348e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16004735177301213, -0.017571890743440868, 0.031988346016616064]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24250282057694758, 0.10334434274513316, 0.022222514987051262, -0.15000770411331082, 0.004385242818765281, -0.10002104086364545, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6754391274301076, -0.04444665589547332, 0.14738284835618237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.045876768195196586, -2.833765360031708e-05, 0.004132563867027421, -1.4839871668655537e-06, 0.000832541291198747, -2.061823837582297e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600349571087517, -0.01770145586364828, 0.031984449896428395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24479005415104668, 0.10334272845097672, 0.02242846930624998, -0.15000777776775132, 0.004426753357632958, -0.10002114313176848, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6834402481524985, -0.045338135052637646, 0.1489818600113899]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04574467148198211, -3.2285883128606505e-05, 0.00411908638397435, -1.4730888100131256e-06, 0.000830210777353534, -2.0453624605102816e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600224144478189, -0.01782958314328649, 0.03198023310415052]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24707074246673555, 0.10334103764578095, 0.022633755807996526, -0.15000785087280727, 0.004468148499941095, -0.1000212445703161, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6914407346575107, -0.0462359493405216, 0.1505806450058359]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04561376631377729, -3.381610391538624e-05, 0.00410573003493091, -1.4621011192002264e-06, 0.0008279028461627341, -2.0287709524375374e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16000973010024377, -0.01795628575767917, 0.03197569988891966]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24934494465932536, 0.10333937121588066, 0.022838380465478522, -0.1500079234220059, 0.004509429357793151, -0.10002134516998495, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.699440580168477, -0.047140028181256774, 0.15217918772758207]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.045484043851796226, -3.3328598005766444e-05, 0.004092493149639925, -1.4509839722865077e-06, 0.0008256171570411013, -2.011993377127638e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1599969102193264, -0.018081576814703418, 0.03197085443492361]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.25161271942632224, 0.10333780724678863, 0.023042349160843065, -0.15000799529489925, 0.004550597024556257, -0.10002144476505512, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7074397782084517, -0.04805030163861886, 0.15377747276273857]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04535549533993808, -3.127938184055098e-05, 0.0040793739072908265, -1.4374578672876962e-06, 0.0008233533352621341, -1.991901403365508e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998396079949395, -0.018205469147241714, 0.03196570070312983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2538741250250015, 0.10333640037958398, 0.023245667681798775, -0.15000806649093595, 0.004591652574109741, -0.1000215433532149, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7154383225950193, -0.04896670042382532, 0.15537548489993488]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04522811197358551, -2.8137344093005064e-05, 0.004066370419114236, -1.4239207338742502e-06, 0.0008211109910696841, -1.9717631957763895e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15997088773135104, -0.018327975704129137, 0.031960242743926476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.25612921927169197, 0.10333518291572864, 0.023448341722547655, -0.15000813701028293, 0.004632597061055798, -0.10002164093350979, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7234362074326022, -0.049889155895411895, 0.15697320912989823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04510188493380949, -2.4349277106919086e-05, 0.004053480814977581, -1.4103869392300339e-06, 0.0008188897389211255, -1.9516058977264347e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15995769675165808, -0.018449109431731614, 0.0319544845992672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.25837805954158516, 0.10333416722997266, 0.023650376888045523, -0.15000820685342905, 0.004673431521673097, -0.10002173750536082, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7314334271048738, -0.050817600056630746, 0.15857063064318155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044976805397864146, -2.031371511964554e-05, 0.004040703309957356, -1.3968629223907938e-06, 0.0008166892123459742, -1.9314370205954102e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15994439344543218, -0.018568883224377032, 0.03194843026566624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.26062070276972954, 0.10333334905306475, 0.02385177870073128, -0.15000827598790845, 0.004714156975416838, -0.10002183302315162, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7394299762674554, -0.05175196554883487, 0.16016773482497235]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04485286456288734, -1.6363538158197644e-05, 0.004028036253715111, -1.382689587868713e-06, 0.0008145090748748352, -1.9103558159788117e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15993098325163188, -0.018687309844082418, 0.03194208363581572]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2628572054505867, 0.10333271121640945, 0.02405255260853905, -0.15000834440005673, 0.004754774426712563, -0.10002192746663706, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7474258498417211, -0.052692185648650185, 0.16176450725297814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04473005361714357, -1.2756733106001308e-05, 0.004015478156155436, -1.3682429654596555e-06, 0.0008123490259144914, -1.8888697087540805e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15991747148531305, -0.018804401996306248, 0.031935448560115626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.26508762363726895, 0.10333222750617385, 0.024252703993492972, -0.1500084120939234, 0.0047952848668825765, -0.10002202083984314, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7554210430084136, -0.0536381942661282, 0.16336093369605836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04460836373364514, -9.674204712095643e-06, 0.004003027699078406, -1.353877333509523e-06, 0.0008102088034002794, -1.8674641215638693e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15990386333384968, -0.018920172349560307, 0.031928528861604494]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2673120129414288, 0.10333186633945665, 0.024452238180277724, -0.1500084790738226, 0.004835689276064566, -0.10002211314722456, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.76341555120095, -0.054589925941318555, 0.16495700011168518]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04448778608319669, -7.223334344032695e-06, 0.0039906837356950475, -1.3395979834725042e-06, 0.000808088183639793, -1.8461476282723448e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15989016385072644, -0.019034633503807106, 0.031921328312536405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.26953042853347003, 0.10333159404634065, 0.02465116044417969, -0.15000854534428604, 0.004875988624988173, -0.10002220439355264, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7714093700989456, -0.055547315840243486, 0.1665526926430417]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044368311840824744, -5.445862320050276e-06, 0.003978445278039363, -1.3254092689671988e-06, 0.0008059869784721276, -1.824926561473613e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15987637795991314, -0.019147797978498554, 0.031913850627130376]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2717429251429817, 0.10333137761394057, 0.024849476017975516, -0.15000861091005177, 0.004916183876515213, -0.10002229458393049, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7794024956219943, -0.056510299750678276, 0.16814799761606405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044249932190233085, -4.32864800172508e-06, 0.003966311475916454, -1.311315314905916e-06, 0.0008039050305408062, -1.8038075569355152e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15986251046097405, -0.0192596782086958, 0.03190609946044691]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2739495570593706, 0.10333118681560001, 0.025047190097506257, -0.15000867577605453, 0.004956275986885084, -0.10002238372376349, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7873949239236486, -0.05747881407789648, 0.1697429015365352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044132638327777016, -3.815966811214887e-06, 0.003954281590614795, -1.2973200551719209e-06, 0.0008018422073974141, -1.7827966601206466e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15984856603308634, -0.019370286544363978, 0.0318980784094228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.27615037813268956, 0.10333099570671443, 0.025244307845820144, -0.15000873994741984, 0.004996265906639071, -0.10002247181875316, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.795386651385558, -0.05845279584043266, 0.17133739108726143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04401642146637921, -3.822177711434511e-06, 0.003942354966277703, -1.2834273063283703e-06, 0.0007997983950797364, -1.7618997935989611e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15983454923818607, -0.01947963525072365, 0.03188979101452433]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2783454417746549, 0.10333078351608817, 0.025440834395887547, -0.15000880342944778, 0.005036154581224447, -0.10002255887489248, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.803377674611739, -0.059432182665875015, 0.1729314531253334]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04390127283930712, -4.243812525363838e-06, 0.003930531001348092, -1.2696405585411844e-06, 0.0007977734917075222, -1.7411227861338585e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15982046452362142, -0.01958773650884707, 0.031881240761439625]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.280534800959843, 0.1033305349972854, 0.025636774851990726, -0.15000886622760784, 0.0050759429513011975, -0.10002264489845251, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8113679904229674, -0.06041691278668432, 0.17452507467946504]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043787183703761466, -4.9703760554135155e-06, 0.003918809122063529, -1.2559632014907505e-06, 0.0007957674015350019, -1.7204712008525275e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15980631622456604, -0.019694602416186122, 0.031872431082632845]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.28271850822704814, 0.10333024032814164, 0.025832134289960413, -0.1500089283475258, 0.00511563195279003, -0.10002272989596761, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8193575958512821, -0.06140692503603015, 0.17611824294739997]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04367414534410213, -5.893382875004663e-06, 0.003907188759393764, -1.2423983592222752e-06, 0.0007937800297766446, -1.6999503019726594e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15979210856629433, -0.019800244986916744, 0.03186336535869875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2848966156807819, 0.10332989465929975, 0.02602691775647827, -0.1500089897949776, 0.0051552225167106926, -0.10002281387423123, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.827346488134601, -0.0624021588436359, 0.17771094529337791]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04356214907467464, -6.9133768380495665e-06, 0.0038956693303571015, -1.2289490358422545e-06, 0.0007918112784132601, -1.6795652724324474e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597778456663768, -0.01990467615211503, 0.03185404691955871]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.28706917499289303, 0.10332949741574912, 0.026221130267684387, -0.1500090505758676, 0.005194715568864285, -0.10002289684027461, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8353346647114424, -0.06340255423162452, 0.17930316924565265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0434511862422227, -7.944871012459946e-06, 0.0038842502241223965, -1.2156178000953194e-06, 0.0007898610430718366, -1.6593208675950465e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15976353153682643, -0.020007907759772434, 0.0318444790454949]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.28923623740428234, 0.10332905145066051, 0.02641477680733089, -0.15000911069623774, 0.005234112029413506, -0.10002297880136972, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8433221232157535, -0.0644080518103614, 0.18089490249405826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043341248227785976, -8.919301772053437e-06, 0.003872930792930072, -1.2024074025364023e-06, 0.0007879292109844364, -1.6392219020593067e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15974917008622308, -0.020109951574737304, 0.031834664968112485]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.29139785372669147, 0.10332856214027344, 0.02660786232470734, -0.15000917016223753, 0.0052734128124114115, -0.10002305976500296, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8513088614718439, -0.06541859277428819, 0.1824861328876172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04323232644818272, -9.786207741316617e-06, 0.00386171034752901, -1.1893199955852009e-06, 0.000786015659958096, -1.6192726648206346e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15973476512180762, -0.02021081927853593, 0.03182460787117888]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.293554074344547, 0.10332803649415295, 0.026800391732533846, -0.15000922898012845, 0.0053126188253227345, -0.10002313973887929, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8592948774894236, -0.06643411889774825, 0.18407684843218974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04312441235711089, -1.0512922409870303e-05, 0.0038505881565301173, -1.1763578184363522e-06, 0.0007841202582264676, -1.599477526548888e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15972032035159217, -0.020310522469201408, 0.03181431089145096]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2957049492168433, 0.10332748233859759, 0.026992369904983667, -0.15000928715626657, 0.00535173096857404, -0.10002321873090829, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.867280169458746, -0.06745457253080042, 0.18566703728816195]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043017497445926825, -1.1083111107229559e-05, 0.0038395634489964, -1.1635227624855766e-06, 0.0007822428650261137, -1.5798405801472918e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15970583938644847, -0.02040907266104334, 0.0318037771194439]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.297850527879053, 0.10332690761392402, 0.027183801675955917, -0.1500093446970918, 0.005390750135159585, -0.10002329674918031, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8752647357458557, -0.06847989659502164, 0.18725668776817084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04291157324419298, -1.1494493471360395e-05, 0.0038286354194450307, -1.1508165042166715e-06, 0.0007803833317108914, -1.560365440380827e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1596913257421954, -0.02050648128442441, 0.03179300960017787]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.299990859445052, 0.10332631981005735, 0.02737469183767937, -0.1500094016091248, 0.005429677210321284, -0.10002337380196107, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8832485748879394, -0.06951003457929926, 0.18884578833486626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.042806631319979874, -1.1756077333398683e-05, 0.003817803234469083, -1.1382406602047044e-06, 0.0007785415032339804, -1.541055614946231e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1596767828416742, -0.020602759685552495, 0.03178201133390833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3021259926090574, 0.1033257255502829, 0.027565045139689, -0.1500094578989542, 0.005468513071312054, -0.10002344989769207, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8912316855887791, -0.07054493053561418, 0.19043432759870804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04270266328010881, -1.1885195489109694e-05, 0.0038070660401925915, -1.125796588031035e-06, 0.0007767172198153971, -1.5219146202139667e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15966221401679462, -0.02069791912629838, 0.031770785276835516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.30425597564757445, 0.10332513032080516, 0.02775486628818479, -0.15000951357322692, 0.0055072585872446645, -0.10002352504496832, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8992140667143067, -0.07158452907481427, 0.19202229431579765]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.042599660770340914, -1.1904589554583705e-05, 0.003796422969915852, -1.113485454153704e-06, 0.0007749103186522053, -1.502945524915729e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1596476225105518, -0.02079197078400172, 0.031759334341792095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3063808564213513, 0.10332453833425918, 0.027944159945754, -0.15000956863863843, 0.005545914619021985, -0.10002359925253017, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9071957172882569, -0.07262877536238123, 0.1936096773857436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.042497615475537376, -1.1839730919630454e-05, 0.003785873151384124, -1.1013082301515212e-06, 0.0007731206355464007, -1.4841512369652657e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15963301147900363, -0.02088492575133897, 0.03174766139891916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3085006823773436, 0.10332395250861434, 0.028132930731417975, -0.1500096231019266, 0.005584482019339736, -0.10002367252924202, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9151766364879175, -0.07367761511419113, 0.19519646584956013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04239651911984614, -1.1716512896918848e-05, 0.0037754157132795143, -1.0892657633621812e-06, 0.0007713480063550346, -1.4655342371064153e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15961838399321296, -0.020976795036197902, 0.03173576927633021]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3106073020659039, 0.10332337854148974, 0.028320482265820502, -0.15000966870639382, 0.0056228111617659575, -0.10002373461224327, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9231094530516137, -0.07472145554500015, 0.19677115644984025]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04213239377120598, -1.1479342492114194e-05, 0.003751030688050521, -9.120893446924336e-07, 0.000766582848524428, -1.2416600250398667e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15865633127392514, -0.020876808616180447, 0.031493812005602514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3126098952457772, 0.10332284641696683, 0.028498839598930518, -0.1500100817900876, 0.0056592446112130245, -0.10002456041684918, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9305957187118021, -0.07569602507676208, 0.19824826232288928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.040051863597465216, -1.0642490458097362e-05, 0.003567146662200323, -8.261673875510393e-06, 0.0007286689889413484, -1.6516092118097312e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1497253132037683, -0.019491390635238734, 0.029542117460980476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31443926874850425, 0.10332237757976635, 0.028661836022275976, -0.15001099483960964, 0.005692523725398532, -0.10002625734702274, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9373928210073526, -0.07656971098201253, 0.1995806815535737]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03658747005454047, -9.376744009706101e-06, 0.003259928466909189, -1.8260990441132797e-05, 0.0006655822837101507, -3.393860347107556e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13594204591100795, -0.01747371810500881, 0.02664838461368838]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31606662275376346, 0.10332198661734378, 0.028806880545416913, -0.15001257687774291, 0.005722125750397684, -0.10002894925667692, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9434149581715543, -0.07733494011630161, 0.20075404313385897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03254708010518427, -7.819248451635785e-06, 0.0029008904628187553, -3.164076266573587e-05, 0.0005920404999830507, -5.3838193083670426e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12044274328403481, -0.015304582685781595, 0.02346723160570544]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3174911365978103, 0.10332168483362031, 0.028933877029759927, -0.15001470981484208, 0.005748036844570836, -0.10003245257333418, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9486738710338738, -0.07799701600317752, 0.20177314556168108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028490276880937, -6.03567446938783e-06, 0.002539929686860283, -4.2658741983145474e-05, 0.0005182218834630396, -7.006633314509806e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1051782572463891, -0.013241517737518204, 0.020382048556442097]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31872650927865204, 0.10332148004915269, 0.02904402967296915, -0.15001696685470292, 0.005770507000930261, -0.10003629158150958, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9532290314546588, -0.07856656533767781, 0.20265165905603091]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02470745361683458, -4.095689352428911e-06, 0.0022030528641844957, -4.514079721687587e-05, 0.00044940312718850964, -7.678016350787341e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0911032084157001, -0.0113909866900057, 0.017570269886996635]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31979223350183095, 0.10332137362159707, 0.02913906505109426, -0.1500172425565492, 0.005789891310918553, -0.10003703400972054, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9571572315169582, -0.0790554597448708, 0.2034061068439106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021314484463578184, -2.128551112394285e-06, 0.001900707562502168, -5.514036925250084e-06, 0.00038768619976583066, -1.4848564219303214e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07856400124598857, -0.009777888143859867, 0.015088955757593765]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32070891599535056, 0.10332134744762694, 0.02922081330264332, -0.1500174527708254, 0.005806564858331019, -0.10003757044046865, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9605370255841236, -0.07947497749144482, 0.20405289807664298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01833364987039281, -5.234794025623375e-07, 0.001634965030981182, -4.204285523890006e-06, 0.00033347094824932866, -1.0728614962244765e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06759588134330642, -0.008390354931480395, 0.012935824654647422]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3214961207886183, 0.10332137910660898, 0.029291014768987076, -0.1500177379551962, 0.005820883597945364, -0.10003820291117005, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.963441666044053, -0.0798351264558084, 0.20460704949494996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015744095865354316, 6.331796406987266e-07, 0.0014040293268751777, -5.703687416282992e-06, 0.00028637479228689575, -1.2649414027945605e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05809280919858905, -0.007202979287271632, 0.011083028366139438]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32217152815939015, 0.10332144881363478, 0.029351244011058337, -0.1500180868576028, 0.005833169130580514, -0.10003888891608088, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9659365901093725, -0.08014452429683226, 0.20508178811557237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013508147415436971, 1.394140515977055e-06, 0.0012045848414252306, -6.978048131656092e-06, 0.00024571065270300254, -1.3720098216709745e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.049898481306390526, -0.006187956820477323, 0.009494772412448255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.322750727622933, 0.10332154125683989, 0.02940289054596245, -0.1500184384201689, 0.005843704981633201, -0.10003956220902593, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9680790465613092, -0.0804105032920081, 0.20548855407438218]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011583989270857404, 1.848864102105997e-06, 0.0010329306980822808, -7.031251322381427e-06, 0.00021071702105373175, -1.3465858900937968e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04284912903873378, -0.0053195799035167905, 0.00813531917619604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32324728989494617, 0.1033216452919178, 0.02944716466561267, -0.1500188299406522, 0.005852737936282021, -0.10004034714895085, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9699186205235781, -0.0806392833780997, 0.20583716093998775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009931245440262929, 2.0807015581975825e-06, 0.0008854823930044233, -7.830409665420957e-06, 0.0001806590929764091, -1.5698798498486524e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03679147924537868, -0.004575601721831806, 0.006972137312110954]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3236729481301363, 0.10332175335745515, 0.0294851132091579, -0.1500192406217717, 0.005860481351922626, -0.10004117837040108, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9714980488411608, -0.08083614579002193, 0.20613599757900758]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008513164703802359, 2.1613107470021494e-06, 0.0007589708709046055, -8.213622390221093e-06, 0.00015486831281211555, -1.6624429004414887e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03158856635165154, -0.003937248238444746, 0.00597673278039645]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3240378081386516, 0.10332186056774079, 0.029517638054237686, -0.15001967678864575, 0.005867118989848188, -0.10004196194888963, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9728540853626501, -0.08100558657493173, 0.20639222786283906]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0072972001703054444, 2.1442057127400096e-06, 0.0006504969015957227, -8.723337481520962e-06, 0.00013275275851123815, -1.5671569771085008e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027120730429785765, -0.0033888156981960547, 0.005124605676629434]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32435055461301737, 0.10332196390654821, 0.029545514354327704, -0.15002014436279623, 0.005872808769887851, -0.1000426880018997, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9740183104427782, -0.08115144492470755, 0.20661197046205118]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006254929487316511, 2.0667761485109546e-06, 0.000557526001800362, -9.351483009625949e-06, 0.00011379560079326082, -1.4521060201099538e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02328450160256351, -0.0029171669955164606, 0.004394851984242261]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32461864112407124, 0.1033220616391923, 0.02956940740601082, -0.15002055313455698, 0.005877686227451204, -0.10004334078103809, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9750178466632097, -0.08127700778558342, 0.20680045364637603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005361730221077603, 1.9546528818555513e-06, 0.000477861033662324, -8.175435215123442e-06, 9.754915126705303e-05, -1.305558276794181e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.019990724408628962, -0.002511257217517263, 0.003769663686497212]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32484845861298506, 0.10332215278860385, 0.029589887631756163, -0.15002095710621496, 0.005881867578496745, -0.10004401668926688, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9758759891374625, -0.08138509608602612, 0.20696214859478393]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004596349778275921, 1.822988230838852e-06, 0.00040960451490685374, -8.079433159526202e-06, 8.362702091082998e-05, -1.3518164575795766e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017162849485057044, -0.002161766008854222, 0.0032338989681580093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3250454837649755, 0.10332223693673287, 0.029607443805142464, -0.15002147062836285, 0.005885452417907611, -0.10004483722416617, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9766127451390855, -0.08147813501145389, 0.2071008815247186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003940503039808336, 1.6829625803326659e-06, 0.0003511234677260382, -1.0270442957594471e-05, 7.169678821730668e-05, -1.6410697985898636e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014735120032458051, -0.0018607785085553367, 0.002774658598693349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32521440922120926, 0.10332231416827514, 0.029622494684762593, -0.15002211021273992, 0.005888526086572418, -0.10004575402998754, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9772452898530821, -0.08155821117836452, 0.20721992697227853]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0033785091246751847, 1.5446308455821939e-06, 0.00030101759240258103, -1.2791687541520382e-05, 6.147337329615691e-05, -1.83361164273692e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012650894279933177, -0.0016015233382128628, 0.0023809089511987037]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32535925476056105, 0.10332238490610468, 0.029635398937231664, -0.15002286362761322, 0.0058911616924520556, -0.10004675938412434, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9777883692474848, -0.08162712168540125, 0.20732208910195418]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002896910787036039, 1.4147565907436082e-06, 0.00025808504938143483, -1.5068297465661992e-05, 5.271211759275058e-05, -2.0107082735898254e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010861587888052712, -0.0013782101407345034, 0.0020432425935131226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32548346282801216, 0.10332244974404842, 0.029646463663863906, -0.1500237412231271, 0.005893421847063744, -0.10004797785332699, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9782546479731619, -0.0816864156426958, 0.20740977113148507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0" + }, + "execution_count": 9, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "reset_giskard()\n", + "# Define a world feature as a point at the origin of map\n", + "world_feature = PointStamped()\n", + "world_feature.header.frame_id = 'map'\n", + "\n", + "# Define a robot feature as a point at the origin of the right gripper tool frame\n", + "robot_feature = PointStamped()\n", + "robot_feature.header.frame_id = 'r_gripper_tool_frame'\n", + "\n", + "# use the distance feature function to constrain the distance between the features to be between 2m and 2.5m\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction',\n", + " root_link='map',\n", + " tip_link='r_gripper_tool_frame',\n", + " world_feature=world_feature,\n", + " robot_feature=robot_feature,\n", + " lower_limit=2,\n", + " upper_limit=2.5)\n", + "\n", + "gs.add_default_end_motion_conditions()\n", + "gs.execute()" + ], "metadata": { "collapsed": false, "pycharm": { @@ -399,19 +443,19 @@ }, { "cell_type": "code", - "execution_count": 13, + "execution_count": 8, "outputs": [ { "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21405007691131805, 0.04188077202253695, -0.36111200186744086, 0.0, -1.004733782777196, 0.48736018039340784, -0.9487478790977968, -1.392377789199791, -2.3294660300946273, -0.4548700950082352, 0.11575516878897756, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8799811840759517, 0.01162710877305629, 1.7383064794236054, -2.0301529420491278, -1.4865011013621898, -0.10361483364873676, 0.2211701008918833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.6074844303731284, -0.7273603211352454, 0.013367732054879625]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21402839575309973, 0.04938077106361105, -0.34949996513697584, 0.0, -1.0011652823484956, 0.49111018039268434, -0.9524978790974004, -1.3961277892001054, -2.333216030094612, -0.45713842380556585, 0.11200516878892969, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762311840758314, 0.015377108772934429, 1.7420564794229674, -2.0280055433823345, -1.4902511013621702, -0.1039161082788246, 0.2174201008919637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.6068674451073257, -0.7279932343850507, 0.012742732054806746]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0004336231643662778, 0.14999998082148203, 0.23224073460930056, 0.0, 0.07137000857401192, 0.07499999999988681, -0.07499999999997856, -0.07499999999998418, -0.07499999999969256, -0.045366575946612815, -0.07499999999996639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999998275, 0.07499999999996271, 0.07499999999992144, 0.042947973335866495, -0.07499999999960884, -0.006025492601756743, -0.07499999999839187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012339705316053159, -0.012658264996105478, -0.01250000000003011]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21401091393802746, 0.06766867523493247, -0.3294428440896994, 0.0, -0.9956442654321376, 0.502355417572033, -0.9637478790973795, -1.4073777892001187, -2.3418636346680195, -0.46002599815828366, 0.10075516878893027, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8649811840758328, 0.026627108772930754, 1.7533064794229591, -2.0211558895334654, -1.4979906583964677, -0.10650015306691515, 0.21178046007110707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.605012932428605, -0.7298885002567542, 0.01086773205480565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003496363014453439, 0.36575808342642835, 0.40114242094552827, 0.0, 0.1104203383271599, 0.22490474358697282, -0.2249999999999549, -0.22499999999996995, -0.17295209146814824, -0.05775148705435569, -0.22499999999993303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2249999999999659, 0.22499999999992545, 0.22499999999984277, 0.1369930769773847, -0.15479114068595232, -0.05168089576181112, -0.11279281641713287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03709025357441372, -0.03790531743406946, -0.037500000000022335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21399824442986745, 0.09312164414909241, -0.3051588885308801, 0.0, -0.9900963067571215, 0.5190262759670525, -0.9843706590441835, -1.4280027891915854, -2.3532703363165997, -0.4622819430092069, 0.08027458571902919, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8445032906656067, 0.046876564013675945, 1.7697961234994897, -2.0072100977975302, -1.507338359997853, -0.11211891265943025, 0.20725821734621477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.601601068542692, -0.7333514465709071, 0.0074302320501798726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0002533901631998896, 0.5090593782831986, 0.48567911117638723, 0.0, 0.11095917350032275, 0.3334171679003927, -0.4124555989360815, -0.4124999998293359, -0.22813403297160093, -0.04511889701846443, -0.4096116613980215, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.409557868204524, 0.40498910481490374, 0.3297928815306118, 0.2789158347187026, -0.18695403202770272, -0.1123751918503019, -0.09044485449784613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06823727771826336, -0.06925892628305809, -0.06875000009251553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139877768117349, 0.12248595152345859, -0.2792862844929731, 0.0, -0.9853782612343235, 0.5388035036973994, -1.012591094452177, -1.4563119322099296, -2.3656214652961167, -0.4637487071492661, 0.052293116171255406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8171106330909736, 0.07405882941916246, 1.7884271960872264, -1.9853347116067976, -1.5161648961629113, -0.12078305181055067, 0.20605355864698724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5968742549350132, -0.7381037652994843, 0.002690648713208975]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00020935236265099495, 0.5872861474873238, 0.5174520807581398, 0.0, 0.0943609104559585, 0.3955445546069373, -0.5644087081598685, -0.5661828603668827, -0.24702257959034035, -0.029335282801183842, -0.5596293909554757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5478531514926603, 0.5436453081097303, 0.37262145175473604, 0.43750772381465186, -0.17653072330116545, -0.17328278302240852, -0.024093173984550506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09453627215357363, -0.09504637457154319, -0.09479166673941794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21397802435603058, 0.15380762144525748, -0.25310087122878755, 0.0, -0.9818441002320552, 0.5599935383483494, -1.046980193862732, -1.49071613077541, -2.377858697666331, -0.4648162929822095, 0.01822707172262443, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.785720703700884, 0.10625365067461987, 1.8069219205748044, -1.9563299173892552, -1.523260762684021, -0.13211747957535364, 0.2093408053762992, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5911984996943036, -0.7438780183083025, -0.0030728878835797222]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0001950491140864607, 0.6264333984359775, 0.5237082652837104, 0.0, 0.0706832200453656, 0.4238006930189997, -0.687781988211096, -0.6880839713096081, -0.24474464740429208, -0.02135171665886833, -0.6813208889726194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.6277985878017921, 0.6438964251091479, 0.3698944897515589, 0.5800958843508487, -0.1419173304221958, -0.22668855529605958, 0.06574493458623955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.11351510481419054, -0.11548506017636315, -0.11527073193577393]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21396844228792683, 0.18558776993065917, -0.22710523577307629, 0.0, -0.9803929406200691, 0.5816833798156663, -1.0864125530418198, -1.5299378943534712, -2.389398472202879, -0.46601206345656865, -0.02066490135687067, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753523702431539, 0.14162037160127605, 1.8239729357636572, -1.9213747608853842, -1.528230776554355, -0.14561125569674876, 0.21746668728306562, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5851861066509967, -0.7504561062613002, -0.009235377740604352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00019164136207500801, 0.6356029697080336, 0.5199127091142255, 0.0, 0.029023192239720164, 0.43379682934633695, -0.7886471835817574, -0.7844352715612226, -0.23079549073095726, -0.023915409487183178, -0.7778394615899018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.6439400253868981, 0.7073344185331236, 0.34102030377705606, 0.6991031300774188, -0.09940027740667923, -0.2698755224279023, 0.16251763813532838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1202478608661397, -0.1315617590599544, -0.12324979713214648]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21395857080998235, 0.21684550491193783, -0.20143950516724243, 0.0, -0.9816867740571443, 0.6034240713205168, -1.1299584403861185, -1.572951694862709, -2.4001053203132714, -0.46798041613012126, -0.06343828223169613, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7224282583502917, 0.17835791249750033, 1.8389361854496946, -1.881474876166441, -1.5313409283697756, -0.16080054771325827, 0.23011195510298352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5794561143327635, -0.7576766728835327, -0.015171820856739151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00019742955888989508, 0.6251546996255728, 0.513314612116677, 0.0, -0.025876668741504273, 0.4348138300970095, -0.870917746885973, -0.8602760101847542, -0.21413696220785153, -0.03936705347105192, -0.8554676174965092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.6219088816249494, 0.7347508179244852, 0.2992649937207499, 0.7979976943788614, -0.06220303630841271, -0.30378584033019007, 0.2529053563983581, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.114599846364666, -0.1444113324446493, -0.1187288623285303]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139484132138488, 0.24684083020161507, -0.17609690972439307, 0.0, -0.9858794785686925, 0.6248616432386986, -1.1767951502615592, -1.6187744983143428, -2.410278280300332, -0.4715363713215314, -0.1093602727268847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6936153595555632, 0.21526890927503223, 1.851749371384, -1.8376374767776857, -1.5328497732157655, -0.17735993379142004, 0.2464317833395671, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5746349678776295, -0.7654259398241374, -0.02025721723346848]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00020315192267065572, 0.5999065057935448, 0.5068519088569873, 0.0, -0.08385409023096471, 0.42875143836363594, -0.9367341975088141, -0.9164560690326777, -0.203459199741212, -0.07111910382820372, -0.9184398099037714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5762579758945691, 0.7382199355506377, 0.2562637186861111, 0.8767479877751052, -0.030176896919796414, -0.33118772156323517, 0.32639656473167206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09642292910267965, -0.15498533881209364, -0.10170792752491885]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21393945768201375, 0.2751899760926101, -0.15102048413825206, 0.0, -0.9924345641541855, 0.6433835195064347, -1.226195642834585, -1.6663953054822753, -2.419027079696625, -0.4773992110967462, -0.15769574024147434, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6675588755981103, 0.25161570765851016, 1.8626080903300444, -1.7909626138931913, -1.5329583692274078, -0.19501229595158184, 0.26526197977983784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5709055129095209, -0.7736155380082226, -0.023866566877198982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00017911063670103568, 0.5669829178199, 0.5015285117228202, 0.0, -0.1311017117098605, 0.37043752535472024, -0.9880098514605158, -0.9524161433586481, -0.1749759879258602, -0.11725679550429555, -0.966709350291793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5211296791490558, 0.7269359676695591, 0.2171743789208871, 0.933497257689888, -0.0021719202328458476, -0.35304724320323616, 0.37660392880541504, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.074589099362174, -0.16379196368170296, -0.07218699272136953]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21393163484573074, 0.3019405327867023, -0.12614019254342373, 0.0, -1.0001417842267126, 0.6563727550087424, -1.2761956678898574, -1.7148804342151156, -2.425101802163615, -0.4863551745846885, -0.20769574024175413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.644140395956616, 0.2869140583740125, 1.8717787276891364, -1.7424381900071182, -1.5317902816703632, -0.21351291963175456, 0.2852343734515358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5678308673883008, -0.7821612920847926, -0.02537486977336057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00015645672566030807, 0.5350111338818441, 0.4976058318965663, 0.0, -0.15414440145054073, 0.25978471004615394, -1.000000501105448, -0.9697025746568062, -0.12149444933979288, -0.1791192697588464, -1.000000000005596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.46836959282988416, 0.7059670143100475, 0.18341274718184103, 0.9704884777214632, 0.023361751140889977, -0.3700124736034544, 0.3994478734339595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06149291042440318, -0.17091508153139914, -0.03016605791782337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21392428807420777, 0.3274065255250102, -0.10138570163291992, 0.0, -1.0076088117800528, 0.6620315557307538, -1.3261956929444743, -1.7632567293905932, -2.4275329085529544, -0.498819747645085, -0.2576957402465617, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.622918922296096, 0.32075450546047596, 1.8795969919878763, -1.692969490456383, -1.5293137461980844, -0.23266435174468078, 0.3048269130304959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5650538381252062, -0.7909918277271243, -0.024849747434561812]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00014693543045949433, 0.5093198547661579, 0.4950898182100763, 0.0, -0.1493405510668045, 0.11317601444022843, -1.0000005010923365, -0.9675259035095521, -0.04862212778679051, -0.24929146120792955, -1.0000000000961522, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4244294732104016, 0.676808941729269, 0.15636528597479976, 0.9893739910147035, 0.04953070944557823, -0.38302864225852423, 0.3918507915792028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.055540585261894745, -0.17661071284663327, 0.010502446775975172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21391694797866068, 0.35215643096103505, -0.07668975046886739, 0.0, -1.013557954009221, 0.6594337812627501, -1.37619571799973, -1.8109910506997415, -2.4254736145925144, -0.5147523332138069, -0.30769574024655544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6036436718074583, 0.35271137033029476, 1.8866082902618366, -1.643665393088377, -1.5251930821727566, -0.25239718306665804, 0.3223596927149609, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5624988499823724, -0.7999972782860758, -0.022782366697704184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00014680191094191595, 0.49499810872049677, 0.49391902328105064, 0.0, -0.11898284458336604, -0.05195548936007299, -1.000000501105113, -0.9546864261829683, 0.04118587920879917, -0.3186517113744366, -0.9999999999998745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38550500977275426, 0.6391372973963756, 0.14022596547920665, 0.9860819473601208, 0.08241328050655437, -0.3946566264395454, 0.35065559368929977, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.051099762856676605, -0.18010901117902983, 0.04134761473715254]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21390937851581235, 0.37678934480111875, -0.0519908533606013, 0.0, -1.0175438792060088, 0.6479326038266131, -1.4261957430549717, -1.8576788920611815, -2.4179288523576505, -0.5336362017647442, -0.3576957402382077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.586111805848065, 0.38267592473792694, 1.893699779229268, -1.5962533684513525, -1.5186516722194912, -0.2729355740088597, 0.3363025256254184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5602780353678474, -0.8085559116039884, -0.019750660472524627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00015138925696674824, 0.4926582768016743, 0.4939779421653217, 0.0, -0.07971850393575505, -0.23002354872273878, -1.0000005011048325, -0.9337568272288015, 0.15089524469727406, -0.3776773710187483, -0.9999999998330448, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3506373191878672, 0.5992910881526433, 0.14182977934862995, 0.948240492740489, 0.13082819906530938, -0.4107678188440336, 0.2788566582091495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044416292290499086, -0.17117266635825143, 0.060634124503591125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21390348515233687, 0.4013605571032425, -0.027240002396329798, 0.0, -1.0195495715612344, 0.6278724453736115, -1.4761957681102162, -1.9033812020400194, -2.4043279951571157, -0.5547897566566473, -0.4070369956816421, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5704403930796766, 0.409064963498223, 1.9007612389564281, -1.5533367474201625, -1.5095123328669755, -0.29387190868867213, 0.3448277078512635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5585795168429903, -0.816044491507389, -0.016338431616452126]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011786726950953425, 0.4914242460424742, 0.49501701928543007, 0.0, -0.04011384710451425, -0.4012031690600304, -1.000000501104892, -0.9140461995767553, 0.27201714401069454, -0.4230710978380612, -0.9868251088686868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3134282553677689, 0.5277807752059213, 0.14122919454320257, 0.8583324206237984, 0.18278678705031426, -0.41872669359624815, 0.1705036445169017, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03397037049714163, -0.14977159806801144, 0.06824457712145003]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139008002843461, 0.42587391948905007, -0.002383756091800287, 0.0, -1.019030222831308, 0.6002599125934656, -1.5247297433700846, -1.9486567690694414, -2.384910439932968, -0.578385857751574, -0.4554497542851375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569053119813665, 0.42986372792443556, 1.9076374125697164, -1.5169793925806894, -1.4978489260561323, -0.31444930644709984, 0.3461459429510867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.557535434154174, -0.8218362729487612, -0.012971208027627008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.3697359815104575e-05, 0.4902672477161514, 0.4971249260905902, 0.0, 0.010386974598526375, -0.5522506556029184, -0.9706795051973673, -0.905511340588439, 0.3883511044829535, -0.47192202189853527, -0.9682551720699084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2707016219662041, 0.4159752885242512, 0.13752347226576409, 0.7271470967894607, 0.23326813621686415, -0.41154795516855397, 0.02636470199646393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020881653776323585, -0.11583562882744404, 0.06734447177650237]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21390324077851916, 0.4503219123930196, 0.022637559817665468, 0.0, -1.0126398621347574, 0.5662669749693652, -1.5680476688345877, -1.9933604780451852, -2.3592127341671203, -0.6047976405701264, -0.5047255030643343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.545389363854257, 0.4439528244847452, 1.9147755620107882, -1.487513716959438, -1.4834903390150427, -0.3343323851700372, 0.3389193187873829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5570526276409673, -0.8258179263474436, -0.009908425023136016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.8809883461016935e-05, 0.48895985807939035, 0.500426318189315, 0.0, 0.1278072139310124, -0.6798587524820071, -0.86635850929006, -0.8940741795148782, 0.5139541153169536, -0.528235656371047, -0.9855149755839359, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23031896254218687, 0.28178193120619355, 0.14276298882143812, 0.5893135124250282, 0.28717174082179364, -0.397661574458747, -0.1445324832740761, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009656130264136024, -0.07963306797364726, 0.06125566008981982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21391005849020772, 0.47463853141052853, 0.047887785822635476, 0.0, -0.9967488064806366, 0.5270726248701981, -1.602399544503729, -2.0340737657447376, -2.3275368326998254, -0.634862848818934, -0.5547255030643333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5357966307703568, 0.4511417770454332, 1.9230681342774139, -1.4641759208311131, -1.4661449774296555, -0.3537088796674716, 0.32284937968903676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5570877676205952, -0.8284641425515393, -0.0072553578296703815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013635423377142704, 0.4863323803501789, 0.5050045200994003, 0.0, 0.31782111308241745, -0.7838870019833412, -0.6870375133828264, -0.8142657539910518, 0.6335180293459018, -0.6013041649761517, -0.9999999999999811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1918546616780042, 0.14377905121375925, 0.16585144533251409, 0.4667559225664967, 0.3469072317077424, -0.3875298899486874, -0.3213987819669225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007027995925557453, -0.05292432408191605, 0.053061343869312674]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2139334483596116, 0.4985735739545678, 0.07343414614360294, 0.0, -0.9722562601021301, 0.4837171447906766, -1.626709680400141, -2.0675554018843925, -2.290431239422649, -0.6674370113949618, -0.6047255030643199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5280283841930167, 0.4525975589522735, 1.93301572291819, -1.4463920759289723, -1.446363343870087, -0.37267127423336777, 0.29964975088163814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5576876148255, -0.8299905434021891, -0.004873435638741116]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004677973880773713, 0.47870085088078507, 0.5109272064193494, 0.0, 0.48985092757013005, -0.86710960159043, -0.4862027179282442, -0.6696327227930992, 0.7421118655435227, -0.6514832515205565, -0.9999999999997315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15536493154680073, 0.02911563813680665, 0.1989517728155225, 0.3556768980428182, 0.395632671191371, -0.3792478913179226, -0.46399257614797196, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01199694409809998, -0.03052801701299591, 0.0476384438185853]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21398536586411634, 0.5218603873164371, 0.09934099531076732, 0.0, -0.9406622229990439, 0.43703276072690245, -1.6429754351139467, -2.090055386501394, -2.248746764801429, -0.7005154010433398, -0.654725503064307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5220610678566364, 0.4503702196531628, 1.9441203258076558, -1.43370204844071, -1.425817089746854, -0.3906657552567055, 0.2725585046140236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5588517035578984, -0.8305087429935376, -0.002615780531037931]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010383500900951598, 0.4657362672373859, 0.5181369833432873, 0.0, 0.6318807420617233, -0.9336876812754831, -0.3253150942761113, -0.4499996916500954, 0.8336894924244017, -0.66156779296756, -0.9999999999997403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1193463267276054, -0.04454678598221347, 0.22209205778931673, 0.25380054976524635, 0.41092508246465687, -0.3598896204667542, -0.5418249253522913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.023281774647963948, -0.010363991826969137, 0.04515310215406371]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21406087636472304, 0.5441227755977854, 0.1256305474195321, 0.0, -0.9033869933166002, 0.38768525347600363, -1.6537384360843654, -2.1013053789343266, -2.2033991851046246, -0.7331751349842528, -0.704725503064253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5179563418883333, 0.44662018038515844, 1.9551478846905694, -1.4255634753052067, -1.406497740091368, -0.40663333982728767, 0.24532564087073333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5605008954654052, -0.8302096620097952, -0.0004453158401527277]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015102100121340595, 0.4452477656269656, 0.5257910421752963, 0.0, 0.7455045936488732, -0.9869501450179762, -0.21526001940837552, -0.22499984865865247, 0.9069515939360875, -0.6531946788182611, -0.9999999999989202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08209451936606435, -0.07500078536008792, 0.22055117765827362, 0.16277146271006576, 0.38638699310972086, -0.3193516914116437, -0.5446572748658054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03298383815013396, 0.005981619674849062, 0.04340929381770406]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21415361433482594, 0.5651643770235749, 0.15232188970893384, 0.0, -0.8615668095710967, 0.33768522842081306, -1.6609998564528572, -2.105055379215468, -2.1551211213473445, -0.7655850000482245, -0.7547255030641845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5156493098808035, 0.44302241855683644, 1.9647891696918023, -1.4212491469066264, -1.3900333040962913, -0.4195688074900582, 0.22170115964814516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.562465039710131, -0.8293549872613308, 0.0015947485563835282]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018547594020580254, 0.42083202851579055, 0.5338268457880342, 0.0, 0.8364036749100711, -1.0000005011038111, -0.14522840736983644, -0.07500000562283285, 0.9655612751455993, -0.6481973012794343, -0.9999999999986303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04614064015059661, -0.07195523656644034, 0.19282570002465607, 0.08628656797160733, 0.32928871990153324, -0.2587093532554108, -0.47248962445176346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03928288489451463, 0.017093494969286232, 0.04080128793072513]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21428261667834597, 0.5849247623975713, 0.17944216393362122, 0.0, -0.8161106625748167, 0.28768520336558134, -1.6665909433991697, -2.1044235759741072, -2.1051211213473615, -0.797530116295248, -0.8047255030641636, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5148421791331945, 0.4405123573890369, 1.9722441476217358, -1.4198995341951057, -1.377356176760104, -0.4290171159111577, 0.20455584774453986, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.564527970584957, -0.8281877581507554, 0.0034457899274372493]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002580046870400827, 0.39520770747992795, 0.5424054844937473, 0.0, 0.9091229399255988, -1.0000005011046345, -0.1118217389262485, 0.012636064827217047, 0.9999999999996627, -0.6389023249404682, -0.9999999999995823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016142614952178325, -0.0502012233559915, 0.14909955859867183, 0.02699225423041226, 0.25354254672374865, -0.1889661684219901, -0.34290623807210596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.041258617496521634, 0.023344582211509656, 0.03702082742107442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21447326292951113, 0.6034049110196956, 0.2070271590539286, 0.0, -0.7677457449779825, 0.23768517831036837, -1.6722170466532966, -2.100228331180767, -2.055121121347368, -0.8284214556657017, -0.854725503064142, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5151331757713309, 0.4393703252172557, 1.977371276428664, -1.4206320234316392, -1.3684859952485824, -0.4351575593773576, 0.1940391974466647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5665153477234395, -0.8268940568848144, 0.005069559905532198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0038129250233031264, 0.36960297244248763, 0.5516999024061477, 0.0, 0.9672983519366839, -1.0000005011042596, -0.1125220650825393, 0.08390489586680734, 0.9999999999998701, -0.617826787409075, -0.9999999999995686, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005819932762726177, -0.02284064343562343, 0.10254257613856074, -0.01464978473066747, 0.17740363023043174, -0.12280886932399827, -0.21033300595750307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.039747542769646024, 0.025874025318819056, 0.032475399561898974]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2147528194391773, 0.6206211483447068, 0.23511967003349202, 0.0, -0.7177457199227378, 0.1876851532551317, -1.6793672214072184, -2.092700007942825, -2.005121121347293, -0.8573738332175487, -0.9047255030641406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5161169158600225, 0.43947959333426834, 1.980492935799108, -1.4226468487876465, -1.362846073037505, -0.43859338382985574, 0.1890053500882898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5683203736631777, -0.8255937378667552, 0.00645900155088425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005591130193322867, 0.34432474650022504, 0.5618502195912682, 0.0, 1.0000005011048934, -1.0000005011047333, -0.14300349507843493, 0.1505664647588354, 1.0000000000014964, -0.5790475510369404, -0.9999999999999714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.019674801773831265, 0.0021853623402527007, 0.06243318740887693, -0.04029650712014602, 0.11279844422154837, -0.06871648904996261, -0.10067694716749805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03610051879476411, 0.026006380361184803, 0.027788832907041046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21514133636079058, 0.6365907913430936, 0.26376742096181105, 0.0, -0.6677456948674612, 0.13768512820119255, -1.6891832883517202, -2.082107826374659, -1.9551211213472992, -0.8834409325670629, -0.9547255030641343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5174434848993956, 0.4405535647795303, 1.9821376505931925, -1.4252829236700009, -1.3596255108626238, -0.44009375945606505, 0.18790582525225283, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5698943533786944, -0.8243537738735832, 0.007630360135157746]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007770338432266037, 0.31939285996773437, 0.572955018566381, 0.0, 1.000000501105533, -1.000000501078783, -0.19632133889003536, 0.21184363136331272, 0.999999999999876, -0.5213419869902838, -0.9999999999998745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026531380787464323, 0.021479428905238712, 0.03289429588169204, -0.05272149764708777, 0.06441124349762345, -0.03000751252418639, -0.021990496720739716, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03147959431033582, 0.024799279863437995, 0.023427171685469924]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21559044202916097, 0.6513357323798745, 0.29302118231223295, 0.0, -0.6177456698126543, 0.08768510316302033, -1.7019055790544244, -2.068828731576044, -1.9051211213473214, -0.9068089690990174, -1.0047255030641231, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5188557769742803, 0.4422461276918362, 1.9828351633023416, -1.4280559071605006, -1.3580396766029565, -0.4403814382610352, 0.18926395754351613, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5712276850132962, -0.8232148701875811, 0.008607432107111174]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008982113367407861, 0.2948988207356192, 0.5850752270084375, 0.0, 1.0000005010961355, -1.0000005007634445, -0.25444581405408667, 0.2655818959723025, 0.9999999999995548, -0.4673607306390901, -0.9999999999997785, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.028245841497693436, 0.03385125824611803, 0.013950254182983832, -0.05545966980999485, 0.03171668519334534, -0.005753576099402899, 0.027162645825266146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02666663269203405, 0.022778073720041477, 0.019541439439068567]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2158857804279169, 0.6648754867996546, 0.32293285434492236, 0.0, -0.5677456447573406, 0.03846402269947199, -1.7168642462366164, -2.0533318626105665, -1.8551211213473224, -0.9288847806446873, -1.0547255030641085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5202471409464502, 0.4442362473220161, 1.982901356859925, -1.4308206897744993, -1.3575786316862317, -0.4398727900774998, 0.19208519730591841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5723440231000738, -0.8221846311049259, 0.009423193076419234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005906767975118453, 0.27079508839560135, 0.5982334406537876, 0.0, 1.0000005011062747, -0.9844216092709669, -0.2991733436438381, 0.3099373793095547, 0.9999999999999769, -0.44151623091339615, -0.9999999999997068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027827279443396007, 0.03980239260359849, 0.0013238711516685587, -0.05529565227997608, 0.00922089833449716, 0.010172963670708173, 0.05642479524804575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02232676173555257, 0.020604781653104857, 0.01631521938616118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159103248195618, 0.6772376315459074, 0.35355316376097023, 0.0, -0.5177456196985276, -0.00639525610091915, -1.7314351349267365, -2.036149538653221, -1.8051211254173727, -0.9534183672039404, -1.1047255030644998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5216018600201224, 0.4462535611173844, 1.9824899659772908, -1.43361410292211, -1.3579477328334828, -0.43876478772028976, 0.19575594476739241, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5732786927226692, -0.8212611096317783, 0.01010853533928399]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004908878328981764, 0.24724289492505763, 0.6124061883209581, 0.0, 1.0000005011762596, -0.8971855760078227, -0.29141777380240186, 0.3436464791469105, 0.9999999185989956, -0.4906717311850626, -1.000000000007826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027094381473443008, 0.040346275907366135, -0.008227817652685586, -0.05586826295221423, -0.0073820229450200295, 0.022160047144200914, 0.0734149492294799, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018693392451909194, 0.018470429462951684, 0.013706845257295135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21591809916144236, 0.6884761003342825, 0.38492938823153205, 0.0, -0.46774559464374815, -0.0436671758512217, -1.7433715699150971, -2.0174338524870175, -1.7584624532020252, -0.9841597287767223, -1.154725503064472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5228408878906328, 0.44809974032885524, 1.9818589262212907, -1.436251338766988, -1.3587889607064068, -0.4374069371815546, 0.19962133705716606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5740470912350104, -0.8204647393382132, 0.010673876235862679]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015548683761147848, 0.22476937576750178, 0.6275244894112364, 0.0, 1.0000005010955892, -0.745438395006051, -0.23872869976721, 0.3743137233240758, 0.9331734443069486, -0.6148272314556386, -0.9999999999994476, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024780557410206246, 0.036923584229417175, -0.012620795120002921, -0.052744716897559746, -0.016824557458479154, 0.02715701077470347, 0.07730784579547287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015367970246825116, 0.015927405871302838, 0.011306817931573763]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21610518259718742, 0.6986508393283996, 0.4171034029484536, 0.0, -0.41774556959183407, -0.07347218582437884, -1.7532301549983202, -1.9968895393400135, -1.7162870802035057, -1.0207528180342547, -1.2047255030644293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5238571573181845, 0.4496781097881178, 1.9813283647244933, -1.4384604484134897, -1.3597658449957826, -0.43622462878644236, 0.20313570828235272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5746620508184985, -0.8198066570943798, 0.011127560097199687]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0037416687149008704, 0.2034947798823411, 0.6434802943384312, 0.0, 1.000000501038282, -0.5961001994631429, -0.19717170166446063, 0.4108862629400797, 0.8435074599703899, -0.7318617851506478, -0.9999999999991428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020325388551032584, 0.031567389185251316, -0.010611229935948806, -0.04418219293003397, -0.019537685787518445, 0.023646167902244993, 0.070287424503733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0122991916697603, 0.013161644876666068, 0.009073677226740184]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162343033222278, 0.7078118452244335, 0.4501105671587205, 0.0, -0.36774554453626296, -0.09690134203580636, -1.761544700939211, -1.9721746062238763, -1.6748450072361283, -1.0620272894402405, -1.2547255030645281, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.524673001695444, 0.4510001492311551, 1.9809170383055825, -1.4402888447405928, -1.3607687126545345, -0.43524822566641097, 0.20622491514305752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5751522977154073, -0.8192603460384954, 0.011491936717635617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002582414500807392, 0.18322011792067883, 0.6601432842053381, 0.0, 1.0000005011114224, -0.46858312422855053, -0.16629091881781388, 0.49429866232274333, 0.828841459347548, -0.8254894281197187, -1.0000000000019789, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016316887545187387, 0.026440788860746276, -0.008226528378214592, -0.03656792654206047, -0.02005735317503829, 0.019528062400627478, 0.06178413721409572, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009804937938176241, 0.010926221117688293, 0.007287532408718606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162711890077621, 0.7160269801016663, 0.4863784252004865, 0.0, -0.31774551948096824, -0.11360226366310819, -1.7677712323515853, -1.9412527608613792, -1.6321713316739597, -1.1070468665649071, -1.3047255030645084, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5253242594531973, 0.4520665899648609, 1.9805905571586677, -1.441818579075301, -1.3617692391313345, -0.43443765474576707, 0.20890185798052224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5755380497716864, -0.8188085082057069, 0.011781101090047551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007377137106863599, 0.16430269754465562, 0.7253571608353208, 0.0, 1.0000005011058941, -0.3340184325460365, -0.1245306282474882, 0.6184369072499402, 0.8534735112433738, -0.9003915424933324, -0.9999999999996035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013025155155065297, 0.021328814674115106, -0.006529622938295442, -0.03059468669416693, -0.0200105295360013, 0.016211418412877703, 0.05353885674929457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007715041125582626, 0.009036756655768476, 0.005783287448238683]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159367506666766, 0.7233865153216565, 0.5251744528170496, 0.0, -0.26774549442831785, -0.12342146655364405, -1.771188601824272, -1.9045152845676274, -1.5903369380614212, -1.1550625282643645, -1.354725503058329, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.525899213414699, 0.45278801160362625, 1.980187198508186, -1.4432988786032843, -1.3629472452589293, -0.43357439586132634, 0.2113537761611685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5758347211539119, -0.8184474799087609, 0.012002327230215428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006688766821709505, 0.14719070439980478, 0.7759205523312611, 0.0, 1.0000005010530082, -0.19638405781071713, -0.06834738945373522, 0.7347495258750361, 0.83668787225077, -0.9603132339891487, -0.9999999998764122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011499079230032749, 0.014428432775307988, -0.00806717300963372, -0.029605990559664973, -0.0235601225518954, 0.017265177688813953, 0.049038363612924935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0059334276445095965, 0.007220565938920812, 0.004424522803357532]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2158916048919643, 0.7300199138168821, 0.565680859900154, 0.0, -0.2177454693738724, -0.1283063309782898, -1.7738704582208418, -1.8634470456714147, -1.553053998942496, -1.2023242745390155, -1.4009755030462177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.526351954915823, 0.45326620774519955, 1.979880082590455, -1.4445268224935641, -1.364050566137246, -0.4328866556453435, 0.21337136256767764, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576058041961036, -0.8181695539790187, 0.012163533554393306]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0009029154942464543, 0.13266796990451232, 0.8101281416620897, 0.0, 1.0000005010889093, -0.09769728849291497, -0.05363712793139592, 0.821364777924255, 0.7456587823785038, -0.9452349254930191, -0.9249999997577742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009054830022484882, 0.009563922831465552, -0.006142318354621725, -0.024558877805596468, -0.022066417566334734, 0.01375480431965618, 0.04035172813018302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0044664161424821935, 0.005558518594844598, 0.003224126483557547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589189919682666, 0.7361088754167711, 0.6074039117793574, 0.0, -0.16892147583361156, -0.12956225143849473, -1.7765674459585095, -1.820695993134153, -1.5233605592214299, -1.2450821053898335, -1.439725503032831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5266852958960513, 0.4535613280572647, 1.9797109718256964, -1.4454807088340924, -1.3650199245358223, -0.4324219235076778, 0.2149562932432828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576223948085373, -0.8179602140625281, 0.012276572207045667]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.88609724750343e-06, 0.1217792319977778, 0.8344610375840658, 0.0, 0.9764798708052171, -0.02511840920409865, -0.053939754753353844, 0.8550210507452309, 0.5938687944213256, -0.8551566170163605, -0.7749999997322676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006666819604565746, 0.0059024062413025, -0.0033822152951722296, -0.019077726810566825, -0.019387167971525624, 0.009294642753314968, 0.031698613512103596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0033181224867408015, 0.004186798329813272, 0.0022607730530471923]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589179049203364, 0.7419896101737604, 0.6499906929966629, 0.0, -0.12293056851496348, -0.12839912201660045, -1.7794324364527976, -1.7783894157666098, -1.5015766638851424, -1.2795860212549266, -1.4672255223888533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5269085793459622, 0.4536970573072909, 1.9796983819463954, -1.4461982755440874, -1.3658959765838994, -0.43218793955717316, 0.21618844913039548, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5763461840669706, -0.8178046273553017, 0.012354010113691537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.174095860320641e-06, 0.11761469513978803, 0.8517356243461112, 0.0, 0.9198181463729616, 0.02326258843788543, -0.0572998098857646, 0.8461315473508657, 0.4356779067257498, -0.6900783173018591, -0.5500003871204437, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004465668998217787, 0.002714585000523732, -0.0002517975860218875, -0.01435133419990044, -0.017521040961542503, 0.004679679010092371, 0.02464311774225373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024447196319503485, 0.00311173414452738, 0.0015487581329174274]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.215891300583474, 0.7492557013048864, 0.6960862303606239, 0.0, -0.08017595878416242, -0.12606001160848526, -1.7825971347798657, -1.7373062925934304, -1.486111230178705, -1.3047685187847757, -1.4848641171228292, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.527023775674254, 0.45366041774089694, 1.979881184598014, -1.4467323245553512, -1.3667866296224584, -0.4322087245552573, 0.21717654821202317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5764357684233186, -0.8176899617881661, 0.012406459950623996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.798171192739838e-06, 0.1453218226225197, 0.921910747279219, 0.0, 0.8550921946160212, 0.04678220816230391, -0.06329396654136117, 0.8216624634635894, 0.30930867412875174, -0.5036499505969823, -0.3527718946795181, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002303926565833962, -0.0007327913278783694, 0.0036560530323733686, -0.010680980225275452, -0.017813060771180934, -0.0004156999616818438, 0.019761981632554135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001791687126959772, 0.0022933113427117493, 0.0010489967386491615]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589173662226246, 0.759351261113381, 0.7430336148888977, 0.0, -0.04026912872065058, -0.1237878204342026, -1.786477301610424, -1.6974154790669336, -1.474585284131528, -1.321363987196231, -1.4957549757997157, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5270099956686989, 0.45337431814628315, 1.9803723159021267, -1.447137270124206, -1.3679050721537116, -0.4325829223975431, 0.2180583515044032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5765011963325737, -0.8176059127579575, 0.01244193810791947]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.720775769080022e-06, 0.20191119616989317, 0.9389476905654772, 0.0, 0.7981366012702368, 0.0454438234856532, -0.07760333661116693, 0.7978162705299348, 0.23051892094354293, -0.3319093682291082, -0.2178171735377326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00027560011110191324, -0.005721991892276191, 0.00982262608225562, -0.008098911377098809, -0.022368850625062584, -0.007483956845716114, 0.017636065847600378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001308558185101751, 0.0016809806041733, 0.0007095631459094907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21589430115799504, 0.7732847017996285, 0.7876129632847731, 0.0, -0.002327587580490162, -0.12355871710289275, -1.7927925866216299, -1.6583658459876376, -1.4638333861573112, -1.3293772034657854, -1.5029898745044112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.526767110999636, 0.4525544660849843, 1.9815573384992808, -1.4474763615281996, -1.369826406076475, -0.43368371325002, 0.21908811276104348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5765488771991691, -0.8175445258402938, 0.012466102060951773]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.129071465156936e-05, 0.27866881372495017, 0.8915869679175081, 0.0, 0.7588308228032083, 0.004582066626196889, -0.1263057002241159, 0.7809926615859178, 0.21503795948433374, -0.16026432539108484, -0.1446979740939091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004857693381261481, -0.01639704122597763, 0.0237004519430849, -0.006781828079873515, -0.03842667845527177, -0.02201581704953777, 0.020595225132805525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0009536173319111582, 0.0012277383532731728, 0.0004832790606460757]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21590609631658084, 0.7900574840513496, 0.8240423854027401, 0.0, 0.03523287020506859, -0.12912270161455572, -1.805292989813483, -1.6198665217233719, -1.4501055362560549, -1.3250581675934394, -1.5095112286419894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5256104695071213, 0.44938487605488964, 1.9858700843775696, -1.4479332697632863, -1.3758855876505387, -0.4379331040685293, 0.22148334910696701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576583675118812, -0.8174996573283833, 0.012482754931288205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00023590317171581565, 0.3354556450344224, 0.7285884423593383, 0.0, 0.751209155711175, -0.11127969023325943, -0.2500080638370649, 0.769986485285313, 0.27455699802512457, 0.08638071744693857, -0.13042708275156265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023132829850290696, -0.06339180060189321, 0.08625491756577541, -0.009138164701733294, -0.12118363148127341, -0.08498781637018643, 0.04790472691847068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006959583928589584, 0.0008973702382113635, 0.0003330574067286343]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21591239160698106, 0.8065715201808511, 0.8494001141253666, 0.0, 0.07269977981555831, -0.13990672684877223, -1.8246258050487183, -1.5812186300344115, -1.4310302358916624, -1.3121568795791914, -1.51662712810651, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.524140281619032, 0.4454489033612587, 1.991197044132715, -1.4483993780003213, -1.3832021319099619, -0.44321845263029125, 0.2242202521301125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766090195596798, -0.8174669470106104, 0.012494043396536002]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012590580800439537, 0.33028072259003083, 0.5071545744525306, 0.0, 0.7493381922097945, -0.21568050468433003, -0.3866563047047031, 0.7729578337792077, 0.3815060072878471, 0.258025760284962, -0.14231798929041423, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029403757761788128, -0.07871945387261897, 0.10653919510290671, -0.009322164740701322, -0.14633088518846293, -0.10570697123523844, 0.0547380604629098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005068888173575506, 0.0006542063554582017, 0.00022576930495594148]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159163704083399, 0.8205090998338253, 0.8650613980892129, 0.0, 0.10656739377778013, -0.15369819438266474, -1.8470411303589107, -1.5456334884977432, -1.4093301464761927, -1.2944233394230389, -1.5245393743630447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5226919026162564, 0.4416296960259477, 1.9963609801742173, -1.448818667896878, -1.3901718883057692, -0.4483618399367749, 0.22673047492575288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766274551752486, -0.817443138320974, 0.012501034905632967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.957602717686654e-05, 0.27875159305948405, 0.31322567927692535, 0.0, 0.6773522792444362, -0.2758293506778502, -0.4483065062038499, 0.7117028307333694, 0.4340017883093956, 0.3546708031230489, -0.1582449251306935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896758005550831, -0.07638414670621974, 0.10327872083004798, -0.008385797931134292, -0.13939512791614628, -0.10286774612967307, 0.05020445591280705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00036871231137786917, 0.00047617379272641753, 0.00013983018193930766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21591846638433038, 0.8308267091968453, 0.8735532413427327, 0.0, 0.13460465274938582, -0.1673231784558116, -1.8693759873858737, -1.5155056574937162, -1.3876766768030777, -1.2756075469879022, -1.5328901572724403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5214092770187255, 0.43829550374891313, 2.0008710070916047, -1.449173336645027, -1.396145887793108, -0.45286870080990366, 0.22879928499548088, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576640854211947, -0.8174258264651038, 0.012504095352313446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.191951980910782e-05, 0.20635218726040166, 0.16983686507039716, 0.0, 0.5607451794321137, -0.2724996814629371, -0.44669714053925935, 0.6025566200805388, 0.43306939346229867, 0.37631584870273244, -0.16701565818791347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02565251195061844, -0.06668384554069101, 0.09020053834774705, -0.007093374962978895, -0.11947998974677948, -0.09013721746257458, 0.041376201394560115, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00026798073396736726, 0.00034623711740634864, 6.120893360955853e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.215919588922821, 0.8375202029258337, 0.8773169676153797, 0.0, 0.15628752455972358, -0.17903238903461943, -1.889774123183603, -1.49173645040255, -1.3677584926005861, -1.259459501159503, -1.5411219256484496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5203317788181698, 0.43553305940460224, 2.0046117283894684, -1.4494644123703038, -1.400999829049478, -0.45661849619583966, 0.23040781201872712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576650586858912, -0.8174132481648868, 0.01250339576930071]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2450769812901647e-05, 0.13386987457976823, 0.07527452545294017, 0.0, 0.43365743620675534, -0.2341842115761567, -0.4079627159545817, 0.4753841418233231, 0.39836368404983175, 0.32296091656798814, -0.1646353675201882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021549964011112532, -0.05524888688621789, 0.07481442595727661, -0.005821514505537173, -0.09707882512740067, -0.07499590771872015, 0.03217054046492456, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00019465293930204708, 0.00025156600433931715, -1.3991660254685949e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592028416743744, 0.8412076929133199, 0.8782851637975998, 0.0, 0.17219441942329763, -0.18838381922462513, -1.9074529453660065, -1.4741007150488583, -1.3503662981337086, -1.2472265785183194, -1.5487315660902718, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5194503203404521, 0.43330126572356464, 2.007638203136889, -1.449700224282889, -1.404843872631857, -0.45966122029341006, 0.2316219746546978, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766576531322427, -0.8174041143422259, 0.012499270388777595]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3904892328924762e-05, 0.07374979974972211, 0.019363923644401433, 0.0, 0.3181378972714808, -0.18702860380011424, -0.353576443648071, 0.3527147070738369, 0.3478438893375491, 0.24465845282366966, -0.152192808836446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0176291695543547, -0.044635873620752206, 0.060529494948413226, -0.004716238251705162, -0.07688087164758074, -0.06085448195140746, 0.02428325271941388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014132546661368788, 0.00018267645321861574, -8.250761046231589e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592080875722977, 0.8427448057043214, 0.8778145431288397, 0.0, 0.18339369966780433, -0.1956518856007628, -1.9223225653088494, -1.4617439120012894, -1.3356723184941723, -1.2382601369314048, -1.555396119876389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5187363714987747, 0.4315116777774094, 2.010068682137961, -1.4498909717613313, -1.4078683151679736, -0.462111079149444, 0.2325317153861216, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766627816127567, -0.8173974846632517, 0.012492327253483876]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0491795846399363e-05, 0.03074225582003097, -0.009412413375202367, 0.0, 0.22398560489013386, -0.14536132752275313, -0.297392398856859, 0.24713606095138038, 0.29387959279072645, 0.17932883173829212, -0.13329107572234478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0142789768335462, -0.03579175892310448, 0.04860958002144151, -0.0038149495688463075, -0.06048885072233197, -0.0489971771206786, 0.01819481462847594, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010256961028162241, 0.0001325935794857931, -0.0001388627058744008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592144623358347, 0.8429567723611886, 0.876766934215052, 0.0, 0.19101533016282285, -0.2014844810922375, -1.9345392921528537, -1.453567437051174, -1.3235930863131655, -1.2316585904370987, -1.560965063559079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5181554471802858, 0.43006568991592586, 2.012035269925368, -1.450046458769252, -1.4102724078066773, -0.4640975024317748, 0.23322298669636848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576666502537178, -0.8173926742470801, 0.012483378408803487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2749527073852692e-05, 0.004239333137342767, -0.020952178275752208, 0.0, 0.1524326099003705, -0.11665190982949397, -0.24433453688008688, 0.16352949900230987, 0.24158464362013726, 0.13203092988612086, -0.11137887365379968, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01161848636977806, -0.028919757229670433, 0.03933175574813183, -0.0031097401584169247, -0.04808185277407372, -0.03972846564661532, 0.013825426204937482, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.441848842412248e-05, 9.620832343191341e-05, -0.00017897689360777522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592207136732375, 0.8424985506961189, 0.8756467084427816, 0.0, 0.19610265931802137, -0.20632522305355458, -1.9446056578985407, -1.448494782146984, -1.3137019045711587, -1.2264961082123185, -1.5654865477704474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5176727895144926, 0.42886894358724215, 2.0136644755581936, -1.4501757241126365, -1.4122380278492914, -0.46574556114470866, 0.233768373574324, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576669201551716, -0.8173891847950254, 0.01247329796908276]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.250267480566886e-05, -0.009164433301393956, -0.022404515445408363, 0.0, 0.10174658310397038, -0.09681483922634204, -0.20132731491373773, 0.10145309808379763, 0.19782363484013826, 0.10324964449560496, -0.0904296842273688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009653153315865222, -0.02393492657367454, 0.03258411265651309, -0.0025853068676888018, -0.03931240085228328, -0.03296117425867807, 0.010907737559110448, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.398029076222452e-05, 6.978904109171216e-05, -0.00020160879441454436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592276667102406, 0.841815208425571, 0.8746818778104144, 0.0, 0.19950917726296824, -0.21058461093920003, -1.95311717483538, -1.4455991060348434, -1.3054556475814114, -1.2220420470146103, -1.5691231888959736, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5172549626536735, 0.4278346439823447, 2.0150730081056403, -1.4502869507262741, -1.4139250520492952, -0.4671715518737851, 0.23422642363032573, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766711589451656, -0.8173866540558294, 0.012462887843654128]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3906074006320027e-05, -0.013666845410958063, -0.01929661264734479, 0.0, 0.06813035889893718, -0.08518775771290872, -0.17023033873678506, 0.05791352224281087, 0.16492513979494575, 0.08908122395416296, -0.0727328225105235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008356537216378641, -0.020685992097948365, 0.028170650948937014, -0.002224532272752956, -0.033740484000075, -0.028519814581529038, 0.00916100112003444, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.914786899051769e-05, 5.0614783918740665e-05, -0.0002082025085726267]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592363281583407, 0.8411631461231693, 0.8739743485374111, 0.0, 0.2018913752727152, -0.21466387717629185, -1.9606882785656565, -1.444152850098053, -1.2982730206757522, -1.2177424343571432, -1.5720975586767845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.516869399914534, 0.42688127996717673, 2.0163708509166547, -1.4503878095286389, -1.4154772742120336, -0.46848581513436083, 0.23464506123575493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766725783174815, -0.8173848189166727, 0.012452789896708727]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.732289620053473e-05, -0.013041246048033497, -0.01415058546006677, 0.0, 0.04764396019493895, -0.08158532474183608, -0.15142207460553064, 0.028925118735807644, 0.14365253811318474, 0.08599225314934242, -0.05948739561621958, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007711254782791014, -0.019067280303360277, 0.02595685622028429, -0.0020171760472965953, -0.03104444325477014, -0.02628526521151416, 0.008372752108584354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.838744631771187e-05, 3.670278313388672e-05, -0.00020195893890803947]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592477667594878, 0.8406577130835283, 0.8735226834083538, 0.0, 0.20374254166865938, -0.21897056420877617, -1.9679482942235194, -1.443627838497016, -1.2915514948599816, -1.21314021080406, -1.5746601787676242, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5164828272274602, 0.4259277100762982, 2.017667829288331, -1.4504859646409984, -1.4170327057611107, -0.4697991077461509, 0.23506626840277056, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766736075232575, -0.817383488393567, 0.012443449818613044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2877202294066204e-05, -0.010108660792821005, -0.009033302581144181, 0.0, 0.03702332791888362, -0.08613374064968642, -0.14520031315725546, 0.010500232020739651, 0.13443051631541214, 0.09204447106166512, -0.05125240181679408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007731453741476311, -0.019071397817570584, 0.025939567433532294, -0.0019631022471926374, -0.031108630981543005, -0.0262658522358016, 0.008424143340312738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0584115520505476e-05, 2.6610462113848206e-05, -0.00018680156191364653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592632075994195, 0.8403241692890389, 0.8732743701294216, 0.0, 0.2054385467094953, -0.22393733246598, -1.9755598358118025, -1.4436694255958185, -1.2846606616430987, -1.2077988481117838, -1.5770747284452407, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5160595274596225, 0.4248882328976074, 2.019080213625286, -1.450589540676932, -1.4187333479159343, -0.4712290886333637, 0.2355301573373347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766743539716053, -0.8173825239153957, 0.01243512032532734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.0881679863520025e-05, -0.006670875889790261, -0.0049662655786444935, 0.0, 0.03392010081671844, -0.09933536514407672, -0.15223083176566451, -0.0008317419760473996, 0.13781666433765968, 0.1068272538455255, -0.04829099355232919, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008465995356754803, -0.020789543573815503, 0.028247686739097513, -0.0020715207186697256, -0.03401284309647063, -0.02859961774425593, 0.00927777869128266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4928966956951001e-05, 1.928956342612068e-05, -0.00016658986571407256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21592837313759222, 0.8401399818720189, 0.8731745563741776, 0.0, 0.2072753417686052, -0.2300038506932905, -1.9842096390879937, -1.4440596654363946, -1.276954947687852, -1.2012731841826814, -1.5796078017330637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5155618918280447, 0.4236736009321645, 2.0207293173394536, -1.4507070522003822, -1.420724401049599, -0.47289879103111937, 0.23607546635694754, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766748960795607, -0.8173818247433609, 0.012427886678573266]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.10475530056903e-05, -0.0036837483403993143, -0.0019962751048792655, 0.0, 0.03673590118219847, -0.12133036454621018, -0.17299606552382382, -0.00780479681152317, 0.15411427910493397, 0.13051327858204945, -0.05066146575645986, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009952712631557798, -0.024292639308858496, 0.032982074283348234, -0.002350230469002594, -0.03982106267329322, -0.03339404795511332, 0.010906180392256867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0842159109250312e-05, 1.3983440697576432e-05, -0.00014467293508149443]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21593090915604493, 0.8400644754306554, 0.8731711105808895, 0.0, 0.20947300638217142, -0.23747315527226306, -1.9944781440869066, -1.4446748684738369, -1.267888536873459, -1.1931992518250587, -1.582495335368966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5149588180569578, 0.4222112042482151, 2.0227141431200466, -1.4508456205572675, -1.423121295141431, -0.4749088822705441, 0.23673063968469862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576675291477197, -0.8173813174321216, 0.012421701531268587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.072036905393115e-05, -0.0015101288272689334, -6.891586576328562e-05, 0.0, 0.043953292271324496, -0.14938609157945143, -0.20537009997825864, -0.012304060748844723, 0.18132821628785936, 0.16147864715245108, -0.057750672718043614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01206147542173898, -0.0292479336789873, 0.03969651561186048, -0.002771367137704609, -0.04793788183663858, -0.04020182478849534, 0.013103466555021596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.90795273015664e-06, 1.0146224784961677e-05, -0.00012370294609357957]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21593458542595576, 0.8400565276487061, 0.8732155072342905, 0.0, 0.21195611774069972, -0.24651320793852163, -2.005780787001844, -1.4453993079128558, -1.2579430956204947, -1.1841526882115823, -1.5856560986036354, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.514243799190956, 0.4204890296150937, 2.0250525489854976, -1.4510064027574883, -1.425937687052036, -0.4772781503751746, 0.237493967843305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766755822171956, -0.8173809486191156, 0.012416422839096742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.35253982162208e-05, -0.00015895563898790134, 0.0008879330680210279, 0.0, 0.04966222717056607, -0.1808010533251716, -0.22605285829874183, -0.014488788780377838, 0.19890882505928295, 0.18093127226952876, -0.06321526469338973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014300377320032542, -0.034443492662428424, 0.04676811730902393, -0.003215644004415444, -0.0563278382120984, -0.04738536209261056, 0.015266563172127922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.814799968591929e-06, 7.3762601198729884e-06, -0.00010557384343690711]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159377105050664, 0.8400830617014325, 0.8732754512898439, 0.0, 0.21470389616639007, -0.25604386349769387, -2.0178742870655078, -1.4461792230555628, -1.2473079523965982, -1.1744097539488378, -1.5890858194832187, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5134465284677285, 0.41858071846444683, 2.027645110789527, -1.4511837088736705, -1.429046657016919, -0.47990637707530426, 0.23832559787056715, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766757990824232, -0.8173806794225769, 0.012411842508808769]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.250158221312072e-05, 0.0005306810545285066, 0.0011988811110659446, 0.0, 0.05495556851380717, -0.19061311118344498, -0.24187000127328145, -0.015598302854141849, 0.21270286447793008, 0.19485868525488895, -0.0685944175916668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015945414464552568, -0.03816622301293802, 0.05185123608059011, -0.003546122323647246, -0.062179399297660566, -0.05256453400259258, 0.01663260054524279, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.337304552879942e-06, 5.383930773913741e-06, -9.160660575947477e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159401042072035, 0.8401214637842623, 0.8733258854014846, 0.0, 0.2176404747430788, -0.2650664053455912, -2.030355835872431, -1.4469771693295321, -1.2363190364920513, -1.1643540291278451, -1.5927166197570775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5126139262124012, 0.41659996207142724, 2.030337858477653, -1.4513680900137969, -1.432257544752325, -0.4826378721006799, 0.2391699375814941, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766759617707886, -0.8173804826240931, 0.01240772225928613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.787404274154579e-05, 0.000768041656595599, 0.0010086822328158646, 0.0, 0.058731571533774646, -0.1804508369579477, -0.24963097613846758, -0.015958925479386522, 0.2197783180909384, 0.2011144964198525, -0.07261600547717549, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016652045106548267, -0.0396151278603915, 0.05385495376251854, -0.003687622802525284, -0.06421775470812037, -0.05462990050751203, 0.016886794218539013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2537673107950513e-06, 3.935969675339722e-06, -8.240499045276278e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21594197441795052, 0.84015863685121, 0.8733572814594331, 0.0, 0.22065823596785175, -0.27305696764196996, -2.042752286947001, -1.4477627659410925, -1.2253801173615602, -1.154403534011897, -1.5964397100542411, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5117893052339886, 0.41465028947128185, 2.032990500177995, -1.4515506001072485, -1.4353993725434375, -0.4853305374358153, 0.2399793098458615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676083491778, -0.817380338914657, 0.012403825303958642]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7404214940475286e-05, 0.0007434613389519565, 0.000627921158970837, 0.0, 0.06035522449545908, -0.15981124592757517, -0.24792902149139728, -0.01571193223121016, 0.21877838260982452, 0.19900990231896143, -0.07446180594327372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01649241956825173, -0.03899345200290812, 0.053052834006838676, -0.003650201869034196, -0.06283655582225203, -0.053853306702708464, 0.016187445287347797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.434419785478593e-06, 2.874188722444224e-06, -7.79391065497722e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21594354553461037, 0.8401886364337162, 0.8733692803972181, 0.0, 0.22365660805189697, -0.27992594781047014, -2.054671589213391, -1.4485130572280134, -1.2148295008256054, -1.144891112663089, -1.6001495093296336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.511002082831931, 0.41280064598478106, 2.0355095100399567, -1.451725049944099, -1.4383605986887842, -0.4878894239456292, 0.24072458173168984, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766761739515076, -0.8173802342771437, 0.0123999487798776]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.142233319720339e-05, 0.0005999916501264072, 0.00023997875569772256, 0.0, 0.05996744168090451, -0.13737960337000357, -0.23838604532779534, -0.015005825738417735, 0.21101233071909675, 0.19024842697616257, -0.07419598550784838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015744448041149495, -0.036992869730015754, 0.05038019723924021, -0.0034889967370092738, -0.059224522906932454, -0.05117773019627771, 0.014905437716566855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.809194594560338e-06, 2.0927502673642333e-06, -7.753048162083476e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159449820297096, 0.8402101010810369, 0.8733679954901823, 0.0, 0.22656483244170594, -0.28584143386337596, -2.065879500033873, -1.4492141274173287, -1.2048719040331601, -1.1360081586679716, -1.603770258890877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5102665040534171, 0.4110829541548379, 2.0378514356700976, -1.4518883737617432, -1.4410920192881933, -0.49027018239967124, 0.24139504103846432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766762406808519, -0.8173801583820273, 0.012395952020772734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8729901984752316e-05, 0.00042929294641247693, -2.569814071482732e-05, 0.0, 0.05816448779617955, -0.11830972105811606, -0.22415821640964378, -0.014021403786305387, 0.19915193584890464, 0.17765907990234958, -0.07241499122487151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01471157557027697, -0.03435383659886264, 0.04683851260281737, -0.0032664763528811513, -0.05462841198818197, -0.04761516908084137, 0.013409186135489448, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3345868867553702e-06, 1.5179023284750687e-06, -7.99351820972933e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159470230481963, 0.8402241033428237, 0.873316473887058, 0.0, 0.22922145137901329, -0.2909324093961718, -2.0758262154002325, -1.4498335646532874, -1.19599881717931, -1.128182259202516, -1.6071054191225584, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5095845525926923, 0.4095002636860508, 2.0400124478410366, -1.452039623045926, -1.4435920631059063, -0.49246867263430294, 0.24199305364027823, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766762894499942, -0.81738010363057, 0.012391770596960651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.0820369733810705e-05, 0.0002800452357358271, -0.0010304320624853146, 0.0, 0.05313237874614665, -0.10181951065591664, -0.19893430732718959, -0.012388744719175039, 0.17746173707700288, 0.15651798930911226, -0.06670320463362689, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013639029214494468, -0.03165380937574211, 0.04322024341877805, -0.0030249856836570633, -0.05000087635425719, -0.043969804692634264, 0.0119602520362783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.75382847270955e-07, 1.0950291452706703e-06, -8.362847624165307e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159489966313008, 0.8402326395087604, 0.8732373272524211, 0.0, 0.23163421257495104, -0.2953353469309635, -2.084621671625861, -1.4503780018378793, -1.1881193894152526, -1.121314693473251, -1.6101627168502768, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5089502229199343, 0.4080363760371041, 2.04201412463679, -1.452180121586204, -1.445890341432157, -0.4945064492712407, 0.24252940036177964, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763248443838, -0.8173800643513706, 0.012387410277318217]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.947166208996519e-05, 0.00017072331873303499, -0.0015829326927375889, 0.0, 0.04825522391875479, -0.08805875069583459, -0.1759091245125729, -0.010888743691839047, 0.15758855528114588, 0.13735131458529704, -0.061145954554366375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012686593455158733, -0.029277752978934327, 0.04003353591507405, -0.0028099708055602177, -0.04596556652501308, -0.040755532738755665, 0.010726934430028246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.078877923232286e-07, 7.855839884439229e-07, -8.720639284867325e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21595099266389092, 0.8402377276484505, 0.8731588134762326, 0.0, 0.23385293871434631, -0.2992877995882791, -2.092528680289307, -1.450863810201461, -1.1810079601994896, -1.1151855044540675, -1.6129993417278743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5083525410696597, 0.4066639962342536, 2.0438931609506077, -1.452312269798413, -1.448033558718617, -0.4964204949428506, 0.24301856586222076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763503960346, -0.8173800363385021, 0.012382929481272998]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9920651802372225e-05, 0.00010176279380187969, -0.0015702755237693192, 0.0, 0.044374522787905706, -0.07904905314631136, -0.15814017326892033, -0.009716167271634019, 0.1422285843152585, 0.12258378038366921, -0.056732497551952116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011953637005493213, -0.027447596057010047, 0.037580726276351194, -0.002642964244178485, -0.04286434572920141, -0.038280913432198124, 0.009783310008822429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.110330139398487e-07, 5.602573691511586e-07, -8.961592090437526e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21595313419935216, 0.8402409797990021, 0.8730968281321149, 0.0, 0.23593649538374117, -0.30304366586495857, -2.099825670503527, -1.4513089452712393, -1.174423848655995, -1.1095649712731295, -1.6156834869333663, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.50777792089147, 0.40535053884177635, 2.045693645666361, -1.4524389672373113, -1.4500757684875984, -0.49825542700245756, 0.24347583941302972, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763688102383, -0.8173800164738938, 0.012378414707804826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.2830709225039965e-05, 6.504301103345072e-05, -0.0012397068823546441, 0.0, 0.04167113338789714, -0.0751173255335885, -0.14593980428440173, -0.008902701395564878, 0.131682230869891, 0.11241066361875963, -0.053682904109841674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492403563794468, -0.02626914784954481, 0.03600969431506262, -0.002533948777964499, -0.04084419537962833, -0.0366986411921391, 0.009145471016178991, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.682840762130365e-07, 3.972921648385109e-07, -9.029546936343603e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21595548564482472, 0.8402434860195173, 0.8730559524624514, 0.0, 0.23794557033661567, -0.3068162975717414, -2.1067756350848548, -1.4517309095845337, -1.1681377893609863, -1.1042395974801473, -1.6182869481125797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5072119585216643, 0.40406230439471447, 2.0474613881533763, -1.4525632553691452, -1.4520716127281788, -0.5000577335602894, 0.2439155470198356, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676382172261, -0.817380002440857, 0.012373956685973405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.702890945114864e-05, 5.012441030329155e-05, -0.0008175133932696904, 0.0, 0.040181499057489876, -0.07545263413565606, -0.13899929162655747, -0.008439286265888071, 0.12572118590017434, 0.1065074758596434, -0.0520692235842691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011319247396112711, -0.025764688941237786, 0.0353548497403109, -0.002485762636680195, -0.03991688481160455, -0.03604613115663642, 0.008794152136117582, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.672404536954776e-07, 2.806607361082081e-07, -8.916043662840314e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159580726693663, 0.840245869530659, 0.873033214046067, 0.0, 0.23993983923623685, -0.31075820973619334, -2.1136168834040268, -1.452145953540715, -1.1619398528599996, -1.099019626367877, -1.6208822700658403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5066410133885872, 0.40276800736201873, 2.0492390764378476, -1.4526880131809121, -1.4540708410689183, -0.5018708300377867, 0.24434983230168383, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676392108324, -0.817379992513634, 0.012369632043218578]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.17404908317958e-05, 4.7670222835896046e-05, -0.0004547683276874278, 0.0, 0.03988537799242344, -0.07883824328903885, -0.1368249663834378, -0.00830087912362951, 0.12395873001973316, 0.10439942224540322, -0.051906439065212674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011418902661540612, -0.025885940653914523, 0.03555376568942702, -0.0024951562353396394, -0.0399845668147919, -0.03626192954994639, 0.008685705636964716, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9872126240237643e-07, 1.9854445858287876e-07, -8.64928550965503e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2159608841536071, 0.8402484111452629, 0.8730239800319247, 0.0, 0.24197393499607453, -0.3149554196906617, -2.120552158117975, -1.4525681878027377, -1.1556494082795836, -1.0937469963910538, -1.6235377347850863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.506053871567022, 0.4014424027175185, 2.051061273191534, -1.4528156270749337, -1.4561128408258919, -0.5037299362171452, 0.24478759693517918, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766763998916629, -0.8173799854079904, 0.012365492236145767]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.622968481552113e-05, 5.0832292077428795e-05, -0.0001846802828468088, 0.0, 0.04068191519675366, -0.08394419908936741, -0.13870549427896434, -0.008444685240453125, 0.12580889160831923, 0.10545259953646562, -0.05310929438491979, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011742836431306334, -0.026512092890004155, 0.03644393507372888, -0.002552277880430158, -0.04083999513947152, -0.03718212358717131, 0.008755292669906762, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5566677781963244e-07, 1.421128725089157e-07, -8.27961414562238e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21596386743500362, 0.8402511803203537, 0.8730235011087707, 0.0, 0.24409181065568408, -0.31942508838161177, -2.127733127210675, -1.4530084586377217, -1.1491295454353578, -1.0883063992950341, -1.6263098983711688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5054434443751898, 0.4000699316727836, 2.0529493654191224, -1.452947644357068, -1.458221251668446, -0.5056568971369724, 0.24523357100384258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764064860321, -0.8173799801842342, 0.01236155953543708]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.9665627930762826e-05, 5.538350181546567e-05, -9.57846308060275e-06, 0.0, 0.042357513192191235, -0.08939337381900063, -0.14361938185399623, -0.008805416699680711, 0.13039725688451576, 0.10881194192039391, -0.05544327172165074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012208543836644697, -0.027449420894698887, 0.037761844551767114, -0.0026403456426838797, -0.04216821685108552, -0.03853921839654265, 0.008919481373267667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3188738514049965e-07, 1.0447512484759081e-07, -7.86540141737562e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21596791935933207, 0.8402541435701938, 0.8730988289298659, 0.0, 0.24611662478430685, -0.32334780789951073, -2.134547216497519, -1.4534297783224368, -1.1429342209444933, -1.0831630326458568, -1.628968556275335, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.504807760643504, 0.3986474695557953, 2.0549085975546424, -1.4530838697318595, -1.4603998765897372, -0.5076572448587156, 0.2456872916353901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764134359896, -0.8173799758642565, 0.012357826730312984]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.103848656920515e-05, 5.926499680215976e-05, 0.0015065564219046395, 0.0, 0.04049628257245506, -0.07845439035797905, -0.13628178573687688, -0.008426393694302361, 0.12390648981729102, 0.10286733298354611, -0.05317315808332461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012713674633719708, -0.02844924233976674, 0.03918464271039906, -0.0027245074958317174, -0.043572498425824675, -0.04000695443486381, 0.009074412630950702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3899915003731548e-07, 8.639955350694817e-08, -7.46561024819113e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21597193409023838, 0.8402572356730094, 0.8731385286506769, 0.0, 0.24803444972891642, -0.326734566813432, -2.1409460258204467, -1.4538288974523306, -1.1371066795213836, -1.078353146790863, -1.6314959066735615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5041516944992641, 0.3971863693134425, 2.056923364488729, -1.4532234661303138, -1.4626303382089374, -0.5097150993131078, 0.24614398878160565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764200682881, -0.8173799723988152, 0.012354263573504849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.02946181258546e-05, 6.184205631085905e-05, 0.0007939944162183162, 0.0, 0.03835649889219139, -0.06773517827842575, -0.12797618645855235, -0.007982382597875527, 0.11655082846219302, 0.09619771709987601, -0.05054700796452541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0131213228847984, -0.029222004847056036, 0.0402953386817301, -0.0027919279690843397, -0.04460923238400132, -0.04115708908784493, 0.00913394292431082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3264597061330337e-07, 6.930882429567642e-08, -7.126313616272932e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21597580098874633, 0.8402603979967255, 0.8731418168528109, 0.0, 0.24986017871290592, -0.32975468697718513, -2.1469838422511227, -1.4542080915877584, -1.131597685108248, -1.073834053765486, -1.6339115395295283, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5034837183596121, 0.3957057154866313, 2.0589672791372515, -1.4533649440652163, -1.4648826326779465, -0.5118035332713099, 0.24659672396577523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676426062618, -0.8173799696960767, 0.012350825882576735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.733797015885058e-05, 6.324647432168868e-05, 6.576404268071893e-05, 0.0, 0.036514579679790014, -0.060402403275062605, -0.1207563286135167, -0.0075838827085569814, 0.1101798882627073, 0.09038186050753894, -0.04831265711933672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013359522793037494, -0.029613076536222943, 0.04087829297045396, -0.0028295586980501266, -0.045045889380181066, -0.04176867916404165, 0.009054703683391337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1988659731255845e-07, 5.405476933653853e-08, -6.875381856227498e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21597954225161634, 0.8402635903566044, 0.8731254488513662, 0.0, 0.25160791712664754, -0.33254465266262534, -2.152714362834844, -1.4545694974777101, -1.1263590478165488, -1.0695629641483857, -1.6362336148536138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5028129464348694, 0.3942257812705339, 2.0610123159070524, -1.453506621352885, -1.4671253456031503, -0.513893917256438, 0.24703865045483375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764313287118, -0.8173799676451967, 0.01234746753808419]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.482525740014176e-05, 6.384719757821989e-05, -0.0003273600288930092, 0.0, 0.03495476827483247, -0.05579931370880366, -0.11461041167442258, -0.00722811779903413, 0.1047727458339869, 0.08542179234200462, -0.04644150648171211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013415438494855743, -0.029598684321947788, 0.04090073539601287, -0.002833545753377569, -0.04485425850407688, -0.04180767970256149, 0.00883852978117076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0532187457689919e-07, 4.1017600071540133e-08, -6.716688985091734e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21598317526017582, 0.840266791299757, 0.8731044743544452, 0.0, 0.2532882684028876, -0.3351873334458538, -2.15817977789227, -1.4549148855488858, -1.121353325258512, -1.0655057851441387, -1.6384753379862809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5021472193327972, 0.39276376854788075, 2.0630346788683083, -1.4536470029108424, -1.4693322243894469, -0.5159619122087167, 0.24746442436466015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764358902698, -0.8173799661363714, 0.012344148214609399]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.266017118958212e-05, 6.40188630539151e-05, -0.0004194899384202893, 0.0, 0.03360702552480073, -0.052853615664568754, -0.10930830114851764, -0.006907761423514851, 0.100114451160739, 0.08114358008494028, -0.04483446265334185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013314542041443191, -0.029240254453062893, 0.04044725922511563, -0.0028076311591443705, -0.04413757572593312, -0.041359899045575244, 0.008515478196527903, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.123115983403507e-08, 3.017650623789691e-08, -6.638646949578774e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21598672739051494, 0.840269992250373, 0.8730872023137283, 0.0, 0.2549104285903367, -0.33773279880183693, -2.1634168216463885, -1.4552461348917507, -1.1165481192412319, -1.061632874142527, -1.640647868333564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.50149207536764, 0.39133158096996906, 2.065017865470375, -1.4537850042771912, -1.4714855030519272, -0.5179906055149067, 0.24787081674601294, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.57667643981954, -0.8173799650703748, 0.012340838212088787]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.104260678254591e-05, 6.401901232016424e-05, -0.0003454408143366345, 0.0, 0.032443203748981714, -0.050909307119663155, -0.10474087508237638, -0.006624986857296179, 0.09610412034560263, 0.07745822003223508, -0.043450606945661906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013102879303143262, -0.028643751558233316, 0.03966373204133352, -0.0027600273269765625, -0.04306557324960674, -0.040573866123799825, 0.008127847627055679, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.858540390420901e-08, 2.1319932463373096e-08, -6.620005041224869e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21599023750996257, 0.8402731894558457, 0.8730550050672039, 0.0, 0.25648402088746197, -0.3402172483121448, -2.1684623994059233, -1.4555654926454147, -1.1119107872998688, -1.0579149537936885, -1.6427629300091413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5008504454907556, 0.38993525113043764, 2.066953463348415, -1.4539200289192935, -1.4735766204438343, -0.5199713373859122, 0.24825671024947876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764430115545, -0.8173799644444931, 0.012337521447530603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.020238895242379e-05, 6.394410945302479e-05, -0.0006439449304864127, 0.0, 0.031471845942505836, -0.049688990206156504, -0.10091155519069359, -0.006387155073278527, 0.09274663882726263, 0.07435840697677065, -0.04230123351154607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012832597537688306, -0.027926596790627947, 0.038711957560798545, -0.0027004928420482754, -0.04182234783814261, -0.03961463742010866, 0.0077178700693162836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.384028693777528e-08, 1.251763399971688e-08, -6.633529116367521e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21599436792287738, 0.840276380359421, 0.8730420980213279, 0.0, 0.2578895391027214, -0.3416664841205167, -2.172936067042996, -1.455848573189898, -1.1077918943715033, -1.054629909932421, -1.6446588832971125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5002227502550505, 0.3885757264048003, 2.068840631793639, -1.4540515275883104, -1.475604748825344, -0.5219032557865871, 0.24862234358366195, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764458231401, -0.8173799640801734, 0.012334193106299114]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.260825829634245e-05, 6.381807150572551e-05, -0.0002581409175194594, 0.0, 0.02811036430518823, -0.02898471616743855, -0.08947335274145043, -0.00566161088966712, 0.08237785856731027, 0.06570087722535108, -0.0379190657594234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0125539047141031, -0.02719049451274664, 0.03774336890447918, -0.0026299733803356296, -0.040562567630195535, -0.03863836801349951, 0.007312666683663661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.6231710857984e-08, 7.286394442834348e-09, -6.656682462979252e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21599866063315842, 0.8402795636406772, 0.8730938620570995, 0.0, 0.259097553415057, -0.3426145669272039, -2.1767513369243243, -1.456088966496512, -1.1042726720320097, -1.0518381684604678, -1.6462948852691983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4996083217108915, 0.38725115420539963, 2.0706819070538702, -1.4541795547559513, -1.4775734148598763, -0.5237888976132876, 0.24896909044128693, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764478667123, -0.8173799640733977, 0.01233085444364129]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.585420562091473e-05, 6.366562512438438e-05, 0.001035280715432305, 0.0, 0.024160286246712848, -0.01896165613374361, -0.07630539762657003, -0.004807866132278067, 0.07038444678987046, 0.05583482943906325, -0.03272003944171398, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01228857088317776, -0.026491443988014115, 0.036825505204626394, -0.002560543352818697, -0.03937332069064297, -0.03771283653400949, 0.006934937152499552, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.087144508140631e-08, 1.355139631199785e-10, -6.677325315645922e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21600307339291597, 0.840282734001734, 0.8731659135291623, 0.0, 0.26011534975836104, -0.34341307283754824, -2.1799411942776503, -1.4562881774004632, -1.101325095723957, -1.0495119630429142, -1.6476789159860632, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.499005411520749, 0.3859572817526361, 2.072483020804953, -1.4543044935007026, -1.4794897108490765, -0.5256340583182608, 0.249298999931896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764492357568, -0.8173799643597911, 0.012327514131730749]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.825519515100636e-05, 6.3407221136733e-05, 0.0014410294412551528, 0.0, 0.02035592686608015, -0.015970118206887558, -0.06379714706651891, -0.0039842180790242675, 0.05895152616105247, 0.04652410835107346, -0.027680614337299514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012058203802852795, -0.025877449055270896, 0.0360222750216538, -0.002498774895027, -0.03832591978400594, -0.03690321409946335, 0.006598189812181653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.738088705416519e-08, -5.727866627791286e-09, -6.680623821083274e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21600760338122116, 0.8402858825873146, 0.8732385858225742, 0.0, 0.2609701602257557, -0.3441911960270135, -2.1826016870499947, -1.4564524741393363, -1.0988631688833257, -1.04757764847458, -1.6488454918094053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.498411550258241, 0.38468835538758583, 2.0742517559829716, -1.4544269147593014, -1.4813628551412743, -0.5274466383675188, 0.24961440522961895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676450246775, -0.8173799647898277, 0.012324185414873703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.059976610381864e-05, 6.297171161136526e-05, 0.0014534458682382834, 0.0, 0.017096209347893337, -0.015562463789304428, -0.05320985544688826, -0.0032859347774625114, 0.049238536812628096, 0.03868629136668215, -0.023331516466843925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011877225250161955, -0.025378527301005448, 0.035374703560374206, -0.0024484251719773874, -0.037462885843955684, -0.03625160098516035, 0.006308105954459039, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0220363943462078e-08, -8.60073087623746e-09, -6.657433714093033e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160122445337358, 0.8402889989928035, 0.8733009456660552, 0.0, 0.2616977288434556, -0.34498275287142993, -2.1848537555118566, -1.456590172296587, -1.0967774997819122, -1.0459441837108503, -1.6498408388495722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4978240479556264, 0.38343825185320335, 2.0759964275033207, -1.4545474428541498, -1.4832024623658167, -0.5292350955943539, 0.2499175531111112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676451176323, -0.8173799652363248, 0.012320882836493928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.282305029296259e-05, 6.232810977676406e-05, 0.00124719686962106, 0.0, 0.01455137235399849, -0.015831136888329354, -0.045041369237240614, -0.0027539631450126017, 0.041713382028270976, 0.032669295274594445, -0.01990694080333951, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011750046052288134, -0.025002070687649536, 0.034893430406978954, -0.002410561896967367, -0.03679214449084485, -0.03576914453670107, 0.006062957629844768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8590958226394474e-08, -8.929943478964784e-09, -6.605156759550462e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21601699218016002, 0.8402920735607735, 0.8733489383788298, 0.0, 0.2623339291974208, -0.34579319365451033, -2.186816046239905, -1.4567095075502066, -1.094960083260173, -1.044523151000005, -1.650711965459393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.497240461511184, 0.38220149284385857, 2.077724497583437, -1.4546666432961515, -1.4850170323032812, -0.5310070292665925, 0.25021032616603434, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676452201198, -0.8173799656177889, 0.01231761942606625]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.495292848439846e-05, 6.149135939904885e-05, 0.0009598542554910823, 0.0, 0.012724007079304326, -0.016208815661607735, -0.039245814560968637, -0.0023867050723895295, 0.03634833043478584, 0.028420654216906416, -0.017422532196413994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011671728888848383, -0.024735180186895512, 0.03456140160232337, -0.0023840088400339326, -0.036291398749291756, -0.03543867344477241, 0.005855461098463357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0497502775466458e-08, -7.629282107061982e-09, -6.526820855354412e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21602183941226855, 0.8402950991718837, 0.873382124216459, 0.0, 0.2629099031404904, -0.346621715289843, -2.1885897644570163, -1.456817440087771, -1.093318276094908, -1.0432397089362135, -1.6515001744638835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.496658951463837, 0.38097398870123533, 2.0794415447589887, -1.4547849452465569, -1.4868128741748357, -0.5327681219783683, 0.2504940820448552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764534156281, -0.8173799658912186, 0.012314404807096944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.694464217079713e-05, 6.051222220448142e-05, 0.0006637167525854425, 0.0, 0.01151947886139131, -0.01657043270665271, -0.03547436434222365, -0.0021586507512861273, 0.03283614330529753, 0.025668841275832008, -0.015764180089812084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01163020094693851, -0.024550082852464464, 0.03434094351103029, -0.0023660390081064295, -0.035916837431089366, -0.03522185423551743, 0.005675117576417374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4288600571100832e-08, -5.468593945376315e-09, -6.429237938610368e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21602677451575514, 0.8402980721587655, 0.8734029313021023, 0.0, 0.26345012878626733, -0.3474663496811826, -2.1902531890173953, -1.4569192424176018, -1.091780016976992, -1.0420363776868344, -1.6522383330187072, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4960784811732752, 0.37975342663267037, 2.081150713265234, -1.4549026027541647, -1.4885935768130218, -0.5345215712854419, 0.25076961092939415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676454860548, -0.8173799660385457, 0.012311244373383835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.870206973198153e-05, 5.9459737636686745e-05, 0.0004161417128669426, 0.0, 0.010804512915538847, -0.016892687826792274, -0.03326849120758313, -0.0020360465966165094, 0.030765182358321614, 0.024066624987581543, -0.01476317109647452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011609405811235193, -0.02441124137129899, 0.034183370124907304, -0.0023531501521568896, -0.0356140527637217, -0.035068986141470186, 0.005510577690779668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8898400057527212e-08, -2.9465414857049456e-09, -6.320867426219298e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21603178234914075, 0.8403009923225342, 0.8734150935761278, 0.0, 0.2639723650067338, -0.34832476728485945, -2.191862173258034, -1.4570185622514165, -1.090293565209582, -1.0408724463435228, -1.6529506093452302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4954988408677532, 0.37853928166827056, 2.0828526826187206, -1.455019693178047, -1.490360041910831, -0.5362680539157356, 0.25103719587470413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764565446336, -0.81737996605679, 0.012308139423165202]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010015666771249617, 5.840327537439549e-05, 0.00024324548050988937, 0.0, 0.010444724409329486, -0.017168352073536272, -0.03217968481277232, -0.0019863966762911625, 0.029729035348200178, 0.023278626866232197, -0.014245526530462198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01159280611044039, -0.024282899287996162, 0.034039387069728345, -0.002341808477644138, -0.03532930195618059, -0.03492965260587574, 0.005351698906199745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.3681711148251684e-08, -3.648867031866524e-10, -6.209900437266995e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21603684772938933, 0.8403038622652894, 0.8734221584040455, 0.0, 0.2644885620347491, -0.3491945748809529, -2.1934535836974383, -1.4571177040232528, -1.0888245052572514, -1.0397212770954807, -1.6536535267366221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4949205193629742, 0.37733251037935706, 2.0845460804273266, -1.4551361454075298, -1.4921109794083756, -0.5380061450473197, 0.25129674433100896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764584575443, -0.8173799659518832, 0.012305087974689108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010130760497157876, 5.7398855103869964e-05, 0.00014129655835455363, 0.0, 0.010323940560304902, -0.017396151921869198, -0.031828208788085774, -0.001982835436724865, 0.029381199046611402, 0.023023384960844166, -0.014058347827838082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011566430095577701, -0.024135425778270072, 0.033867956172122377, -0.002329044589656098, -0.035018749950894525, -0.03476182263168082, 0.005190969126096845, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.825821562923392e-08, 2.098134770857365e-09, -6.10289695218573e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160419586015939, 0.840306686355978, 0.8734267264056708, 0.0, 0.2650061321049504, -0.3500736969376522, -2.1950497117297227, -1.4572179702760037, -1.087351806346736, -1.0385669539726834, -1.6543575483327677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4943444800744854, 0.3761350536637586, 2.0862281655538006, -1.455251785885099, -1.493843671021013, -0.5397330161048502, 0.25154794950320897, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764605788461, -0.8173799657345175, 0.012302085924466721]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010221744409101825, 5.648181377198899e-05, 9.136003250619738e-05, 0.0, 0.010351401404025936, -0.01758244113398611, -0.031922560645693265, -0.0020053250550186794, 0.029453978210307263, 0.023086462455943566, -0.014080431922910334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01152078576977829, -0.023949134311968937, 0.03364170252947782, -0.002312809551386046, -0.0346538322527477, -0.03453742115061156, 0.005024103444000692, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.2426037001831756e-08, 4.3473135950859515e-09, -6.004100444774419e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21604736366008312, 0.8403094697460571, 0.8734350252157219, 0.0, 0.2654753272598436, -0.35007369685073425, -2.1964948965858353, -1.457309016342181, -1.0860195784645676, -1.0375220401963547, -1.6549949366573575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4937718592315767, 0.3749493820320416, 2.0878956883176696, -1.4553662179367854, -1.4955546182532826, -0.5414453428277196, 0.2517902931139017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764629579977, -0.8173799653843985, 0.012299128130303778]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010810116978461577, 5.5667801582025265e-05, 0.00016597620102219325, 0.0, 0.009383903097863886, 1.7383589394348586e-09, -0.028903697122247954, -0.0018209213235435564, 0.026644557643368046, 0.02089827552657359, -0.012747766491794214, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011452416858172186, -0.023713432634340594, 0.03335045527738269, -0.00228864103372838, -0.03421894464539412, -0.03424653445738627, 0.004846872213854495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.7583032652669756e-08, 7.0023801632327565e-09, -5.9155883258873476e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21605292192902004, 0.8403122195777611, 0.8734372103487635, 0.0, 0.2658630306423856, -0.35007369672056887, -2.197685934968483, -1.4573835881858568, -1.0849233377592336, -1.0366609872689547, -1.6555207844135031, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4932043641828499, 0.37377899526364156, 2.089543808521132, -1.4554790311330794, -1.4972389020885069, -0.5431381496677691, 0.25202317501417015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764642094635, -0.8173799654700676, 0.012296207289021099]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011116537873814752, 5.499663408062551e-05, 4.3702660832242995e-05, 0.0, 0.007754067650840075, 2.6033077414944466e-09, -0.02382076765295628, -0.0014914368735165844, 0.021924814106682906, 0.017221058548000885, -0.010516955122914125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011349900974535804, -0.023407735368000934, 0.0329624040692496, -0.0022562639258814454, -0.033685676704486515, -0.033856136800989305, 0.004657638005368282, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.502931740470178e-08, -1.713383830696593e-09, -5.841682565358139e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160585391291496, 0.8403149430445964, 0.8734345432742399, 0.0, 0.2661605267060515, -0.35007369661005544, -2.198596159025725, -1.4574397145003435, -1.0840878379201462, -1.036002827391036, -1.6559232247874403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4926437342621508, 0.37262730562338797, 2.091167678978915, -1.4555899048065803, -1.4988918082590552, -0.5448064351101257, 0.25224615709221154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764647153144, -0.8173799658462997, 0.012293315814647952]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011234400259109423, 5.446933670645957e-05, -5.3341490474560505e-05, 0.0, 0.005949921273318584, 2.2102689838432975e-09, -0.018204481144838934, -0.0011225262897345686, 0.01670999678174615, 0.013163197558374204, -0.00804880747874222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011212598413980085, -0.023033792805071538, 0.03247740915565266, -0.0022174734700178556, -0.0330581234109665, -0.03336570884713363, 0.0044596415608277335, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0117018351183196e-08, -7.524640491033929e-09, -5.782948746291969e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21606419019354017, 0.8403176449292039, 0.8734305242789671, 0.0, 0.2663754610526783, -0.3500736964995256, -2.1992499859923624, -1.4574789960140326, -1.0834905673230133, -1.0355296836080907, -1.656212565479602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4920912140342255, 0.3714966324890408, 2.0927639272914322, -1.4556986487309893, -1.500510253731467, -0.546446704393496, 0.2524591119138862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764647329032, -0.8173799664131799, 0.012290448418470734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011302128781127323, 5.403769214999374e-05, -8.037990545659056e-05, 0.0, 0.004298686932535316, 2.210597086556155e-09, -0.013076539332748138, -0.0007856302737820273, 0.011945411942659356, 0.009462875658903318, -0.005786813843234277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011050404558505105, -0.02261346268694326, 0.03192496625035007, -0.0021748784881772867, -0.03236890944823384, -0.032805385667405255, 0.004259096433493393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.517768428796712e-10, -1.1337603859675264e-08, -5.7347923544341295e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21606987954738943, 0.840320326936797, 0.8734276448856592, 0.0, 0.26652304696815105, -0.3500736963881574, -2.1996952462877326, -1.4575046552230122, -1.0830872961176365, -1.0352068357052098, -1.6564094350764715, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.491547393758524, 0.37038793125407254, 2.094331087745453, -1.4558051986136993, -1.5020931481849071, -0.5480574201944037, 0.2526622241944754, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764644351838, -0.8173799671016769, 0.012287602890487727]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011378707698513687, 5.364015186245173e-05, -5.7587866157467624e-05, 0.0, 0.002951718309455116, 2.227364387914466e-09, -0.008905205907407678, -0.0005131841795898658, 0.008065424107534932, 0.006456958057618456, -0.003937391937389303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010876405514030218, -0.02217402469936531, 0.031343209080416025, -0.0021309976541977766, -0.03165788906880445, -0.03221431601815558, 0.004062245611784706, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.954388377393999e-09, -1.3769940527717209e-08, -5.691055966015633e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21607561986259652, 0.8403229860092861, 0.8733679421681183, 0.0, 0.2666200465748417, -0.3500736963881574, -2.19998434780142, -1.4575202111349723, -1.0828294873825681, -1.0349963471155126, -1.656536646165338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4910123094358776, 0.36930103850648877, 2.095869280650176, -1.455909580758646, -1.5036410138327807, -0.5496386773336333, 0.25285589996621527, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764638727941, -0.8173799679481956, 0.012284781881987866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011480630414200897, 5.318144978099488e-05, -0.0011940543508174048, 0.0, 0.0019399921338127543, 1.3740920187555718e-16, -0.005782030273746158, -0.0003111182392027648, 0.005156174701367167, 0.004209771793941766, -0.002544221777326584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01070168645292897, -0.021737854951675163, 0.030763858094457613, -0.0020876428989337814, -0.03095731295746958, -0.03162514278459109, 0.0038735154347971103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1247793010478697e-08, -1.693037198530423e-08, -5.6420169997199354e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21608142335284938, 0.8403256344410629, 0.8732730221958629, 0.0, 0.26668154295241614, -0.3500736963839558, -2.2001642036429567, -1.4575287768314653, -1.082673630413205, -1.0348643288531616, -1.6566147878075357, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904856796610584, 0.36823511751602084, 2.097379596913235, -1.4560118803635589, -1.505155329693353, -0.5511915691808458, 0.2530406616816926, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764631558823, -0.8173799689462681, 0.012281972752968212]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001160698050575208, 5.296863553630828e-05, -0.001898399445107342, 0.0, 0.00122992755148914, 8.403191703895965e-11, -0.003597116830740637, -0.00017131392985822455, 0.003117139387265121, 0.002640365247018794, -0.0015628328439553064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010532595496385036, -0.021318419809358707, 0.030206325261178685, -0.0020459920982595424, -0.030286317211445653, -0.03105783694424939, 0.0036952343095461187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4338236692685037e-08, -1.9961450377687756e-08, -5.61825803930674e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160872984051237, 0.8403282667797484, 0.8731716360417939, 0.0, 0.2667196087252823, -0.35007369638384267, -2.200272256939825, -1.457532813973132, -1.0825849499114293, -1.0347837776716564, -1.6566604070221342, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.489967071199596, 0.3671890961826113, 2.098863473495817, -1.4561121874368386, -1.5066378879622007, -0.5527175506241686, 0.25321703907196536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764623632663, -0.8173799700592117, 0.012279180781709515]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011750104548601343, 5.264677370890524e-05, -0.00202772308137857, 0.0, 0.0007613154573232015, 2.2631267980748753e-12, -0.0021610659373615844, -8.074283333510929e-05, 0.0017736100355154186, 0.001611023630101886, -0.0009123842919704596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010372169229245363, -0.020920426668190953, 0.029677531651635544, -0.0020061414655956227, -0.029651165376951227, -0.0305196288664566, 0.0035275478054554174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5852319991075795e-08, -2.2258872788251025e-08, -5.58394251739441e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160932488153187, 0.8403308779965991, 0.8730823279819212, 0.0, 0.26674316270941384, -0.3500736963837715, -2.2003360671756718, -1.457534110427853, -1.0825378116015334, -1.0347348518687667, -1.6566857729405895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4894560877464096, 0.3661619989805257, 2.100322223965943, -1.4562105786354598, -1.5080903185381425, -0.5542179526663771, 0.2533855112554236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764615091486, -0.8173799712608908, 0.012276410891470036]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011900820389981708, 5.2224337015493136e-05, -0.0017861611974546309, 0.0, 0.00047107968263136035, 1.4238312115015279e-12, -0.0012762047169337133, -2.592909441932608e-05, 0.0009427661979174479, 0.0009785160577929358, -0.000507318369107171, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01021966906372807, -0.020541944041711672, 0.029175009402523246, -0.0019678239724255247, -0.029048611518836497, -0.03000804084416983, 0.003369443669164644, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7082353003507865e-08, -2.403358238480162e-08, -5.5397804789577385e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2160992744817701, 0.8403334710729071, 0.8730135427216953, 0.0, 0.2667583740551514, -0.35007369638305663, -2.200374606950838, -1.4575338759986292, -1.0825145378411614, -1.0347039171936627, -1.6566994005773483, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4889524788008033, 0.36515314127144377, 2.1017567603936245, -1.4563071059086743, -1.5095138151665513, -0.5556936947745841, 0.25354647872089425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676460591319, -0.8173799725376257, 0.012273660069897706]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012051332902810702, 5.186152616093572e-05, -0.0013757052045178986, 0.0, 0.0003042269147510323, 1.4297265423870196e-11, -0.0007707955033258808, 4.688584476185251e-06, 0.0004654752074402101, 0.0006186935020791216, -0.00027255273517869203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010072178912127017, -0.02017715418163816, 0.028690728553633325, -0.0019305454642888316, -0.028469932568178005, -0.029514842164140225, 0.003219349309413864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.83565906542714e-08, -2.55346982010287e-08, -5.50164314466208e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21610537275161257, 0.8403360414840053, 0.8729653807567382, 0.0, 0.2667692445900187, -0.3500736963830547, -2.200400149442479, -1.4575328834282077, -1.082503670595127, -1.0346821701829645, -1.6567068414454744, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4884561543744583, 0.36416219559303303, 2.103167492401232, -1.456401784295093, -1.5109090443863868, -0.5571451824134597, 0.25370025404692825, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764596045464, -0.8173799738694202, 0.012270932877414415]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012196539684909367, 5.140822196302737e-05, -0.0009632392991409771, 0.0, 0.0002174106973457762, 3.8481185504686814e-14, -0.0005108498328159295, 1.9851408427501e-05, 0.00021734492068962004, 0.00043494021396335786, -0.0001488173625199674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009926488526898777, -0.019818913568214285, 0.028214640152143106, -0.0018935677283730557, -0.027904584396713096, -0.029029752777511048, 0.003075506520680302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9735451383059122e-08, -2.663588809662533e-08, -5.454384966581851e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161115398824826, 0.8403385948671653, 0.8729354664981931, 0.0, 0.2667782160040623, -0.3500736963830379, -2.200420124653131, -1.4575315875967711, -1.0824982538972692, -1.0346642957922623, -1.6567114951409836, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.487967199521145, 0.3631891652669818, 2.1045543647128153, -1.4564946035604835, -1.5122761919239986, -0.558572342725361, 0.2538470818587765, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676458560669, -0.8173799752472309, 0.012268223727074347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012334261740060763, 5.1067663199555634e-05, -0.0005982851709022802, 0.0, 0.00017942828087215402, 3.3576584864001144e-13, -0.0003995042130417084, 2.5916628733989853e-05, 0.00010833395715823283, 0.0003574878140449331, -9.307391018313635e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009779097066266451, -0.019460606521024448, 0.02773744623166859, -0.0018563853078117402, -0.02734295075223607, -0.028543206238027335, 0.0029365562369657295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.087755072302794e-08, -2.7556214804878894e-08, -5.418300680138068e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161177721217722, 0.8403411147161127, 0.87300668532155, 0.0, 0.266786643105313, -0.3500736962672246, -2.2004386800516786, -1.4575302451935308, -1.082494391749819, -1.0346473337344415, -1.656715274423275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4874857925305522, 0.36223430432296766, 2.1059169628096237, -1.4565855198617146, -1.51361507803542, -0.5599747369700196, 0.25398714890692364, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764575225438, -0.8173799765569176, 0.012265549234641975]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012464478579181433, 5.0396978948691604e-05, 0.0014243764671384288, 0.0, 0.0001685420250142293, 2.3162664219299105e-09, -0.00037110797094756396, 2.6848064808373916e-05, 7.724294899994321e-05, 0.0003392411564153651, -7.558564582898887e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00962813981185661, -0.019097218880283144, 0.027251961936164328, -0.0018183260246187492, -0.026777722228427503, -0.02804788489317157, 0.002801340962942834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.07625021711229e-08, -2.619373337895835e-08, -5.348984864744271e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161240663306556, 0.8403435967075659, 0.8731151839702143, 0.0, 0.26679521246506904, -0.3500736961816764, -2.2004578857608204, -1.4575289771546878, -1.082490126054409, -1.0346298154557136, -1.6567191572574416, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4870122050283865, 0.3612980198120377, 2.107254656452844, -1.4566744806635217, -1.5149253040899513, -0.5613517035106609, 0.2541206174655808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764564881472, -0.8173799777697793, 0.012262913826162802]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012588417766816042, 4.9639829063040445e-05, 0.00216997297328444, 0.0, 0.00017138719512064935, 1.7109641898255132e-09, -0.00038411418283296406, 2.536077686195136e-05, 8.531390820205297e-05, 0.00035036557455550696, -7.765668333469897e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009471750043313494, -0.01872569021859945, 0.026753872864405007, -0.0017792160361434699, -0.026204521090626456, -0.027539330812824794, 0.0026693711731425544, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.068793141869637e-08, -2.425723414656588e-08, -5.2708169583458215e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21613042019406994, 0.8403460416365942, 0.8732222651870635, 0.0, 0.26680421038560276, -0.3500736960877822, -2.200478580055263, -1.4575278267816014, -1.0824846516157092, -1.034611154154967, -1.656723559685289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4865467489198454, 0.3603807831248214, 2.1085667238490178, -1.4567614294729023, -1.5162063796774385, -0.562702486289889, 0.2542476407855931, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676455472514, -0.8173799788921401, 0.012260316885405777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012707726828716987, 4.8898580566280263e-05, 0.0021416243369831948, 0.0, 0.00017995841067440914, 1.877882879468442e-09, -0.00041388588885431585, 2.300746172472331e-05, 0.00010948877399771765, 0.000373226014934676, -8.804855694920412e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009309122170823981, -0.018344733744325242, 0.026241347923480242, -0.0017389761876118572, -0.025621511749744134, -0.02701565558456237, 0.0025404664002458047, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0312668165193254e-08, -2.2447216054389142e-08, -5.19388151404874e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21613683212671525, 0.8403484522277817, 0.8733131758198035, 0.0, 0.26681370326321546, -0.3500736959798418, -2.200500931710084, -1.4575267967998164, -1.0824777927862785, -1.0345912402469393, -1.6567285871452153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4860897388111172, 0.3594830631130394, 2.109852445919921, -1.4568463104930374, -1.5174578177651659, -0.5640263321947248, 0.25436837412553875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764544863876, -0.8173799799298933, 0.012257755898045612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012823865290587848, 4.821182374856682e-05, 0.0018182126547999684, 0.0, 0.00018985755225454256, 2.1588084305256643e-09, -0.00044703309642565934, 2.059963570073196e-05, 0.0001371765886106432, 0.00039827816055351684, -0.0001005491985291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009140202174562803, -0.017954400235639958, 0.025714441418061982, -0.001697620402700065, -0.02502876175454811, -0.026476918096716543, 0.002414666798913787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9722524922311807e-08, -2.075506356644679e-08, -5.1219747203297085e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.216143301041937, 0.8403508315962265, 0.8733821669122404, 0.0, 0.26682365098477906, -0.3500736958681432, -2.2005247904278065, -1.4575258717632138, -1.0824696764247497, -1.0345701899685655, -1.656734192899307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4856414687417157, 0.3586052840452168, 2.111111165789696, -1.4569290719229164, -1.518679193611367, -0.5653225524631456, 0.2544829806265226, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676453533335, -0.817379980892355, 0.01225522792711685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012937830443493078, 4.758736889649628e-05, 0.0013798218487375887, 0.0, 0.00019895443127199703, 2.2339714096155932e-09, -0.00047717435444466705, 1.8500732051897947e-05, 0.00016232723057524334, 0.00042100556747254043, -0.0001121150818314749, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00896540138803077, -0.01755558135645253, 0.025174397395500734, -0.0016552285975822614, -0.024427516924023472, -0.025924405368415324, 0.0022921300196770415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.906105230508192e-08, -1.9249234083103773e-08, -5.055941857524238e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21614982609436315, 0.8403531826270276, 0.8734290968079154, 0.0, 0.2668339731906955, -0.35007369575742936, -2.200549889718512, -1.4575250306311687, -1.0824605418055477, -1.0345482003307207, -1.6567402710533996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4852022007369134, 0.3577478051690608, 2.112342317837651, -1.4570096678581739, -1.519870172660985, -0.5665905526764778, 0.2545916332258039, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764526111552, -0.8173799817915721, 0.01225273019260172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013050104852282063, 4.7020616023293886e-05, 0.0009385979135000912, 0.0, 0.0002064441183293038, 2.214276373170689e-09, -0.0005019858141032637, 1.6822640904431993e-05, 0.00018269238403940255, 0.00043979275689449824, -0.0001215630818523779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008785360096044234, -0.01714957752311979, 0.024623040959094827, -0.0016119187051502424, -0.02381958099235605, -0.0253600042666449, 0.0021730519856269924, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.844359996236487e-08, -1.7984343722966888e-08, -4.995469030263457e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161564064609126, 0.8403555080192385, 0.8734003342907144, 0.0, 0.2668445849729883, -0.3500736957574293, -2.20057595392447, -1.457524252648341, -1.0824506395942282, -1.034525473171712, -1.6567467069203503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4847721617741512, 0.35691091563412036, 2.1135454349434464, -1.4570880588095008, -1.521030516191996, -0.5678298402732155, 0.2546945135113357, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764516686325, -0.8173799827283615, 0.012250260017818928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001316073309890999, 4.650784421713062e-05, -0.0005752503440191705, 0.0, 0.0002122356458555713, 1.3690306767768303e-15, -0.0005212841191629424, 1.5559656555270642e-05, 0.00019804422639098406, 0.0004545431801758431, -0.00012871733901407984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008600779255243768, -0.016737790698808347, 0.02406234211591552, -0.001567819026538241, -0.02320687062022235, -0.0247857519347533, 0.002057605710636302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.885045275272986e-08, -1.8735789247150882e-08, -4.9403495655821767e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21616304119064805, 0.8403578283195685, 0.8733227568791339, 0.0, 0.2668554293591316, -0.35007369575741104, -2.200602749705545, -1.4575235126061468, -1.0824401810461983, -1.0345021816681899, -1.6567534113964146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4843515704192272, 0.35609483877750825, 2.114720146021429, -1.4571642211122313, -1.522160077292626, -0.5690400196976713, 0.25479181707577636, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676450685136, -0.8173799837517991, 0.01224779675959477]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001326945947090395, 4.6406006600486334e-05, -0.0015515482316112467, 0.0, 0.0002168877228661647, 3.6541982649156954e-13, -0.0005359156215044303, 1.480084388386999e-05, 0.0002091709605956422, 0.000465830070440897, -0.00013408952128761707, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008411827098478748, -0.016321537132242107, 0.02349422155965223, -0.001523246054610437, -0.0225912220126032, -0.0242035884891148, 0.0019460712888126129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9669929697172616e-08, -2.046875192842132e-08, -4.9265164483132386e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21616972912605098, 0.8403601492680635, 0.873229801266869, 0.0, 0.266866452197949, -0.3500736957574084, -2.200630093232158, -1.4575227958606989, -1.0824293338024435, -1.0344784601684094, -1.6567603076729496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4839405956308274, 0.3552997404461769, 2.115866158405844, -1.4572381302344386, -1.5232587837281744, -0.5702207784178267, 0.25488373890977234, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764496600785, -0.8173799848663036, 0.01224533447354385]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013375870805833594, 4.6418969898814205e-05, -0.0018591122452974952, 0.0, 0.00022045677634823765, 5.31379893951386e-14, -0.0005468705322568123, 1.4334908956004658e-05, 0.00021694487509719046, 0.00047442999561092406, -0.00013792553070057228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00821949576799377, -0.015901966626626605, 0.02292024768830123, -0.0014781824441463473, -0.021974128710968467, -0.02361517440310962, 0.0018384366799193092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.050114990156679e-08, -2.2290088742771706e-08, -4.9245721018401214e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21617646887615644, 0.8403624705356598, 0.8731436069591917, 0.0, 0.26687761001675064, -0.35007369575740593, -2.2006578503144967, -1.457522094012375, -1.082418220195092, -1.0344544059986402, -1.6567673370358968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4835393726743205, 0.35452573745901694, 2.11698324755933, -1.4573097644086075, -1.5243266263439894, -0.5713718752445602, 0.25497047409740303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764486001876, -0.817379986059856, 0.012242873147517808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013479500210933771, 4.642535192656507e-05, -0.0017238861535451904, 0.0, 0.000223156376032, 4.895228593199059e-14, -0.0005551416467730762, 1.4036966479234635e-05, 0.00022227214702851136, 0.0004810833953844536, -0.00014058725894544548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008024459130137407, -0.015480059743198809, 0.022341783069722447, -0.001432683483376444, -0.021356852316299062, -0.023021936534671383, 0.0017347037526135593, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1197817673621e-08, -2.3871046680891627e-08, -4.92265205208221e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2161832588304669, 0.8403647897328581, 0.8730745729855597, 0.0, 0.26688887094526603, -0.35007369575740366, -2.2006859283513758, -1.457521402424759, -1.0824069239252205, -1.0344300861656974, -1.656774457983389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4831480116771665, 0.35377290458905536, 2.118071248056229, -1.457379105985687, -1.5253636491656308, -0.5724931305632868, 0.2550522172808518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764475138673, -0.8173799873162869, 0.012240414790030038]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013579908620961706, 4.6383943964709526e-05, -0.001380679472639816, 0.0, 0.00022521857030810812, 4.5071657675653094e-14, -0.0005615607375801633, 1.3831752323282063e-05, 0.00022592539742926216, 0.0004863966588580893, -0.00014241894984100192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00782721994307996, -0.015056657399231677, 0.02176000993797567, -0.0013868315415940888, -0.020740456432828906, -0.02242510637452983, 0.001634863668975554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1726405242395093e-08, -2.512862009234994e-08, -4.916714975541814e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21619009719072538, 0.8403671041898227, 0.8730250905643239, 0.0, 0.2669002129526415, -0.3500736957574016, -2.2007142661292916, -1.457520718706625, -1.0823954991673763, -1.0344055451136152, -1.6567816429052544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4827666021021577, 0.35304127943698055, 2.119130047193072, -1.457446141847574, -1.526369942350554, -0.5735844195468944, 0.25512916185360757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676446408916, -0.8173799886202406, 0.012237961747109524]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013676720516968055, 4.628913929313686e-05, -0.000989648424715688, 0.0, 0.00022684014750957055, 4.139946710372635e-14, -0.0005667555583123272, 1.3674362677109127e-05, 0.00022849515688498203, 0.0004908210416440313, -0.00014369843730866554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0076281915001742695, -0.014632503041496717, 0.0211759827368599, -0.0013407172377381585, -0.020125863698462906, -0.021825779672152452, 0.001538891455115267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2099024503823366e-08, -2.6079074597011422e-08, -4.9060858410289703e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21619698201276316, 0.8403693909794897, 0.8729937033581576, 0.0, 0.26691160204574704, -0.3500736957574017, -2.2007428194324694, -1.457520050983257, -1.082383985994446, -1.0343808116950182, -1.6567888607993935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4823951864378662, 0.3523308655288564, 2.120159577273096, -1.4575108532534877, -1.5273456350290189, -0.574645666675701, 0.2552014917610943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764452909157, -0.8173799899352797, 0.01223553678668683]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001376964407554633, 4.573579333880957e-05, -0.0006277441233252185, 0.0, 0.00022778186211056117, -2.109375869847911e-15, -0.000571066063556301, 1.3354467358528965e-05, 0.00023026345860495946, 0.0004946683719399188, -0.00014435788277919421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007428313285832488, -0.014208278162483209, 0.02059060160048203, -0.0012942281182764291, -0.01951385356929853, -0.02122494257613246, 0.0014465981497341859, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2360008127984424e-08, -2.6300781364404818e-08, -4.849920845388949e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162039112411734, 0.840371644820046, 0.8730639432463851, 0.0, 0.2669230248884602, -0.3500736956413587, -2.2007715620317914, -1.457519400912203, -1.0823724055836264, -1.0343559048021562, -1.6567960982992833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.482033812558446, 0.3516416331967307, 2.1211598214982494, -1.4575732346920631, -1.528290899025163, -0.5756768470954169, 0.2552693950481004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764442140568, -0.8173799911583811, 0.012233145213829094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001385845682049067, 4.507681112581004e-05, 0.0014047977645508538, 0.0, 0.00022845685426318402, 2.3208602049703445e-09, -0.0005748519864364498, 1.30014210797661e-05, 0.00023160821639047431, 0.0004981378572369961, -0.00014474999779595136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007227477588400755, -0.013784646642514194, 0.020004884503069906, -0.001247628771506262, -0.018905279922881726, -0.020623608394317695, 0.0013580657401221635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1537177356203278e-08, -2.4462027476862274e-08, -4.7831457154721864e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21621088274620162, 0.8403738669217018, 0.8731719220750215, 0.0, 0.2669344771029387, -0.3500736955558908, -2.2008004782633654, -1.457518767498764, -1.0823607681610354, -1.0343308370930129, -1.656803350693136, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4816825179742432, 0.35097351968943674, 2.122130811829453, -1.4576332876541562, -1.5292059463657848, -0.5766779858890796, 0.25533305846220017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764431639753, -0.8173799922699669, 0.012230786048447333]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001394301005640464, 4.444203311580015e-05, 0.0021595765727271043, 0.0, 0.00022904428957079792, 1.7093579636436574e-09, -0.0005783246314790183, 1.2668268779095853e-05, 0.00023274845181627655, 0.0005013541828671755, -0.00014504787705052577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007025891684057212, -0.013362270145879145, 0.0194198066240681, -0.0012010592418629734, -0.018300946812435753, -0.020022775873255114, 0.00127326828199477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1001632099928954e-08, -2.2231717444065545e-08, -4.718330763523187e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21621789435531624, 0.8403760606830737, 0.8732789895881766, 0.0, 0.2669459579175962, -0.3500736954617103, -2.200829557757615, -1.4575181491149616, -1.082349078524741, -1.0343056178795946, -1.6568106169147763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4813413239651585, 0.35032642899860605, 2.1230726288615225, -1.4576910188724204, -1.530091029038877, -0.5776491584022576, 0.255392665969017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764421516621, -0.8173799932819799, 0.012228456203358872]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014023218229238042, 4.38752274369505e-05, 0.002141350263103352, 0.0, 0.00022961629314954948, 1.8836104224750254e-09, -0.000581589884989702, 1.2367676045935201e-05, 0.00023379272589137473, 0.0005043842683636384, -0.00014532443280766648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0068238801816956265, -0.012941813816614195, 0.01883634064139092, -0.0011546243652827367, -0.01770165346184227, -0.019423450263559926, 0.0011921501363370915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0246261464036967e-08, -2.024025854716612e-08, -4.659690176922159e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162249438777882, 0.8403782299517353, 0.8733700545444423, 0.0, 0.2669574677974045, -0.35007369535394567, -2.200858792657123, -1.4575175440741612, -1.0823373388890591, -1.034280254820286, -1.65681789742452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4810102329044057, 0.3497002315135996, 2.1239854022820985, -1.4577464395497446, -1.530946439347075, -0.5785904909309358, 0.2554483981079432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764411833685, -0.8173799942041735, 0.012226152107815197]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001409904494393686, 4.338537323242467e-05, 0.0018212991253138855, 0.0, 0.00023019759616600742, 2.155292887558666e-09, -0.0005846979901558906, 1.2100816007284737e-05, 0.00023479271363413404, 0.0005072611861713364, -0.00014561019487512866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006621821215055329, -0.012523949700129247, 0.018255468411517695, -0.0011084135464853324, -0.01710820616396064, -0.01882665057356482, 0.0011146427785238414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9365872725089407e-08, -1.8443872677305486e-08, -4.6081910873516656e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162320291271896, 0.8403803782385246, 0.8734393085536081, 0.0, 0.266969007335507, -0.3500736952423438, -2.2008881760827816, -1.4575169508345838, -1.082325550459439, -1.0342547548833303, -1.6568251930955942, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4806892269473408, 0.34909476375051446, 2.1248693113488164, -1.457799564963331, -1.5317725100909458, -0.5795021612993159, 0.25550043149378615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764402587001, -0.8173799950486483, 0.012223870429537109]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014170498802806397, 4.296573578796341e-05, 0.001385080183315985, 0.0, 0.00023079076205000402, 2.2320375956215015e-09, -0.0005876685131789278, 1.1864791549113498e-05, 0.00023576859240333442, 0.0005099987391157542, -0.00014591342148356242, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006420119141297368, -0.012109355261702811, 0.017678181334354774, -0.0010625082717283661, -0.016521414877413484, -0.018233407367599583, 0.0010406677168597442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8493367796060592e-08, -1.688949633950092e-08, -4.5633565561748545e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21623914793946816, 0.8403825084951195, 0.8734865919518376, 0.0, 0.2669805768156612, -0.3500736951316561, -2.2009177013357832, -1.4575163680436973, -1.0823137142658152, -1.0342291248610438, -1.6568325047003878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4803782676271664, 0.3485098284134123, 2.125724584975342, -1.4578504143167754, -1.5325696144135532, -0.5803843989639473, 0.2555489385405917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764393721133, -0.8173799958296586, 0.012221608280659255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001423762455711207, 4.2605131899019826e-05, 0.0009456679645907822, 0.0, 0.00023138960308379466, 2.213753978831219e-09, -0.000590505060034151, 1.1655817727825226e-05, 0.0002367238724716782, 0.0005126004457319495, -0.0001462320958729737, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006219186403488083, -0.011698706742042785, 0.017105472530507652, -0.0010169870688852792, -0.01594208645214642, -0.017644753292629135, 0.0009701409361103273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7731737294005717e-08, -1.5620204309337705e-08, -4.5242977557076816e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624629818664987, 0.8403846234902675, 0.87345820572641, 0.0, 0.2669921766958053, -0.350073695131656, -2.2009473619765845, -1.4575157940121628, -1.082301831024972, -1.0342033714905519, -1.6568398332761973, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4800772963401478, 0.3479451947391125, 2.126551501375257, -1.4578990105250764, -1.5333381649396705, -0.5812374846215507, 0.2555940868861796, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676438477542, -0.8173799966513855, 0.012219362857769665]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014300494363416418, 4.229990296101078e-05, -0.0005677245085536367, 0.0, 0.00023199760288298798, 1.7502593771009861e-15, -0.0005932128160236012, 1.1480630689381649e-05, 0.0002376648168646385, 0.0005150674098367783, -0.00014657151618922034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006019425740369467, -0.011292673485996394, 0.01653832799830158, -0.0009719241660202519, -0.015371010522344906, -0.017061713152066168, 0.0009029669117578904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7891426172238444e-08, -1.6434537952647496e-08, -4.4908457791772356e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162534777896728, 0.84038674533035, 0.8733810052153832, 0.0, 0.26700382529524774, -0.35007369513163805, -2.2009771557001807, -1.457515218653011, -1.0822898956831388, -1.034177501740425, -1.6568471922209316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.47978626160218, 0.34740059935009787, 2.127350390646015, -1.457945390288809, -1.53407861574216, -0.5820617504741658, 0.2556360471294591, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764375523916, -0.817379997567027, 0.012217111922259024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014359206045868843, 4.243680164729112e-05, -0.0015440102205358805, 0.0, 0.00023297198884819962, 3.5825932826912425e-13, -0.0005958744719222681, 1.1507183036155236e-05, 0.00023870683666071132, 0.0005173950025368957, -0.00014717889468489166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005820694759357955, -0.010891907780293053, 0.015977785415159144, -0.0009275952746526126, -0.014809016049790643, -0.01648531705230189, 0.0008392048655897554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.850300644222019e-08, -1.831282982562898e-08, -4.501871021283191e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2162606847320401, 0.8403888798966405, 0.8732884197180647, 0.0, 0.26701552577237686, -0.35007369513163705, -2.2010070761431777, -1.4575146391687135, -1.0822779087823586, -1.034151522660421, -1.656854584175534, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.479505071018492, 0.3468757480561255, 2.1281216260494693, -1.4579895862484686, -1.5347914553860935, -0.5828575754929392, 0.25567497959908075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764365931054, -0.8173799985822928, 0.012214849324556423]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014413884734586837, 4.269132581105787e-05, -0.001851709946370481, 0.0, 0.0002340095425819217, 1.9756619549716515e-14, -0.0005984088599399577, 1.1589685948041597e-05, 0.0002397380156030742, 0.0005195816000830637, -0.00014783909204763132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005623811673760179, -0.010497025879448278, 0.015424708069089408, -0.0008839191931895187, -0.014256792878668989, -0.015916500375467234, 0.0007786493924336659, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9185725484062533e-08, -2.0305317313420505e-08, -4.5251954052001013e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21626791706948167, 0.8403910264403929, 0.8732025856999391, 0.0, 0.2670272751961376, -0.3500736951316361, -2.2010371153516917, -1.457514055683218, -1.0822658731634591, -1.0341254412782956, -1.6568620074325004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4792336051969313, 0.34637031735485774, 2.1288656236519317, -1.4580316314423525, -1.5354772060140072, -0.5836253838853016, 0.255711037498538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764356035399, -0.8173799996851648, 0.012212575412196055]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001446467488316652, 4.2930875048586925e-05, -0.0017166803625115505, 0.0, 0.00023498847521463188, 1.9407020630381917e-14, -0.0006007841702768923, 1.1669709910676003e-05, 0.00024071237798940046, 0.0005216276425056137, -0.00014846513933088523, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005429316431215983, -0.010108614025354337, 0.014879952049248229, -0.0008409038776750767, -0.013715012558274406, -0.015356167847249351, 0.000721157989145798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.979131161807006e-08, -2.2057441335881603e-08, -4.547824720736257e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21627517293827012, 0.8403931819642296, 0.8731339003273904, 0.0, 0.26703906859207655, -0.35007369513163517, -2.2010672649269503, -1.4575134693062741, -1.082253792468632, -1.0340992645137317, -1.6568694587982957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4789717245536087, 0.3458839563219697, 2.1295828404646935, -1.4580715611442439, -1.536136421338358, -0.5843656426499702, 0.2557443682226654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764345897009, -0.8173800008589348, 0.012210292758946093]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001451173757688937, 4.311047673543585e-05, -0.00137370745097668, 0.0, 0.00023586791877814578, 1.9057346083647097e-14, -0.000602991505171559, 1.172753887649855e-05, 0.00024161389654428348, 0.0005235352912777671, -0.00014902731590383473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005237612866450472, -0.009727220657760192, 0.0143443362552325, -0.0007985940378272056, -0.01318430648701565, -0.014805175293370889, 0.0006666144825478505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0276780086862394e-08, -2.347539834483577e-08, -4.5653064999251605e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21628245055890186, 0.8403953431658724, 0.8730847506870821, 0.0, 0.26705090069583065, -0.3500736951316342, -2.2010975165579345, -1.457512881304607, -1.0822416704686255, -1.0340729991094988, -1.6568769348381993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787192729774674, 0.34541628883814224, 2.1302737716550015, -1.458109413491254, -1.5367696839300513, -0.585078858464341, 0.25577511385138846, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764335575272, -0.8173800020875331, 0.012208004322530197]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014555241263466016, 4.322403285537107e-05, -0.000982992806165355, 0.0, 0.0002366420750825096, 1.8740026088367873e-14, -0.0006050326196848695, 1.1760033341855523e-05, 0.0002424400001269322, 0.0005253080846581279, -0.00014952079807030265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005049031522827549, -0.009353349676550046, 0.013818623806160665, -0.0007570469402051678, -0.012665251833866633, -0.014264316287417996, 0.0006149125744618328, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0643474121042637e-08, -2.4571967333877018e-08, -4.576872831792319e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21628974824240818, 0.8403974851172156, 0.8730537359592998, 0.0, 0.2670627459793237, -0.35007369513163433, -2.2011278569930184, -1.4575123026406043, -1.0822295180120352, -1.0340466515747007, -1.6568844178807645, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4784760498970229, 0.3449669164495067, 2.130938942786761, -1.4581452186198713, -1.5373775989389353, -0.5857655721844568, 0.2558034033557801, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764325119191, -0.8173800033313313, 0.012205734856029759]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001459536701264983, 4.283902686405334e-05, -0.0006202945556472497, 0.0, 0.00023690566986189158, -2.1713538163758635e-15, -0.000606808701674635, 1.1573280055271419e-05, 0.00024304913180895433, 0.0005269506959623978, -0.00014966085130392045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00486446160889306, -0.008987447772710738, 0.013303422635191447, -0.0007161025723463827, -0.012158300177678539, -0.013734274402315415, 0.00056579008783314, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0912162646873643e-08, -2.4875963631527022e-08, -4.538933000875017e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21629706438777901, 0.8403996018545109, 0.8731243073650127, 0.0, 0.2670745962583698, -0.3500736950157164, -2.2011582773873655, -1.457511736289721, -1.082217340158305, -1.0340202282584823, -1.6568919022261788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4782418671294015, 0.3445354203706928, 2.131578914157867, -1.4581790186976036, -1.5379607967230233, -0.5864263584889567, 0.2558293675355805, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764315005874, -0.8173800044857833, 0.012203490378713046]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014632290741666408, 4.233474590688757e-05, 0.0014114281142568934, 0.0, 0.00023700558092248922, 2.3183588758424726e-09, -0.0006084078869434338, 1.132701766742397e-05, 0.00024355707460373214, 0.000528466324367855, -0.0001496869082876438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004683655352424539, -0.008629921576278917, 0.01279942742211643, -0.000676001554645535, -0.01166395568175849, -0.013215726089998244, 0.0005192835960080346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0226633185663278e-08, -2.308903851348098e-08, -4.488954633424214e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21630439748619967, 0.8404016943610069, 0.8732325902621124, 0.0, 0.2670864500084269, -0.3500736949303083, -2.201188771287039, -1.4575111818230162, -1.0822051391365408, -1.0339937350457102, -1.656899387099385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.47801653359037, 0.3441213641530613, 2.1321942746466345, -1.4582108610075397, -1.5385199272259045, -0.5870618210244433, 0.25585313368914525, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764305057, -0.8173800055313815, 0.012201270189917056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014666196841298034, 4.18501299188691e-05, 0.0021656579419954388, 0.0, 0.00023707500114165074, 1.708161631123597e-09, -0.000609877993465055, 1.1089334095520644e-05, 0.00024402043528685044, 0.0005298642554411128, -0.00014969746412284165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0045066707806268565, -0.008281124352628821, 0.012307209775348856, -0.0006368461987208343, -0.01118261005762165, -0.012709250709730318, 0.00047532307129547667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.989775118302607e-08, -2.0911963833339505e-08, -4.440377591980377e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21631174612413442, 0.8404037659444155, 0.8733400399747198, 0.0, 0.2670983079575027, -0.3500736948358992, -2.201219333088103, -1.4575106378303866, -1.0821929163613722, -1.033967177525231, -1.6569068731630796, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4777998508672818, 0.3437242965305973, 2.132785636964021, -1.4582407957468173, -1.5390556559486657, -0.5876725879660186, 0.2558748243035173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676429540065, -0.8173800064800063, 0.012199071347080566]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014697275869504623, 4.143166817163784e-05, 0.0021489942521478005, 0.0, 0.0002371589815159808, 1.8881832788923155e-09, -0.0006112360212851207, 1.0879852590346034e-05, 0.0002444555033744088, 0.000531150409584982, -0.00014972127389383983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004333654461767229, -0.007941352449280998, 0.011827246347727177, -0.0005986947855518416, -0.010714574455222428, -0.012215338831507001, 0.00043381228744099164, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931269594944891e-08, -1.897249746363852e-08, -4.3976856729789664e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21631910898250323, 0.8404058203659344, 0.8734313942816181, 0.0, 0.2671101713915623, -0.35007369472823646, -2.2012499576498064, -1.4575101026923143, -1.0821806729780428, -1.0339405609707888, -1.65691436146373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4775916122503252, 0.34334375416759916, 2.133353633397984, -1.4582688748769361, -1.539568660395015, -0.5882593078441858, 0.2558945565993919, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764286114592, -0.8173800073414733, 0.01219689041088041]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014725716737626143, 4.108843037915216e-05, 0.001827086137965915, 0.0, 0.0002372686811908395, 2.1532540600196154e-09, -0.0006124912340656557, 1.0702761447333558e-05, 0.0002448676665861772, 0.0005323310888435015, -0.00014976601300870654, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004164772339131546, -0.0076108472599623386, 0.011359928679260192, -0.0005615826023763331, -0.010260088926983532, -0.011734397563344314, 0.0003946459174916378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8572119342267552e-08, -1.7229339607056864e-08, -4.36187240031449e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21632648483626604, 0.8404078610019264, 0.8735008633298548, 0.0, 0.2671220414651014, -0.35007369461671, -2.2012806401630662, -1.4575095748965508, -1.0821684100603033, -1.0339138903142895, -1.656921852965369, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4773916031237677, 0.34297926426414327, 2.133898911898631, -1.4582951514165798, -1.5400596266287203, -0.5888226455898563, 0.2559124422590564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764277208043, -0.8173800081279686, 0.01219472421722217]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000147517075256276, 4.0812719841546276e-05, 0.0013893809647326164, 0.0, 0.00023740147078158474, 2.230529526849804e-09, -0.0006136502651983383, 1.0555915271419436e-05, 0.00024525835479075465, 0.000533413129985177, -0.00014983003277980182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004000182531147696, -0.007289798069117633, 0.010905570012948866, -0.0005255307928758968, -0.009819324674107571, -0.011266754913410356, 0.00035771319329024845, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7813095886088723e-08, -1.5729905846717747e-08, -4.332387316480316e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21633387255182054, 0.8404098906112727, 0.8735483200046366, 0.0, 0.26713391900128314, -0.35007369450609876, -2.2013113760963816, -1.457509053135787, -1.0821561286823216, -1.0338871701475774, -1.6569293484056318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4771996020937377, 0.3426303470757356, 2.1344221323779666, -1.4583196790428843, -1.5405292460508637, -0.58936327873107, 0.2559285874167384, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.576676426863595, -0.8173800088538898, 0.012192570094637976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014775431109004844, 4.0592186925421987e-05, 0.0009491334956353416, 0.0, 0.00023755072363469516, 2.2122250946782595e-09, -0.0006147186663051112, 1.0435215275849966e-05, 0.0002456275596339105, 0.0005344033342436033, -0.00014990880525495503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00384002060060185, -0.006978343768154145, 0.01046440958671333, -0.0004905525260891201, -0.009392388442870377, -0.010812662824273412, 0.00032290315364010924, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7144184971665898e-08, -1.4518425130717686e-08, -4.308245168387653e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21634127108201104, 0.840411911773548, 0.8735200946912641, 0.0, 0.26714580514274827, -0.35007369450609865, -2.201342161611738, -1.4575085357847926, -1.0821438294007941, -1.033860404629491, -1.6569368488723941, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4770153828253616, 0.3422965181907837, 2.1349239633413792, -1.4583425117172015, -1.5409782121782185, -0.5898818938828616, 0.25594309240554947, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764259984554, -0.8173800096240316, 0.01219042544560096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001479706038099614, 4.04232455067057e-05, -0.0005645062674475476, 0.0, 0.0002377228293023912, 1.9278214615706745e-15, -0.0006157103071339759, 1.034701988989483e-05, 0.0002459856305474728, 0.0005353103617249062, -0.0001500093352458067, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003684385367522581, -0.006676577699036978, 0.010036619268252788, -0.0004566534863468154, -0.008979322547097449, -0.010372303035832545, 0.00029009977622171173, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.730279494064749e-08, -1.54028340240997e-08, -4.289298074033214e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21634867946193043, 0.8404139469105035, 0.8734430517980745, 0.0, 0.26715771953260353, -0.35007369450608117, -2.2013729976504215, -1.4575080126113116, -1.082131506488649, -1.0338335977309443, -1.6569443683163674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.476838742846336, 0.3419772906426626, 2.135405082440259, -1.4583637138790277, -1.5414072210828136, -0.5903791849483911, 0.2559560599639653, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.5766764251035184, -0.8173800104929301, 0.012188267740580613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000" + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999943677873273, 0.036489651127809095, -0.34861191507695366, 0.0, -1.0029954720697876, 0.48869320376572917, -0.9525215184807941, -1.3886278121725906, -2.334452544500386, -0.4558788900739724, 0.11051798980155325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424639103, 0.01537723122151193, 1.7420423753144298, -2.031187242709937, -1.4888851823925482, -0.10085496898309822, 0.2189845498620707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529550045, -0.0006253905029041468, -0.0006249999999543101]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011264425345431811, -0.10782259036973244, 0.24007968118780842, 0.0, 0.03470669267139551, 0.02650595782943679, -0.0749999999999986, 0.07499999999999744, -0.06632406743743047, -0.02018751168584966, -0.07499999999999926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999737, 0.074999999999998, 0.07499999999999606, -0.012777139263307391, -0.04774843784840461, -2.521049782918791e-13, -0.04371418946734415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059100089, -0.012507810058082935, -0.012499999999997631]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998925805181444, 0.0267630596697571, -0.3278931585753566, 0.0, -1.0000224659428705, 0.49049653362158574, -0.9619301047404497, -1.379593523733744, -2.3410342122554755, -0.4572018850649818, 0.10116315485063393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8674174204432588, 0.025183583202972704, 1.751384115653074, -2.0317932410205013, -1.493464451596551, -0.10085496898310194, 0.21493079853658995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024960475280989564, -0.0025039454747618935, -0.0018977869579240155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00010219471025693422, -0.1945318291610399, 0.4143751300319408, 0.0, 0.05946012253834131, 0.03606659711713095, -0.1881717251931117, 0.18068576877693243, -0.13163335510178822, -0.026459899820186556, -0.18709669901838655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.17671844041302845, 0.19612703962921552, 0.18683480677288364, -0.012119966211281892, -0.09158538408005376, -7.442134995683418e-14, -0.0810750265096152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742876550287904, -0.037571099437154934, -0.025455739159394107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998493688783553, 0.014583839048681577, -0.30283958239639125, 0.0, -0.9965298716413223, 0.4921355227464133, -0.9760200982822472, -1.36680060810211, -2.349875174327609, -0.45803239691922115, 0.08685564365031923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8549868214394558, 0.03999234575967991, 1.7648047375765166, -2.0314752473307713, -1.4992752177285162, -0.10085496898347529, 0.20999822574163152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005922552841754735, -0.005952405107086799, -0.003193360879578438]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.642327957848494e-05, -0.2435844124215104, 0.5010715235793077, 0.0, 0.06985188603096355, 0.03277978249655097, -0.2817998708359508, 0.25585831263267966, -0.17681924144267328, -0.016610237084787073, -0.2861502240062941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24861198007606106, 0.2961752511341441, 0.26841243846885016, 0.006359873794598259, -0.11621532263930487, -7.467089435582319e-12, -0.09865145589916838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853010627311555, -0.06896919264649809, -0.025911478433088442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999809068351237, 0.0014335378704646243, -0.2761944917194697, 0.0, -0.9929074957979815, 0.49347927487126664, -0.9934337460668297, -1.3521735729677822, -2.3599662038298526, -0.457824273575296, 0.06884865106772532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8406534822932354, 0.058139594719090186, 1.7805125395519898, -2.029647170337682, -1.505313962569741, -0.10102857327294908, 0.20517189543805536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010643678979208298, -0.010710374037979753, -0.0038867220396985465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.06010542364428e-05, -0.26300602356433905, 0.5329018135384308, 0.0, 0.07244751686681615, 0.02687504249706601, -0.34827295569164807, 0.29254070268655696, -0.2018205900448637, 0.004162466878503277, -0.3601398516518781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2866667829244086, 0.3629449791882055, 0.31415603950946397, 0.0365615398617862, -0.12077489682449417, -0.0034720857894756426, -0.09652660607152291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09442252274907126, -0.09515937861785909, -0.013867223202402175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997690652879782, -0.011702002331867939, -0.24928874587665734, 0.0, -0.989246276057703, 0.49468681123771097, -1.0130856680342577, -1.3371594841759553, -2.370582763613108, -0.45628347991271506, 0.04830253205125776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8255901082630048, 0.07823517963514391, 1.7972253898468225, -2.026066250201851, -1.510779505665099, -0.10158468126685208, 0.20121590048948146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01641292307501113, -0.01652437680067441, -0.0038640671749981628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.000612651748077e-05, -0.26271080404665126, 0.5381149168562469, 0.0, 0.0732243948055711, 0.024150727328886127, -0.39303843934856075, 0.3002817758365387, -0.21233119566511, 0.030815873251618307, -0.41092238032935124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30126748060461117, 0.40191169832107443, 0.3342570058966499, 0.07161840271662138, -0.10931086190716179, -0.01112215987806014, -0.07911989897147827, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11538488191605661, -0.1162800552538931, 0.00045309729400767884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997283474068714, -0.02422006317593057, -0.22265032601038354, 0.0, -0.9854888087372059, 0.4959988791581555, -1.0342328168154162, -1.3226446897264197, -2.381293431749223, -0.45328812762035114, 0.026100264362257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8104723735088248, 0.09932762778084879, 1.8141873846479377, -2.020712517349157, -1.5151246688409317, -0.10266626822918933, 0.1986374242225254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023024727213398023, -0.023179169679737342, -0.003240362997743023]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.143576221380755e-05, -0.2503612168812526, 0.532768397325476, 0.0, 0.07514934640994225, 0.026241358408890046, -0.42294297562316907, 0.2902958889907117, -0.21421336272229458, 0.05990704584727803, -0.4440453537800151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3023546950835998, 0.42184896291409757, 0.3392398960223039, 0.10707465705388071, -0.08690326351665349, -0.021631739246744976, -0.05156952533912154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13223608276773788, -0.13309585758125864, 0.0124740835451028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996865980793582, -0.03577252767613231, -0.19642956701394904, 0.0, -0.9815406337022685, 0.4976208882400833, -1.056396033113364, -1.3090816174212576, -2.3918853969091396, -0.4488199833015818, 0.0028533308283817463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7956428661300832, 0.12084202839815208, 1.831009251468635, -2.013679421858163, -1.5180326510469635, -0.10435473103804188, 0.19771778927297087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030315445650636933, -0.03050174984173772, -0.002180320475781348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.349865502641323e-05, -0.2310492900040347, 0.5244151799286898, 0.0, 0.07896350069874844, 0.032440181638556685, -0.44326432595895465, 0.271261446103241, -0.21183930319833585, 0.08936288637538736, -0.4649386706775051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.29659014757483493, 0.43028801234606573, 0.3364373364139436, 0.14066190981987875, -0.058159644120635956, -0.03376925617705119, -0.018392698991090466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1458143687447782, -0.14645160324000756, 0.02120085043923349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996442330373115, -0.04616995896947086, -0.17062210968011732, 0.0, -0.9773194217804638, 0.49955824438821456, -1.07920000541233, -1.2966864109287906, -2.402273896109887, -0.44290888219037877, -0.021025607826192387, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7812463341514053, 0.1424741886154075, 1.8475146134884695, -2.0051054194168927, -1.519369528373308, -0.10669360940779955, 0.1985627728675731, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03815425881537758, -0.03835359792954218, -0.0008307438256598999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.473008409361587e-05, -0.20794862586677107, 0.5161491466766346, 0.0, 0.08442423843609374, 0.03874712296262459, -0.45607944597932065, 0.24790412984934107, -0.20776998401494684, 0.11822202222406095, -0.47757877309148267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2879306395735574, 0.4326432043451085, 0.3301072403966928, 0.17148004882540202, -0.02673754652688798, -0.04677756739515352, 0.016899671892044166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1567762632948129, -0.15703696175608922, 0.026991533002428958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996040725524014, -0.055314282637708795, -0.14516865212623695, 0.0, -0.9727456966265481, 0.5009982242991801, -1.1019427606501693, -1.2858660976682268, -2.412379732756123, -0.4355618582535085, -0.04519470760038505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.767324519208989, 0.1640966399781355, 1.8636348863947714, -1.9951358832689376, -1.5191345486479253, -0.10970712890896582, 0.20115281807469315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04643623664364146, -0.046624149490955655, 0.0006903032687336236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.0320969820218e-05, -0.1828864733647586, 0.5090691510776074, 0.0, 0.0914745030783143, 0.028799598219310777, -0.4548551047567852, 0.216406265211273, -0.202116732924724, 0.14694047873740462, -0.48338199548385324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2784362988483254, 0.43244902725455975, 0.3224054581260395, 0.19939072295909918, 0.004699594507654364, -0.060270390023325224, 0.05180090414240096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656395565652775, -0.1654110312282694, 0.03042094188787047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995656080170937, -0.06315356264304221, -0.1199941524971841, 0.0, -0.9677747180971222, 0.5012873611605031, -1.1241369183257128, -1.2768487140584996, -2.422146155899913, -0.42689116470085037, -0.06940616153652623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753877220547299, 0.18568829153512362, 1.8793483881907975, -1.983904792192392, -1.517416586876193, -0.11341034879709012, 0.20538601171981455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.055076911032641694, -0.05522545682713539, 0.002283205327204916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.692907061534153e-05, -0.15678560010666837, 0.5034899925810568, 0.0, 0.09941957058851723, 0.005782737226461488, -0.44388315351087204, 0.18034767219454395, -0.19532846287580571, 0.1734138710531634, -0.4842290787228237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26894597323380076, 0.43183303113976196, 0.3142700359205242, 0.22462182153091065, 0.03435923543464532, -0.07406439776248616, 0.08466387290242797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17281348778000474, -0.17202614672359462, 0.03185804116942584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995281641503582, -0.06966866451748287, -0.09502117513016206, 0.0, -0.9624003387814247, 0.500116271030617, -1.1455779972015496, -1.269654870766623, -2.431548357049536, -0.4170777138025503, -0.09350309815341745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7408879145352454, 0.2072870992331846, 1.8946485238828072, -1.9715281295513343, -1.5143590200051038, -0.11781302443341707, 0.21111215767328254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06400807277254862, -0.0640877832741035, 0.003868547243061622]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.488773347092766e-05, -0.13030203748881303, 0.4994595473404408, 0.0, 0.10748758631395008, -0.023421802597722835, -0.42882157751673766, 0.14387686583753134, -0.1880440229924549, 0.1962690179660015, -0.4819387323378244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2597861202410735, 0.43197615396121986, 0.3060027138401966, 0.24753325282115302, 0.06115133742178465, -0.08805351272653884, 0.11452291906935952, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17862323479813863, -0.17724652893936235, 0.03170683831713413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994913107957552, -0.07486978452803561, -0.07017347678394761, 0.0, -0.9566474214950237, 0.4974535442189808, -1.1662723818940892, -1.2641571779351852, -2.4405939888037196, -0.406312552106569, -0.11740332790066152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7283317732074577, 0.22895947583181858, 1.9095291082817134, -1.9581026453043, -1.5101332014272366, -0.12292019476310419, 0.21815816901528123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07317453423226578, -0.07315595397288652, 0.005390281978841689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.370670920623152e-05, -0.1040224002110549, 0.4969539669242888, 0.0, 0.11505834572802173, -0.0532545362327229, -0.4138876938507903, 0.10995385662875751, -0.1809126350836694, 0.2153032339196265, -0.4780045949448813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25112282655575346, 0.43344753197267905, 0.29761168797812365, 0.2685096849406872, 0.08451637155734373, -0.10214340659374235, 0.1409202268399741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18332922919434316, -0.18136341397566022, 0.030434694715601344]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999454778588323, -0.0787932511944504, -0.04537638636620607, 0.0, -0.9505610930258132, 0.4934320662590068, -1.186347623731432, -1.2601449452411397, -2.4493170870303422, -0.394757933766431, -0.1410787049015602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7161772892543037, 0.2507809650795023, 1.9239788941423313, -1.9437069608164215, -1.504919569294214, -0.1287315809038877, 0.22634589764778879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08253162230411247, -0.0823863518059898, 0.006815783357143117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.306441486449107e-05, -0.07846933332829581, 0.49594180835483076, 0.0, 0.12172656938421006, -0.08042955919948017, -0.401504836746858, 0.08024465388091005, -0.1744619645324521, 0.23109236680276088, -0.4735075400179733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24308967906307802, 0.4364297849536748, 0.28899571721235584, 0.2879136897575728, 0.10427264266044811, -0.11622772281567015, 0.1637545726501511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18714176143693387, -0.1846079566620657, 0.028510027566028558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999418401004553, -0.08149615548172884, -0.020556340685526725, 0.0, -0.9441966043754932, 0.4882542696256191, -1.205982998975845, -1.2573734263664906, -2.457768988172567, -0.3825317687870865, -0.16453548044579352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7043869252787127, 0.27282430441754935, 1.9379806416962566, -1.9284037276933006, -1.4988950104392036, -0.13524091820649173, 0.2355038109280024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09204320725190959, -0.09174447697766148, 0.008132419216196427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.275516754014441e-05, -0.054058085745568765, 0.49640091361358685, 0.0, 0.12728977300639832, -0.10355593266775534, -0.39270750488825773, 0.05543037749298321, -0.16903802284449532, 0.24452329958688943, -0.4691355108846665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23580727951181774, 0.44086678676094054, 0.28003495107850934, 0.30606466246241537, 0.12049117710021234, -0.13018674605208075, 0.18315826560427226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19023169895594233, -0.1871625034334337, 0.026332717181066216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993820843096527, -0.08304951929192882, 0.004359732278485691, 0.0, -0.9376112471486444, 0.48212994460053066, -1.2253658774053524, -1.2555963712456997, -2.466009239976215, -0.36970820743538035, -0.18779826770983304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6929184906149766, 0.2951523694979101, 1.9515121768008965, -1.9122422732104816, -1.4922250618411221, -0.14243568346670238, 0.24547391998940069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10168012295086909, -0.10120299526375542, 0.009342140285319461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.263338980055095e-05, -0.031067276203999572, 0.4983214592802483, 0.0, 0.13170714453697593, -0.12248650050176803, -0.3876575685901491, 0.035541102415818024, -0.16480503607295707, 0.256471227034123, -0.4652557452807905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22936869327472115, 0.4465613016072156, 0.27063070209279794, 0.32322908965637986, 0.13339897196162795, -0.1438953052042129, 0.19940218122796569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19273831397919, -0.18917036572187879, 0.024194421382460668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999345787218696, -0.08353142067439112, 0.029445008079205522, 0.0, -0.9308586256850422, 0.47524219487126584, -1.244668886932497, -1.2545853835584841, -2.4740982777286065, -0.35632634252206563, -0.21089833098617597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6817271814852262, 0.31781441248440706, 1.9645481115374919, -1.8952614045937972, -1.4850596725245517, -0.15029731022491274, 0.2561152164303628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1114188792209438, -0.11074019912926589, 0.010455772812928171]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.259418191355444e-05, -0.009638027649246223, 0.5017055160143966, 0.0, 0.1350524292720445, -0.13775499458529636, -0.38606019054289176, 0.0202197537443123, -0.16178075504782638, 0.2676372982662945, -0.4620012655268586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22382618259500872, 0.4532408597299385, 0.26071869473190895, 0.33961737233368844, 0.14330778633140898, -0.1572325351642074, 0.2128259288192421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1947751254014942, -0.1907440773102094, 0.02227265055217421]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999310607111454, -0.08302938996233994, 0.05477321513919481, 0.0, -0.923991414112252, 0.46773330417573744, -1.2640402128919723, -1.2541392907820497, -2.482092733130743, -0.34240177658041, -0.23386587648540366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.670773099558801, 0.3407370161374479, 1.9768575873766403, -1.877623985725392, -1.4775504600158724, -0.1588547607254304, 0.2672813611253824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12124067996820441, -0.12033872601129876, 0.011496409058730188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.036021448414886e-05, 0.010040614241023614, 0.5065641411997858, 0.0, 0.13734423145580163, -0.1501778139105684, -0.38742651918950577, 0.00892185552869019, -0.15988910804273, 0.2784913188331126, -0.459350909984554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21908163852850127, 0.4584520730608169, 0.24618951678296816, 0.3527483773681055, 0.1501842501735842, -0.17114901001035326, 0.2233228939003923, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19643601494521215, -0.19197053764065736, 0.020812724916040352]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992804213393903, -0.08165764022566474, 0.08041948891832457, 0.0, -0.9170770735508773, 0.45970313497894394, -1.283601065526524, -1.254086813416885, -2.490043326135137, -0.3279381466345287, -0.2567255882798957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6600365308914813, 0.3634496468522489, 1.9875244374976193, -1.859987029478487, -1.4699013151136944, -0.1682919919079088, 0.2787573864212014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13113083499134293, -0.12998432922857048, 0.012517509370653924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0371544126995355e-05, 0.027434994733504064, 0.512925475582595, 0.0, 0.13828681122749548, -0.16060338393586998, -0.3912170526910351, 0.0010495473032916588, -0.15901186008788104, 0.28927259891762647, -0.4571942358898413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21473137334639292, 0.45425261429602043, 0.21333700241957979, 0.35273912493810033, 0.15298289804356144, -0.1887446236495683, 0.2295205059163795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1978031004627706, -0.19291206434543448, 0.020422006238474722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992545743305098, -0.0795159245272511, 0.10646074018709453, 0.0, -0.9101708458552307, 0.45121181250340664, -1.3034525260914236, -1.254290785018126, -2.4979930325894326, -0.31293292071170853, -0.2794942992600252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6494984100499197, 0.38552614818554565, 1.995875388686491, -1.842962512642937, -1.4623139445105957, -0.1786552829958554, 0.2903352443415077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14107795986408048, -0.13966523005111176, 0.013562634334371814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.169401776087522e-05, 0.04283431396827265, 0.5208250253753994, 0.0, 0.13812455391293332, -0.16982644951074582, -0.39702921129799257, -0.004079432024817522, -0.15899412908591287, 0.30010451845640373, -0.45537421960259006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2107624168312294, 0.44153002666593455, 0.16701902377743577, 0.340490336711002, 0.15174741206197195, -0.20726582175893182, 0.23155715840612628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19894249745475076, -0.19361801645082535, 0.02090249927435781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992322813680996, -0.07670867382958221, 0.1329763188290542, 0.0, -0.9032348264408785, 0.44214690901905485, -1.323493252842749, -1.254855348925615, -2.5059698634130587, -0.2980366560047832, -0.3021668847623032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.639108140516877, 0.40669613074814553, 2.001651537455167, -1.8269615651281002, -1.4549582247240107, -0.18982475365300422, 0.30184944505258826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15107350323247298, -0.14937142693135094, 0.014685286317639549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4585924820379004e-05, 0.05614501395337779, 0.5303115728391934, 0.0, 0.13872038828704258, -0.18129806968703563, -0.40081453502650954, -0.0112912781497776, -0.15953661647252596, 0.2979252941385066, -0.45345171004555895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20780539066085135, 0.42339965125199724, 0.11552297537352055, 0.32001895029673716, 0.1471143957317011, -0.22338941314297658, 0.23028401422161135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991086736785002, -0.19412393760478375, 0.02245303966535469]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992130626790985, -0.07340491572848924, 0.15994061314862004, 0.0, -0.8962724789649682, 0.4324964947242017, -1.3438263294093244, -1.2556221171898703, -2.514013184406461, -0.2835484250369043, -0.3247341376957751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6288354085764698, 0.42682450613392386, 2.0049347917272113, -1.8121833806064307, -1.4479642065666531, -0.20157012497956966, 0.31318554591657793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16111059208723302, -0.15909494212136988, 0.01586729616881353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8437378001899175e-05, 0.06607516202185941, 0.5392858863913167, 0.0, 0.13924694951820532, -0.19300828589706293, -0.4066615313315085, -0.015335365285106062, -0.1608664198680467, 0.28976461935757797, -0.4513450586694377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20545463880814627, 0.40256750771556626, 0.06566508544089172, 0.2955636904333909, 0.1398803631471516, -0.23490742653130897, 0.22672201727979394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007417770952007, -0.19447030380037839, 0.023640197023479626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991966840970793, -0.06977970537894607, 0.18726994136662176, 0.0, -0.8892701283554084, 0.42224521192470754, -1.3645891160146304, -1.256394921929232, -2.5221558967836404, -0.2696095747926342, -0.3471787210740257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6186465895692452, 0.4458749683982276, 2.0060105202825427, -1.7986622006434627, -1.4414223202292344, -0.21361339867696572, 0.32427683434982835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1711835067910226, -0.1688296131239169, 0.017074813798622437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.275716403852687e-05, 0.07250420699086339, 0.5465865643600344, 0.0, 0.14004701219119592, -0.20502565598988312, -0.4152557321061212, -0.015456094787236955, -0.16285424754359026, 0.27877700488540236, -0.44889166756501203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20377638014449317, 0.3810092452860746, 0.021514571106627384, 0.2704235992593596, 0.13083772674837285, -0.240865473947921, 0.22182576866500847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2014582940757915, -0.19469342005094056, 0.024150352596178155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991829704491304, -0.06595164889716351, 0.21486738391251042, 0.0, -0.8821869876742153, 0.4113580694793555, -1.3858915903241376, -1.2570265264617904, -2.5304170095375724, -0.25627574742973624, -0.36947639220324785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6085015888525278, 0.46387136236181853, 2.005249868742743, -1.7863216674809272, -1.4353896885281745, -0.22567821158055126, 0.3350945463214575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18128738829199612, -0.17857079626743272, 0.01827446757476247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.742729589774109e-05, 0.07656112963565102, 0.5519488509177736, 0.0, 0.14166281362386218, -0.21774284890704082, -0.4260494861901423, -0.012632090651166567, -0.165222255078642, 0.26667654725795925, -0.44595342258444315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.202900014334348, 0.3599278792718181, -0.015213030795990373, 0.24681066325070852, 0.12065263402119997, -0.24129625807171087, 0.21635423943258303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20207763001947027, -0.19482366287031647, 0.02399307552280062]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999171936687081, -0.06200489325961712, 0.24262760650810797, 0.0, -0.8749077381951124, 0.3997031550632148, -1.4076775335683605, -1.25758594128843, -2.5387972096710043, -0.24417857712991742, -0.391590489618162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.598342974240442, 0.48087099638066244, 2.003027721377976, -1.7750238484235246, -1.4298975236623708, -0.2375200347171883, 0.34563704259039363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19141825256944675, -0.1883148717070868, 0.019458676694438536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2067524098460056e-05, 0.07893511275092788, 0.555204451911951, 0.0, 0.1455849895820586, -0.23309828832281398, -0.43571886488445577, -0.011188296532793842, -0.16760400266863723, 0.24194340599637676, -0.4422819482982835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20317229224171607, 0.33999268037687863, -0.044442947295344856, 0.22595638114805344, 0.10984329731607509, -0.23683646273274064, 0.2108499253787216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20261728554901254, -0.19488150879308166, 0.023684182393521297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991632893154915, -0.057955381131714064, 0.27043383512585756, 0.0, -0.867367996397315, 0.3872512299726996, -1.429980287645491, -1.2580481042981049, -2.5472886953391627, -0.23334210046732623, -0.4134925815781258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.588134021490493, 0.49694044611680416, 1.9996814247534958, -1.7646048459974841, -1.4249597077185387, -0.24894317319441417, 0.3559190350014655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20157257289412323, -0.1980592924005522, 0.020596362724224826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7294743179113573e-05, 0.0809902425580611, 0.5561245723549918, 0.0, 0.1507948359559485, -0.24903850181030343, -0.4460550815426122, -0.009243260193495056, -0.16982971336316888, 0.21672953325182365, -0.43804183919927536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2041790549989801, 0.321388994722834, -0.06692593248960249, 0.20838004852081085, 0.09875631887663844, -0.2284627695445175, 0.2056398482214377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20308640649352938, -0.1948884138693078, 0.022753720595725828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991570323469426, -0.053798476309639034, 0.29815606018178514, 0.0, -0.8595176351390179, 0.37399993210151256, -1.4528474884205413, -1.2583752085214903, -2.5558745158296525, -0.22360631004274767, -0.43515990202702315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5778455511123288, 0.5121486757206983, 1.9954893594833063, -1.7549029483419794, -1.4205778231805546, -0.2598038304006368, 0.36596427551383576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21174720324770274, -0.20780235697116883, 0.0216640683540259]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2513937097453594e-05, 0.08313809644150058, 0.5544445011185514, 0.0, 0.1570072251659406, -0.2650259574237416, -0.4573440155010057, -0.006542084467708544, -0.17171640980979766, 0.19471580849157094, -0.4333464089779465, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2057694075632873, 0.30416459207788243, -0.08384130540378956, 0.19403795311009459, 0.08763769075968289, -0.2172131441244532, 0.2009048102474056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2034926070715904, -0.1948612914123327, 0.021354112596021484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991532140068302, -0.0495261124340122, 0.32565129367259676, 0.0, -0.8513100937361373, 0.3599504123409985, -1.4763174109024948, -1.2585407040120304, -2.564530809104911, -0.21478922970344114, -0.4565740300787786, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5674527919006813, 0.5265628008053821, 1.9906665842974844, -1.7457735158233119, -1.4167452974479746, -0.27000673079348886, 0.375800257381472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22193937709696854, -0.21754296453507113, 0.02265058158026335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.636680224744883e-06, 0.08544727751253674, 0.5499046698162328, 0.0, 0.16415082805761122, -0.28099039521028146, -0.4693984496390691, -0.0033099098108013477, -0.17312586550517142, 0.17634160678613053, -0.42828256103510925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20785518423294885, 0.288282501693675, -0.09645550371643657, 0.1825886503733485, 0.07665051465159964, -0.2040580078570406, 0.1967196373527248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20384347698531594, -0.19481215127804613, 0.019730264524749012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991519586375045, -0.04514634070765176, 0.3514006435865091, 0.0, -0.8426592115557481, 0.3450548782274425, -1.5003302905499343, -1.2586417207195475, -2.5732270149977454, -0.2073179997627597, -0.4777153494071629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569252279431307, 0.5402475213617974, 1.9853689104517105, -1.737095556272282, -1.41345007180058, -0.279497516553597, 0.3854550071751034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23214684001108826, -0.2272802767874083, 0.023568252139719102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.510738651493572e-06, 0.08759543452720886, 0.5149869982782466, 0.0, 0.1730176436077857, -0.2979106822711192, -0.4802575929487916, -0.002020334150341435, -0.17392411785668363, 0.1494245988136289, -0.42282638656768645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.210551279151014, 0.27369441112830695, -0.10595347691547766, 0.17355919102059403, 0.06590451294789099, -0.18981571520216345, 0.1930949958726276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2041492582823945, -0.19474624504674332, 0.018353411189115012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991531433682683, -0.040652203443944004, 0.3734640331474745, 0.0, -0.8335255223283966, 0.32932626206854554, -1.5248929540006286, -1.2586880015078965, -2.581930858881691, -0.20105999855085718, -0.498573411877532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5462492593169215, 0.5532608933159537, 1.9797051056484585, -1.7287711810021689, -1.4106774840942202, -0.28825605805658827, 0.3949547180241143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24236763948430182, -0.23701378075307267, 0.02441571502677804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.369461527810091e-06, 0.08988274527415509, 0.4412677912193081, 0.0, 0.18267378454702882, -0.3145723231779398, -0.4912532690138861, -0.0009256157669812709, -0.1740768776789138, 0.12516002423805006, -0.4171612494073814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2135193725241847, 0.26026743908312594, -0.11327609606504076, 0.16648750540226392, 0.055451754127197606, -0.17517083005982564, 0.18999421698021818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20441598946427111, -0.19467007931328703, 0.016949257741178766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991568038104338, -0.03604378387140768, 0.39102189623055855, 0.0, -0.8238822059508757, 0.3127923029678555, -1.5500276807358593, -1.2586642221456124, -2.5906074666517895, -0.19576593852907737, -0.5191436384328104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5354166890823266, 0.5656565402075744, 1.9737468833513334, -1.7207250504230756, -1.4084109998532808, -0.29628753156221943, 0.4043231753796419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25260010035560265, -0.24674318402336615, 0.02519559589684357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.320884331225334e-06, 0.09216839145072646, 0.35115726166168076, 0.0, 0.1928663275504183, -0.33067918201380153, -0.502694534704615, 0.0004755872456812329, -0.17353215540196934, 0.10588120043559658, -0.4114045311055688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21665140469189534, 0.2479129378324135, -0.11916444594250003, 0.16092261158186555, 0.045329684818788706, -0.1606294701126236, 0.1873691471105526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20464921742601713, -0.1945880654058694, 0.015597617401310607]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991629762965907, -0.0313301511200436, 0.4042356347770096, 0.0, -0.8137036635729823, 0.2954815505203647, -1.5757550714762791, -1.2585520824471372, -2.599220977602953, -0.19121333064802526, -0.539425331861611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5244213501439687, 0.5774842648355991, 1.9675384844805521, -1.7129005387961165, -1.4066329340866166, -0.30361497808066934, 0.41358166513866096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26284282183271745, -0.25646830713754026, 0.025915311458413366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2344972314041837e-05, 0.0942726550272815, 0.26427477092902024, 0.0, 0.2035708475578688, -0.3462150489498161, -0.5145478148083986, 0.0022427939695019595, -0.17227021902327067, 0.09105215762104218, -0.4056338685760125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21990677876715797, 0.2365544925604943, -0.12416797741562423, 0.15649023253918076, 0.03556131533328266, -0.14654893036899808, 0.18516979518038082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20485442954229588, -0.19450246228348259, 0.014394311231395939]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991716731154052, -0.026525558340783968, 0.41380240247527866, 0.0, -0.8029623156404427, 0.2774207428798835, -1.6020897913705852, -1.2583369909018103, -2.607736646785377, -0.1872381734880999, -0.5594203751179667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5132583434356306, 0.5887901948276059, 1.9611049586567002, -1.7052552910862158, -1.405324980846817, -0.3102732739851018, 0.42274918911505466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.273094660675004, -0.2661890497572536, 0.026584619763713735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.739363762884511e-05, 0.09609185558519262, 0.19133535396538198, 0.0, 0.21482695865079082, -0.36121615280962405, -0.5266943978861184, 0.0043018309065368885, -0.17031338364847823, 0.0795031431985073, -0.3999008651271129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2232601341667642, 0.22611859984013546, -0.12867051647703923, 0.15290495419801506, 0.026159064795992434, -0.13316591808864933, 0.1833504795278738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20503677684573077, -0.19441485239426728, 0.013386166106007354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991828863620853, -0.021645009132675964, 0.4205907108636889, 0.0, -0.791628159543138, 0.258635880996209, -1.6290408846014002, -1.2580090366093195, -2.6161224405769827, -0.18372994186970218, -0.5791323817827055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5019239113415281, 0.5996168454478135, 1.9544588074527132, -1.6977572570550705, -1.404468556059473, -0.31630444289788495, 0.4318428320375456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28335470022604436, -0.27590532282194086, 0.027213481376127325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.242649336002097e-05, 0.09761098416216009, 0.13576616776820377, 0.0, 0.22668312194609339, -0.3756972376734905, -0.5390218646163004, 0.006559085849813688, -0.16771587583211528, 0.07016463236795442, -0.39424013329477636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22668864188205057, 0.21653301240415293, -0.1329230240797412, 0.1499606806229051, 0.01712849574688053, -0.12062337825566287, 0.18187285844981813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2052007910208073, -0.19432546129374453, 0.01257723224827178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991965916541216, -0.016701056200382057, 0.4254225939679053, 0.0, -0.7796690759648334, 0.23915418238325292, -1.6566134421122871, -1.25756206611305, -2.624349893978199, -0.18061804771119994, -0.5985661845110753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904153737741563, 0.6100031613137556, 1.947604948074933, -1.6903814793287308, -1.404045026353251, -0.32175417684037083, 0.44087815263000113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29362221457316656, -0.285617048995376, 0.027810817361409907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7410584072310096e-05, 0.0988790586458781, 0.09663766208432883, 0.0, 0.23918167156609368, -0.3896339722591212, -0.5514511502177396, 0.008939409925390817, -0.16454906802433, 0.062237883170044736, -0.3886760545673955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23017075134743417, 0.20772631731884392, -0.1370771875556067, 0.1475155545267934, 0.008470594124443212, -0.10899467884971732, 0.18070641184911032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20535028694244367, -0.1942345234687028, 0.011946719705651644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992127501286358, -0.011702208613917686, 0.4289739422232274, 0.0, -0.7670512784878643, 0.21900591760066124, -1.684810411942989, -1.2569922982686135, -2.632394354661889, -0.17785914352096863, -0.617727581249097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787309925001368, 0.6199845755451108, 1.9405442054172986, -1.683107685070384, -1.4040358776467259, -0.3266693798282774, 0.44986952770788047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30389663225850994, -0.2953241545968568, 0.028383949432997407]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2316949028507026e-05, 0.09997695172928742, 0.0710269651064412, 0.0, 0.25235594953938256, -0.4029652956518339, -0.563939396614037, 0.011395356888729244, -0.1608892136737929, 0.0551780838046262, -0.3832279347604332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23368762548039063, 0.19962828462710325, -0.14121485315268698, 0.14547588516693374, 0.0001829741305017802, -0.09830405975813139, 0.17982750155758723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548835370686713, -0.1941421120296164, 0.01146264143174999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992313101318812, -0.006652692565644477, 0.4317498358492036, 0.0, -0.7537397487466786, 0.19822584140021687, -1.7136341431009776, -1.2562970072993924, -2.6402348296879428, -0.17542754335129496, -0.6366232662843543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4668697844299083, 0.6295930893252552, 1.933275611045951, -1.6759185806028578, -1.404422861464175, -0.33109652878027634, 0.458830413805529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31417750276953854, -0.30502657383305176, 0.02893846063414057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.712000649054735e-05, 0.10099032096546418, 0.05551787251952504, 0.0, 0.2662305948237139, -0.4156015240088871, -0.5764746231597715, 0.01390581938442012, -0.15680950052107492, 0.04863200339347323, -0.37791370070514646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2372241614045679, 0.19217027560288796, -0.1453718874269521, 0.14378208935052617, -0.00773967634898096, -0.08854297903997929, 0.1792177219529715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056174102205722, -0.1940483847238996, 0.011090224022863238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999252208256924, -0.0015530650799208427, 0.43409950235886813, 0.0, -0.7396986511357861, 0.17685419495564528, -1.7430875667126164, -1.255473436518051, -2.6478536261191183, -0.1733086480035227, -0.6552608821508061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4548313208956247, 0.638857379542875, 1.9257978066239203, -1.6687987189318956, -1.4051881357602882, -0.3350806539796887, 0.46777352030281205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32446446710359783, -0.3147242513390845, 0.02947827750528296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.179625008542345e-05, 0.10199254971447269, 0.04699333019329052, 0.0, 0.2808219522178488, -0.4274329288914317, -0.5890684722327764, 0.01647141562682765, -0.1523759286235147, 0.04237790695544556, -0.37275231732903635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24076927068567405, 0.1852858043523969, -0.14955608844061632, 0.14239723341924326, -0.015305485922267837, -0.07968250398824721, 0.17886212994566003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20573928668118585, -0.19395355012065485, 0.010796337422847802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992753700588597, 0.003598798511559146, 0.43624739217648045, 0.0, -0.724891741690841, 0.15493734916362287, -1.77317503344434, -1.2545179696671447, -2.65523591858819, -0.17149465918198545, -0.6736491402359694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4426155419967504, 0.6478029342278301, 1.9181098129680592, -1.6617337984280063, -1.4063144055645729, -0.33866476616335506, 0.4767109036375887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3347572324029258, -0.3244171475426142, 0.030005856709231834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6323603871767203e-05, 0.10303727182959976, 0.04295779635224643, 0.0, 0.2961381888989033, -0.43833691584044815, -0.6017493346344696, 0.01910933701812804, -0.1476458493814388, 0.036279776430745134, -0.36776516170326684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24431557797748968, 0.17891109369910227, -0.15375987311722422, 0.14129841007778507, -0.0225253960856932, -0.07168224367332676, 0.17874766669553313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20585530598655982, -0.19385792407059352, 0.010551584078977523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999300727479941, 0.008804094513933344, 0.43832674680155004, 0.0, -0.7092734812854777, 0.1325250230096199, -1.8038896617668416, -1.2534467156304505, -2.662369107290451, -0.170136386354041, -0.6917974923403458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4302206397529396, 0.656452392197265, 1.91021119496771, -1.654710318457212, -1.4077850093685291, -0.3418894014845274, 0.48565401651967277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34505557801701003, -0.3341052161568823, 0.03052500721608979]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.071484216269138e-05, 0.10410592004748395, 0.041587092501391226, 0.0, 0.3123652081072662, -0.4482465230800592, -0.6142925664500328, 0.02142508073388495, -0.14266377404522404, 0.02716545655888939, -0.3629670420875271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.247898044876214, 0.1729891593886999, -0.15797236000698112, 0.1404695994158832, -0.029412076079125125, -0.06449270642344677, 0.17886225764168148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596691228168415, -0.1937613722853621, 0.01038301013715913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993281607735924, 0.014069201764168223, 0.440554074676966, 0.0, -0.6928109809552064, 0.10967925831495132, -1.8352409943354022, -1.2522513346602826, -2.6692418402322686, -0.16918147937709843, -0.7097178193704274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4176478262465135, 0.6648252180781782, 1.9021025352490581, -1.6477151275537387, -1.4095841982762256, -0.3447930230988332, 0.4946136536266191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35535929515115294, -0.3437884526041532, 0.031034178355589064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.4866587303167144e-05, 0.10530214500469758, 0.044546557508319394, 0.0, 0.329250006605426, -0.4569152938933719, -0.627026651371214, 0.023907619403360444, -0.1374546588363505, 0.0190981395388514, -0.3584065406016334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2514562701285214, 0.1674565176182633, -0.16217319437304076, 0.13990381806946717, -0.035983778153928975, -0.05807243228611571, 0.17919274213892625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20607434268285799, -0.19366472894541778, 0.010183422789985429]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993575682648196, 0.019400616468993246, 0.44289768829019843, 0.0, -0.6754744605295335, 0.08646953830834081, -1.8672451722132992, -1.2509139006384626, -2.6758434597702183, -0.1685470814504019, -0.7274240181573949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4048984576701506, 0.6729382830732726, 1.8937852932352317, -1.640735717797071, -1.4116971315210167, -0.3474117904117522, 0.5035999569603018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3656681770246601, -0.3534668961450138, 0.031531318896992885]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.8814982454298406e-05, 0.10662829409650044, 0.04687227226464876, 0.0, 0.3467304085134582, -0.46419440013220997, -0.6400835575579383, 0.02674868043639765, -0.1320323907589963, 0.012687958533930593, -0.3541239757393488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2549873715272559, 0.16226129990188878, -0.16634484027652924, 0.1395881951333539, -0.04225866489582044, -0.05237534625838001, 0.17972606667365373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617763747014317, -0.1935688708172126, 0.009942810828076472]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993888393816484, 0.0248040893394555, 0.44529375356535134, 0.0, -0.657234770570855, 0.06297094490393922, -1.8999212050323753, -1.249412458692867, -2.682164551083141, -0.16816676905990524, -0.7449317767870256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3919731590322595, 0.6808061382983573, 1.8852615233704535, -1.6337601318767279, -1.4141099807966149, -0.3497796362304216, 0.5126224001403346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37598173324735323, -0.36314035844652015, 0.03201440817113183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.254223365770543e-05, 0.10806945740924509, 0.04792130550305777, 0.0, 0.3647937991735709, -0.4699718680880319, -0.6535206563815221, 0.03002883891191481, -0.12642182625846027, 0.007606247809932947, -0.35015517259261514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2585059727578234, 0.15735710450169496, -0.17047539729556585, 0.1395117184068595, -0.048256985511962884, -0.04735691637338743, 0.18044886360065446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20627112445386322, -0.19346924603012725, 0.00966178548277895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994218755304446, 0.03028111445937137, 0.4476983151298864, 0.0, -0.638051332776127, 0.03926257745153229, -1.9332743876008847, -1.2477508441344103, -2.688197452370262, -0.16810928445998144, -0.7622579496811501, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3788697670593844, 0.6884412863522363, 1.8765336079476393, -1.6267770578307548, -1.4168099483184164, -0.35192815298540625, 0.521689746529341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38629983835555937, -0.3728089685767702, 0.03248476983167084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.607229759236975e-05, 0.10954050239831736, 0.04809123129070107, 0.0, 0.3836687558945604, -0.4741673490481384, -0.6670636513701855, 0.03323229116913221, -0.12065802574241588, 0.001149691998475956, -0.3465234578824916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2620678394575032, 0.15270296107757883, -0.17455830845628348, 0.13966148091946143, -0.053999350436031546, -0.04297033509969325, 0.1813469277801277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063621021641231, -0.19337220260500151, 0.009407233210780217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994565462695438, 0.035833492498871876, 0.4500905981744083, 0.0, -0.6178842585120434, 0.015431057167064749, -1.9673061459951764, -1.2459416831053933, -2.6939362728567957, -0.16848615907127737, -0.7794214344100959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3655861790610817, 0.695854000809875, 1.8676041606193066, -1.6197754582617239, -1.4197854587358523, -0.35388704398114024, 0.5308099776510703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3966223687317779, -0.382472854002744, 0.03294257592190131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.934147819820369e-05, 0.11104756079001019, 0.04784566089043712, 0.0, 0.40334148528167124, -0.47663040568935083, -0.6806351678858344, 0.03618322058034058, -0.11477640973067882, -0.007537492225918648, -0.3432696945789163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26567175996605197, 0.1482542891527731, -0.1785889465666572, 0.14003199138061714, -0.05951020834871641, -0.03917781991467974, 0.18240462243458555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064506075243705, -0.1932777085194761, 0.009156121804609322]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994927114146885, 0.04146423281254037, 0.4524652423308594, 0.0, -0.5967002839762974, -0.008428315810264247, -2.002019540532723, -1.2439956941687156, -2.6993758339653144, -0.16940299491767172, -0.7964438610998594, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3521212162123777, 0.7030525069188116, 1.8584760797939717, -1.6127446918799009, -1.4230261952653138, -0.35568434019006, 0.539990275195647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4069491874556222, -0.3921321596665384, 0.0333861414163522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.233029028954226e-05, 0.1126148062733699, 0.04749288312902246, 0.0, 0.42367949071492217, -0.4771874595465799, -0.694267890750924, 0.038919778733553526, -0.10879122217037608, -0.018336716927886926, -0.3404485337952699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2692992569740784, 0.14397012217873117, -0.18256161650669792, 0.14061532763645895, -0.0648147305892294, -0.035945924178395046, 0.1836059508915353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20653637447688533, -0.19318611327588817, 0.008871309889017753]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995302292547737, 0.04717719163981723, 0.45482467173455715, 0.0, -0.5744743481247945, -0.03221191560342329, -2.0374207516577627, -1.2419173313528997, -2.704510349690118, -0.17094461988618306, -0.8133500607854194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.338474363592058, 0.710043323425046, 1.849152611281147, -1.6056747744240032, -1.4265230589240911, -0.3573465118464638, 0.5492370613052514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4172801236089696, -0.40178706148223914, 0.03381250417578785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.50356801704552e-05, 0.1142591765455371, 0.0471885880739552, 0.0, 0.4445187170300572, -0.47567199586318076, -0.7080242225007946, 0.041567256316315505, -0.10269031449607864, -0.030832499370226814, -0.3381239937112001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27293705240639565, 0.13981633012468742, -0.18646937025649496, 0.14139834911795557, -0.06993727317554597, -0.03324343312807645, 0.18493572219208787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2066187230669484, -0.1930980363140145, 0.008527255188713103]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995689562569696, 0.0529764013584553, 0.4571740315963459, 0.0, -0.5511892882837658, -0.05580878834381451, -2.0735186015691505, -1.2397038596385224, -2.70933229877117, -0.17317392474171134, -0.8301683189783522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3246456650861915, 0.716831383794669, 1.8396373038523934, -1.5985564082349324, -1.4302681534635762, -0.3588985346995499, 0.558555999158406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42761497664776876, -0.4114377704488579, 0.03421828106622663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.745400439178555e-05, 0.1159841943727615, 0.046987197235774894, 0.0, 0.4657011968205729, -0.4719374548078243, -0.7219569982277539, 0.04426943428754573, -0.09643898162103368, -0.044586097110565416, -0.33636516385865606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2765739701173271, 0.1357612073924629, -0.19030614857507142, 0.1423673237814152, -0.07490189078970134, -0.03104045706172176, 0.18637875706309256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20669706077598285, -0.1930141793323752, 0.008115537808775676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996089890845417, 0.05888883692989693, 0.4595184800629568, 0.0, -0.526901883015525, -0.07893182781676603, -2.110092321432455, -1.2373198520905968, -2.7134998146319544, -0.17613304333447521, -0.8465907922731724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.310653127481421, 0.7234196128227636, 1.8299352386537378, -1.5913806634700793, -1.4342550396317781, -0.36036587707562534, 0.5679520932180644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4379532912986751, -0.421084771078369, 0.03457703990224904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.006565514422405e-05, 0.11824871142883255, 0.046888969332218, 0.0, 0.485748105364817, -0.4624607894590302, -0.7314743972660956, 0.047680150958511774, -0.08335031721568739, -0.05918237185527777, -0.32844946589640434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27985075209540916, 0.13176458056189136, -0.19404130397311342, 0.14351489529706157, -0.07973772336403934, -0.029346847521508145, 0.18792188119316772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20676629301812666, -0.1929400125902228, 0.007175176720448172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999650598841945, 0.06497439219545284, 0.4618620525147836, 0.0, -0.5017975861345425, -0.10103100307083646, -2.1465184654326808, -1.234674623861658, -2.7161027121378716, -0.17985000619381897, -0.8617340947443358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2965438552155464, 0.7298096042905275, 1.8200545056691093, -1.5841400898195637, -1.4384785532693973, -0.36177571462075087, 0.5774299590274339, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4482940391134155, -0.43072916432052577, 0.034829289387686035]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.3219514806687e-05, 0.12171110531111831, 0.046871449036536506, 0.0, 0.5020859376196491, -0.4419835050814085, -0.7285228800045104, 0.05290456457877694, -0.052057950118340725, -0.07433925718687479, -0.30286604942326895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28218544531749395, 0.1277998293552787, -0.1976146596925673, 0.14481147301031166, -0.0844702727523845, -0.028196750902510892, 0.18955731618739077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2068149562948069, -0.19288786484313503, 0.0050449897087399016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996936354723793, 0.07126622309335441, 0.4642074181845505, 0.0, -0.4760551418039262, -0.12167984801784872, -2.1822476332991476, -1.2316783456747256, -2.716361757472941, -0.18434645519981743, -0.8748556332219445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.282349992373356, 0.7360038559743707, 1.8100036805633035, -1.5768306365002767, -1.4429338617451328, -0.36315222153362153, 0.5869939497017014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4586358746761437, -0.44037239127138705, 0.0349420811878866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.607326086861515e-05, 0.12583661795803136, 0.046907313395338227, 0.0, 0.5148488866123256, -0.4129768989402451, -0.7145833573293369, 0.05992556373864878, -0.005180906701383242, -0.08992898011996939, -0.26243076955217426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28387725684381143, 0.12388503367686289, -0.20101650211611713, 0.14618906638573945, -0.08910616951470839, -0.027530138257413045, 0.1912798134853488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683671125456485, -0.19286453901722592, 0.0022558360040113136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997379143001764, 0.07776899639084262, 0.46655600538470354, 0.0, -0.4498147428041323, -0.1406513385680828, -2.2169279753438587, -1.228267958933324, -2.7138063538676853, -0.18962681856315414, -0.8855349017778712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2680810973387941, 0.7420045623063706, 1.7997893976568422, -1.5694488605442787, -1.4476169525708655, -0.36451601216623863, 0.5966479672555021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46897740788126946, -0.4500159440950995, 0.03491072156614704]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.855765559401911e-05, 0.13005546594976414, 0.046971744003060124, 0.0, 0.5248079799958779, -0.3794298110046814, -0.6936068408942236, 0.0682077348280285, 0.05110807210511245, -0.1056072672667343, -0.21358537111853512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2853779006912345, 0.12001412663999692, -0.20428565812922733, 0.1476355191199587, -0.09366181651465605, -0.02727581265234201, 0.19308035107601457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683066410251555, -0.1928710564742491, -0.00062719243479135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997859488869993, 0.08449411927742755, 0.46890829058041245, 0.0, -0.423228987139392, -0.15802175540469443, -2.249987385598714, -1.2241457216270608, -2.7084187345750443, -0.1957180323196668, -0.893782711064083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.253748187745712, 0.7478123549353348, 1.7894169406863398, -1.5619896511407834, -1.4525252844554515, -0.36588689044702444, 0.6063954373352898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4793171384805335, -0.4596614333567058, 0.03472380389854716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.606917364578337e-05, 0.1345024577316986, 0.047045703914178304, 0.0, 0.5317151132948059, -0.3474083367322327, -0.6611882050971059, 0.08244474612526588, 0.10775238585281527, -0.12182427513025361, -0.1649561857242356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.286658191861644, 0.11615585257928451, -0.20744913941004678, 0.14918418806990458, -0.09816663769171755, -0.027417565615715768, 0.19494940159575466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2067946119852808, -0.19290978523212576, -0.0037383533519975355]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998346517918872, 0.09141406724463508, 0.4712641065329575, 0.0, -0.3963772718905486, -0.17371562945071847, -2.2814760175244753, -1.219360925440738, -2.7002327508410016, -0.20256769550311668, -0.8997134077907735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.239329617790521, 0.7534266524824335, 1.7788887401772873, -1.5544474328996274, -1.4576573351045903, -0.3672799495537857, 0.6162389829320788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48965387642560615, -0.4693104482638417, 0.03440900117209651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.740580977579372e-05, 0.13839895934415067, 0.047116319050902106, 0.0, 0.5370343049768674, -0.31387748092048084, -0.629772638515227, 0.0956959237264568, 0.16371967468085852, -0.13699326366899722, -0.11861393453380784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28837139910381737, 0.11228595094197273, -0.21056401018104937, 0.15084436482312133, -0.1026410129827759, -0.027861182135225065, 0.19687091193577935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20673475890145315, -0.19298029814271903, -0.006296054529012879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998837262983027, 0.0984876371474542, 0.4736228512128817, 0.0, -0.36931688053387773, -0.18773598357623295, -2.3116213955634004, -1.2140251347964188, -2.6893801310269607, -0.21009366952295444, -0.903551021511901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2247864723311725, 0.7588446208607488, 1.7682046484249256, -1.5468142979099502, -1.463013101024749, -0.3687074540384244, 0.6261802995106079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49998676525617464, -0.47896382469304655, 0.03400803337286887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.814901283098824e-05, 0.14147139805638256, 0.04717489359848419, 0.0, 0.5412078271334178, -0.2804070825102892, -0.6029075607785047, 0.1067158128863861, 0.21705239628081968, -0.15051948039675508, -0.07675227442255034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2908629091869693, 0.10835936756630725, -0.21368183504723234, 0.1526626997935423, -0.1071153184031709, -0.028550089692774814, 0.1988263315705836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20665777661136933, -0.19306752858409676, -0.008019355984552914]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999333034850686, 0.105673669795564, 0.4759836606629676, 0.0, -0.3420989319308359, -0.2001784404608327, -2.3406676079286513, -1.2082366255708006, -2.676068847338364, -0.2181991233110978, -0.9055950446480462, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.210074347685301, 0.7640609965663732, 1.7573630303574068, -1.53907990480734, -1.4685941695923914, -0.3701801278166298, 0.636220089338161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5103153663581976, -0.4886219727508629, 0.03356302377694085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.915437353183409e-05, 0.14372065296219605, 0.047216189001717875, 0.0, 0.5443589720608369, -0.2488491376919947, -0.5809242473050138, 0.11577018451236276, 0.2662256737719409, -0.16210907576286726, -0.04088046272290302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2942424929174305, 0.10432751411248795, -0.2168323613503749, 0.1546878620522016, -0.11162137135285063, -0.02945347556410772, 0.2007957965510602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20657202204046005, -0.19316296115632664, -0.00890019191856041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999985724046607, 0.11296025548712392, 0.47834557029358193, 0.0, -0.314801405808413, -0.21118625359244553, -2.3685314160903346, -1.2018226217381398, -2.660668603774185, -0.2268306392523497, -0.906272283081831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.195169438262761, 0.7690689721673792, 1.746363206779349, -1.531232376173149, -1.474403504951756, -0.3717100360535933, 0.6463583943527268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5206393882958547, -0.49828517094116875, 0.03308743223331075]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010484112307689969, 0.1457317138311984, 0.04723819261228707, 0.0, 0.5459505224484582, -0.22015626263225668, -0.5572761632336668, 0.12828007665321645, 0.3080048712835719, -0.17263031882503777, -0.013544768675696726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.298098188450805, 0.10015951202012112, -0.21999647156115473, 0.15695057268381932, -0.11618670718729492, -0.030598164739270173, 0.20276610029131695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20648043875314065, -0.19326396380611774, -0.00951183087260194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000386188984348, 0.1203205677287292, 0.48070759131574803, 0.0, -0.287474989770132, -0.22085635045821775, -2.3954222793204267, -1.1948892232481507, -2.643436904418872, -0.23587381765469737, -0.9059314193362062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.180038166023946, 0.7738608510681475, 1.7352056038860497, -1.5232611904860027, -1.4804446693925655, -0.3733069528951633, 0.6565944608268954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5309588079582727, -0.5079534101611066, 0.032609806416965675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010578970365539403, 0.14720624483210576, 0.04724042044332186, 0.0, 0.5465283207656204, -0.19340193731544422, -0.5378172646018428, 0.1386679697997807, 0.34463398710626403, -0.18086356804695347, 0.006817274912495987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30262544477629516, 0.09583757801536633, -0.22315205786598608, 0.15942371374292477, -0.12082328881618842, -0.031938336831399336, 0.20472132948337274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063883932483591, -0.1933647843987567, -0.009552516326901475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000916494083057, 0.12770763567726107, 0.4830687392069244, 0.0, -0.26019308643958283, -0.22931048175714647, -2.4215463400455506, -1.1875815492128718, -2.6246036628231084, -0.24515225513938024, -0.9048815573555332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1647218529199097, 0.7783765005428815, 1.723859375416625, -1.5150999797468971, -1.486737404398827, -0.37496984157688623, 0.6669070107583583, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5412740650655505, -0.5176261007453624, 0.03217890689697536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010606101974169083, 0.1477413589706372, 0.04722295782352715, 0.0, 0.5456380666109822, -0.16908262597857465, -0.522481214502478, 0.1461534807055757, 0.37666483191527816, -0.1855687496936574, 0.020997239613460877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30632626208072616, 0.09031298949467995, -0.22692456938849484, 0.16322421478210972, -0.12585470012523042, -0.03325777363445849, 0.20625099862925758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20630514214555695, -0.19345381168511577, -0.008617990399806234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001438740509397, 0.13491240604240237, 0.4854280578776173, 0.0, -0.23325017153039881, -0.23668803750654724, -2.4469621100956136, -1.180043409121759, -2.604441923727538, -0.2542616803190728, -0.9034046231800951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1500139995816223, 0.7820642540186723, 1.711999903987663, -1.5061554522402196, -1.4934494542740804, -0.37658879725504163, 0.6770756911532064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5515865469940715, -0.5272662582455687, 0.03200561485251141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444928526822455, 0.1440954073028262, 0.04718637341385814, 0.0, 0.5388582981836805, -0.14755111498801532, -0.5083154010012589, 0.15076280182225638, 0.4032347819114077, -0.18218850359385164, 0.029538683508763354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2941570667657477, 0.07375506951581443, -0.23718942857923855, 0.17889055013354835, -0.13424099750506613, -0.03237911356310805, 0.20337360789696188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2062496385704195, -0.1928031500041254, -0.0034658408892790024]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001956923917136, 0.14209490819490286, 0.48778483406484985, 0.0, -0.20719014955641507, -0.2431537045007487, -2.4717559018778976, -1.1723466381173246, -2.5832851837647595, -0.26272698890159707, -0.9018119287954139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1362925875347156, 0.7846942107354439, 1.6995945594881667, -1.4962533594938423, -1.500654434469294, -0.37804175814020746, 0.6869377230363743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5618772554935478, -0.5362481924237863, 0.03193009384487926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001036366815479113, 0.14365004305001008, 0.047135523744650826, 0.0, 0.5212004394796748, -0.12931333988402918, -0.4958758356456816, 0.15393542008868819, 0.42313479925557457, -0.16930617165048542, 0.031853887693621664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2744282409381327, 0.052599134335431535, -0.24810688998992422, 0.1980418549275443, -0.1440996039042721, -0.029059217703316893, 0.1972406376633577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20581416998952623, -0.17963868356435048, -0.001510420152642911]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20002491398495875, 0.1494178801698363, 0.49014213867983025, 0.0, -0.18248615642303045, -0.24874252779424932, -2.495791256850934, -1.1643342319297219, -2.561549609322388, -0.27017462278306265, -0.9004516927928198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1235910388524077, 0.7862627988346579, 1.686786930289798, -1.4854969415594632, -1.5083462475227143, -0.3792270963843562, 0.6964032961833078, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5721284937799476, -0.544042023523245, 0.03174277720679715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010689491574809543, 0.14645943949866824, 0.047146092299607985, 0.0, 0.494079862667692, -0.11177646587001251, -0.4807070994607294, 0.1602481237520551, 0.43471148884742883, -0.14895267762931144, 0.027204720051883843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25403097364615596, 0.031371761984279836, -0.2561525839673737, 0.21512835868758007, -0.15383626106840426, -0.023706764882974334, 0.1893114629386691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2050247657279953, -0.15587662198917399, -0.00374633276164229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000302436587149, 0.1568804363366327, 0.4925089959261279, 0.0, -0.15942620646426864, -0.2535716429058741, -2.5191037233799887, -1.1561081590561926, -2.5395311185199434, -0.2762882019431225, -0.8995733094187667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1117286539701878, 0.7868744141902151, 1.6737792940401723, -1.474100709544747, -1.5164731868474546, -0.3800749465354888, 0.705439711141863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.582334625025694, -0.5505038053914475, 0.031328551739566904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010659347512320952, 0.14925112333592852, 0.04733714492595309, 0.0, 0.46119899917523643, -0.09658230223249553, -0.4662493305810919, 0.16452145747058344, 0.4403698160488929, -0.12227158320119691, 0.017567667481062112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23724769764439968, 0.012232307111143079, -0.26015272499251113, 0.2279246402943277, -0.16253878649480763, -0.016957003022651775, 0.1807282991711045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.204122624914929, -0.12923563736404983, -0.008284509344604833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000355409762551, 0.1643493632969471, 0.4948989781480506, 0.0, -0.138134306608576, -0.25778286324663996, -2.541755761063006, -1.1478203450866038, -2.517453701537978, -0.2808626769029118, -0.8993496529219878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1004377528853015, 0.7866677740581992, 1.6607635289911855, -1.4622859299485154, -1.5249653079719356, -0.38055155981383115, 0.7140521457823096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5924971178994362, -0.5556901650508949, 0.03066177407118626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010594635080377414, 0.14937853920628794, 0.047799644438453984, 0.0, 0.42583799711385245, -0.08422440681531787, -0.45304075366034996, 0.16575627939177673, 0.4415483396393033, -0.09148949919578589, 0.00447312993557779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22581802169772486, -0.004132802640316704, -0.2603153009797381, 0.2362955919246301, -0.16984242248962297, -0.00953226556684723, 0.17224869280893232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324985747484237, -0.1037271931889466, -0.01333555336761289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004081292641204, 0.17163111684490254, 0.4973273540293955, 0.0, -0.11861098806654552, -0.261506003937954, -2.563792455725704, -1.1396190617008346, -2.4954889007469143, -0.2838319038624897, -0.8998890469110882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0894421809363275, 0.7857788657157315, 1.6478909021820578, -1.4502320834056803, -1.5337515051369732, -0.3806565744431942, 0.7222674722419069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6026210959822068, -0.559746501253625, 0.029776897416194534]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010543900313926698, 0.14563507095910855, 0.048567517626897164, 0.0, 0.3904663708406098, -0.0744628138262803, -0.44073389325396295, 0.1640256677153848, 0.4392960158212723, -0.059384539191558075, -0.010787879782008984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21991143897947918, -0.017778166849353613, -0.2574525361825549, 0.2410769308567017, -0.17572394330075108, -0.0021002925872602293, 0.16430652919194655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20247956165541275, -0.08112672405460414, -0.01769753309983457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004606432832564, 0.1785368757147403, 0.4998084022537411, 0.0, -0.10078082637104352, -0.264847160038961, -2.5852379440488384, -1.131630598596612, -2.4737657902986205, -0.28524416183276086, -0.9012452613483256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.078500262559309, 0.7843260714150962, 1.6352650158000486, -1.4380627524161154, -1.5427684175926506, -0.3804169066440311, 0.7301226067745017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6127129574718959, -0.5628429113478618, 0.028737698239593924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001050280382721323, 0.1381151773967553, 0.04962096448691232, 0.0, 0.35660323391003995, -0.06682312202014098, -0.4289097664626888, 0.15976926208445047, 0.43446220896587195, -0.02824515940542372, -0.027124288744748738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21883836754036934, -0.029055886012705798, -0.2525177276401867, 0.24338661979130038, -0.1803382491135461, 0.004793355983261567, 0.1571026906518956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20183722979378182, -0.06192820188473633, -0.020783983532012218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005129930180776, 0.1849245954383537, 0.5023535969404489, 0.0, -0.0845365476780033, -0.26789192708329723, -2.606108693073243, -1.1239444492086228, -2.452378330247755, -0.2852004259172213, -0.903428031037695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0674226840202274, 0.7824081342080057, 1.6229472251942958, -1.4258507451503226, -1.5519634683297958, -0.3798798984965973, 0.7376575659920607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6227788903479773, -0.5651382965458367, 0.027612209173982813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010469946964228746, 0.12775439447226813, 0.05090389373415543, 0.0, 0.32488557386080436, -0.06089534088672406, -0.4174149804880978, 0.1537229877597814, 0.42774920101731634, 0.0008747183107913163, -0.04365539378738713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22155157078163232, -0.038358744141811715, -0.24635581211505642, 0.24424014531585422, -0.18390101474290552, 0.010740162948676057, 0.15069918435117943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2013186575216267, -0.0459077039594976, -0.02250978131222222]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005652136933838, 0.1907115542078159, 0.5049708022133425, 0.0, -0.06976173780440523, -0.27070753685227544, -2.6264208198234114, -1.116616946684467, -2.4313907896673914, -0.2838218803566358, -0.906412585221189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0560736135802962, 0.7801058082827312, 1.6109657132036308, -1.4136290432962257, -1.5612950664604608, -0.37910605441542466, 0.7449113819247415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6328242153560852, -0.5667667343942321, 0.026461026087480004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444135061213921, 0.1157391753892438, 0.052344105457870035, 0.0, 0.29549619747196143, -0.05631219537956404, -0.40624253500336754, 0.14655005048311465, 0.4197508116072699, 0.02757091121170977, -0.05969108366987838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22698140879862486, -0.046046518505490075, -0.23963023981329837, 0.24443403708193845, -0.18663196261329876, 0.015476881623452673, 0.14507631865361617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200906500162158, -0.032568756967906835, -0.023023661730056176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006173377981204, 0.19586946360562876, 0.5076644609626558, 0.0, -0.05634179204398947, -0.27334548158613015, -2.646193322366273, -1.1096790839813315, -2.410842927702957, -0.2812329746831892, -0.9101485177967618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0443638223042633, 0.7774845919923008, 1.5993249042842526, -1.4014024614291, -1.570731417155611, -0.3781624858127281, 0.751920026015881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6428532286355354, -0.5678352846961159, 0.025332638215552584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010424820947313969, 0.10315818795625725, 0.05387317498626852, 0.0, 0.26839891520831505, -0.05275889467709448, -0.3954500508572305, 0.138757254062713, 0.4109572392886899, 0.051778113468932276, -0.07471865151145703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23419582552065923, -0.05242432580860899, -0.23281617838756566, 0.24453163734251182, -0.1887270139030052, 0.018871372053931603, 0.14017288182279053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005802655890033, -0.02137100603767564, -0.02256775743854842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006693974018563, 0.20041148659983554, 0.5104356354131638, 0.0, -0.04416856961827303, -0.2758444403769414, -2.6654490711305923, -1.103143801672166, -2.3907551627710806, -0.2775528776658062, -0.9145677909379701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.032240873995808, 0.7745974410638581, 1.588013709038981, -1.3891577880418844, -1.5802488161344124, -0.37711757562047643, 0.7587156306949181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6528692669109263, -0.5684268272253782, 0.024262524580118537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010411920747207684, 0.09084045988413576, 0.0554234890101607, 0.0, 0.24346444851432894, -0.049979175816224464, -0.3851149752863885, 0.1307056461833094, 0.4017552986375233, 0.07360194034765936, -0.08838546282416829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2424589661691047, -0.05774301856885468, -0.2262239049054323, 0.24489346774431225, -0.19034797957602634, 0.020898203845033683, 0.13591209358074058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032076550781866, -0.011830850585245457, -0.02140227270868092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007214257134473, 0.2043774343813399, 0.5132834444778108, 0.0, -0.033141879221293254, -0.27823311442357535, -2.684214783748266, -1.0970116831686958, -2.3711334911723347, -0.27289151361168223, -0.9195916030855968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0196792372387637, 0.7714870996542419, 1.577012080120262, -1.3768717128358068, -1.5898299178620672, -0.376037003117718, 0.7653264677326032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6628748614477549, -0.5686045085855391, 0.023274225345194223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010405662318178713, 0.07931895563008712, 0.05695618129293898, 0.0, 0.22053380793959546, -0.04777348093267944, -0.3753142523534738, 0.12264237006940129, 0.3924334319749157, 0.09322728108248012, -0.10047624295253367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.251232735140885, -0.06220682819232286, -0.22003257837437873, 0.24572150412155103, -0.191622034553094, 0.02161145005516844, 0.13221674075370154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001118907365725, -0.003553627203219339, -0.019765984698486314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007734580778586, 0.20782070618049545, 0.5162057356413299, 0.0, -0.02316952921589255, -0.2805327086574647, -2.7025206472294165, -1.0912751301891823, -2.3519738846130913, -0.26734808709481267, -0.9251359659670314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0066716891018626, 0.7681879876718668, 1.5662958363212114, -1.364516539676587, -1.5994622264425942, -0.3749810550619353, 0.7717773035049438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728719094996554, -0.5684161418783988, 0.022381311534141354]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010406472882246143, 0.06886543598311097, 0.0584458232703806, 0.0, 0.19944700010801403, -0.04599188467778787, -0.36611726962300406, 0.11473105959026818, 0.3831921311848679, 0.11086853033739165, -0.11088725762869056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26015096273802274, -0.06598223964750083, -0.21432487598101155, 0.24710346318439644, -0.19264617161054026, 0.021118961115654065, 0.1290167154468116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994096103801032, 0.003767334142805944, -0.017858276221057384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008255327007832, 0.2107984551058236, 0.5192101868201725, 0.0, -0.014166840177746965, -0.2827589651423013, -2.7203998728202277, -1.085921389661834, -2.333265997210729, -0.2610109256209237, -0.9311159707638332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.993222525276789, 0.76472770791297, 1.5558399599130788, -1.3520640084958147, -1.609136898369661, -0.3740030351449078, 0.7780898891731596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6828618146769264, -0.5678979208460078, 0.02158961746419203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010414924584927073, 0.059554978506562724, 0.060089023576853036, 0.0, 0.18005378076291173, -0.044525129696731926, -0.35758451181622114, 0.10707481054696666, 0.3741577480472417, 0.12674322947777925, -0.11960009593603711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2689832765014719, -0.06920559517793774, -0.2091175281626519, 0.24905062361544741, -0.19349343854133583, 0.01956039834054967, 0.12625171336431662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19979810354541996, 0.01036442064782242, -0.015833881398986463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008787845500087, 0.21333432017666262, 0.522278620524105, 0.0, -0.005963419259842758, -0.2847067784692105, -2.737706908660592, -1.0808938141815105, -2.3150267722676117, -0.25438667800412285, -0.9374635516762867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9793618168468088, 0.7611051078601969, 1.545609423592007, -1.3394608678986315, -1.6188542055022237, -0.3731361931769705, 0.784273511539081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6928467960164502, -0.5671346529160782, 0.02093020073211555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010650369845106335, 0.050717301416780575, 0.06136867407865102, 0.0, 0.16406841835808414, -0.038956266538184035, -0.34614071680728536, 0.10055150960646979, 0.3647844988623467, 0.13248495233601743, -0.12695161824906995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27721416859960457, -0.07245200105546167, -0.20461072642143427, 0.2520628119436626, -0.194346142651256, 0.01733683935874627, 0.12367244731842914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19969962679047468, 0.015265358598590295, -0.013188334641529539]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000932460772157, 0.2154911957901415, 0.5254075520960675, 0.0, 0.0015154044261366864, -0.28641516619292723, -2.7544320930412285, -1.076174171725622, -2.2972498271597006, -0.24759982073920533, -0.9441141009023792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9651278873460428, 0.757327427091728, 1.535580448860818, -1.326672138264618, -1.628612812424153, -0.37240896197700574, 0.7903376336523634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7028278828753675, -0.5661656331890602, 0.020389486558202795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010735244429674809, 0.04313751226957778, 0.0625786314392504, 0.0, 0.14957647371958888, -0.03416775447433472, -0.33450368761273663, 0.09439284911777152, 0.35553890215822376, 0.13573714529835043, -0.13301098452185098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2846785900153182, -0.07555361536937943, -0.20057949462378213, 0.25577459268027014, -0.19517213843858824, 0.01454462399929483, 0.12128244226564817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.199621737178345, 0.019380394540359974, -0.010814283478255146]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000986504638207, 0.2173348800863795, 0.5285963538711298, 0.0, 0.008311286985787932, -0.2879703140158385, -2.770613356296178, -1.071752895513645, -2.2799188962291113, -0.24064150349451635, -0.9510100879683961, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9505529498723302, 0.7534056826233598, 1.5257378740419243, -1.3136770586139697, -1.63841007581735, -0.37184397678607, 0.7962921332243709, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7128055169800916, -0.5650064298475672, 0.019945411914984862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010808773209972387, 0.036873685924759945, 0.06377603550124566, 0.0, 0.13591765119302487, -0.031102956458224976, -0.32362526509899225, 0.08842552423953609, 0.3466186186117867, 0.13916634489377944, -0.13791974132033838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2914987494742535, -0.07843488936736323, -0.19685149637787305, 0.25990159301296684, -0.19594526786394395, 0.011299703818714464, 0.11908999144014908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19955268209448396, 0.023184066829859785, -0.008881492864358671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001040952281578, 0.21892164502751066, 0.5318443998538492, 0.0, 0.014455434372994066, -0.2894449297458632, -2.7863038589103057, -1.0676217341506595, -2.263014026217533, -0.23346849295648808, -0.9581014231716674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9356598942300804, 0.7493518268839664, 1.5160721145437042, -1.3004642700198759, -1.6482428027961602, -0.37145864779806914, 0.8021471910765554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7227798395497232, -0.5636600458570635, 0.019578016659266558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010889528674247463, 0.03173529882262352, 0.0649609196543887, 0.0, 0.12288294774412264, -0.029492314600493903, -0.313810052282559, 0.08262322725971165, 0.33809740023156404, 0.14346021076056528, -0.14182670406542525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2978611128449939, -0.08107711478786886, -0.19331518996440414, 0.2642557718818771, -0.19665453957620216, 0.007706579760017614, 0.11710115704369055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19948645139263124, 0.026927679810074084, -0.007347905114366092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001095818476272, 0.2202943968225748, 0.535150869996002, 0.0, 0.019976112404964497, -0.2908868408754237, -2.801560742506763, -1.0637723948338313, -2.246514853532375, -0.2260387914595803, -0.9653442577370467, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9204627132754218, 0.7451771967137655, 1.5065767335510407, -1.2870279213106035, -1.6581079764407811, -0.3712661111733493, 0.8079130441774274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7327508384249672, -0.5621229025816208, 0.01927182718937029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010973238938801623, 0.027455035901282798, 0.06612940284305621, 0.0, 0.11041356063940856, -0.028838222591209578, -0.3051376719291418, 0.07698678633656415, 0.3299834537031666, 0.1485940299381555, -0.14485669130758602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3039436190931732, -0.08349260340401757, -0.189907619853269, 0.26872697418544794, -0.19730347289241743, 0.003850732494397405, 0.11531706201743988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19941997750488044, 0.030742865508854446, -0.0061237893979253916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20011511096299092, 0.2214825190671099, 0.5385151065100857, 0.0, 0.02490084713840034, -0.2923229338625861, -2.8164412711336357, -1.060196351782816, -2.2304025030501005, -0.21832156697497618, -0.9726993825050722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9049681306376484, 0.740891755553815, 1.4972467377444765, -1.2733648666517141, -1.6680033011218867, -0.3712761292836445, 0.8135997040895893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7427184266565153, -0.560388285861029, 0.019015717754810958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011058230727444141, 0.023762444890702263, 0.06728473028167319, 0.0, 0.09849469466871684, -0.028721859743248285, -0.2976105725374558, 0.07152086102030841, 0.32224700964548914, 0.15434448969208248, -0.14710249536050946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30989165275546887, -0.08570882319900835, -0.1865999161312844, 0.27326109317778985, -0.19790649362210908, -0.00020036220590430396, 0.11373319824323874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935176463096194, 0.03469233441183588, -0.0051221886911865955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012068354139295, 0.22250349531401678, 0.5419369045324964, 0.0, 0.029256928531896972, -0.29376602433815924, -2.8310013768663658, -1.0568847414431133, -2.2146607151661373, -0.21029745116627052, -0.9801307890007165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8891775148909307, 0.7365037811966567, 1.4880774850525833, -1.2594727666522887, -1.677927543943993, -0.37149579637202673, 0.8192166918784729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.752682486082162, -0.5584484377725315, 0.018802084615086322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011145156804087516, 0.020419524938137586, 0.06843596044821347, 0.0, 0.08712162786993259, -0.02886180951146266, -0.2912021146546042, 0.06623220679405235, 0.3148357576792621, 0.1604823161741131, -0.14862812991288768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3158123149343549, -0.08775948714316552, -0.18338505383786374, 0.2778419999885099, -0.19848485644212302, -0.00439334176764448, 0.112339755777672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19928118851293328, 0.0387969617699493, -0.004272662794492707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012628164617755, 0.22332134060079772, 0.54541662471814, 0.0, 0.03317120156856523, -0.29518464960895535, -2.8451380890300952, -1.053961604220274, -2.1992726208632316, -0.20265878664500153, -0.9876002580722529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8730997429735209, 0.7319946575093498, 1.4790548783712623, -1.2453195416574887, -1.687887002196704, -0.37191213155652425, 0.8247616904031708, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7626439397110358, -0.556356609092534, 0.018669902169850008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001119620956917603, 0.01635690573561878, 0.06959440371287186, 0.0, 0.07828546073336504, -0.02837250541592201, -0.282734243274592, 0.05846274445678641, 0.30776188605811694, 0.15277329042537996, -0.14938938143072922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32155543834819605, -0.0901824737461377, -0.18045213362641968, 0.28306449989600013, -0.1991891650542251, -0.00832670368995064, 0.11089997049395796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19922907257747532, 0.04183657359994846, -0.002643648904726283]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013192442139177, 0.2239482275425103, 0.5489548371269524, 0.0, 0.0366715792278375, -0.296586524353173, -2.8588493933976524, -1.0514203929343469, -2.184236114366281, -0.1954379262848652, -0.9950902730344263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8567527786674105, 0.7273588576734159, 1.4701719485389229, -1.230888881533351, -1.6978848911636142, -0.37251543196268055, 0.8302341701041117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7726029312808944, -0.5541258337645512, 0.018610119682379557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001128555042845191, 0.0125377388342514, 0.07076424817624641, 0.0, 0.07000755318544544, -0.028037494884353635, -0.27422608735114595, 0.050824225718544155, 0.3007301299390082, 0.14441720720272663, -0.1498002992434688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32693928612220846, -0.09271599671867779, -0.17765859664678813, 0.28861320248275546, -0.1999577793382039, -0.012066008123126602, 0.1094495940188172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917983139717088, 0.044615506559656834, -0.0011956497494090225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013761457522716, 0.22440734591479483, 0.5525510066268541, 0.0, 0.03975911638397082, -0.29798216934315713, -2.8721656295211786, -1.0492191300271183, -2.1695526216527776, -0.18848173123026996, -1.0025971718647806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8401509814292484, 0.7225974376254728, 1.461426296142665, -1.2161747018287186, -1.7079221563356972, -0.3732971774069232, 0.8356348772421495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7825592728935553, -0.5517519790258053, 0.018604268532772555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011380307670761093, 0.009182367445690917, 0.07192338999803456, 0.0, 0.06175074312266636, -0.027912899799682093, -0.2663247224705193, 0.044025258144572164, 0.29366985427007, 0.13912390109190506, -0.15013797660708325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3320359447632418, -0.09522840095886133, -0.17491304792515783, 0.2942835940926487, -0.20074530344166105, -0.01563490888485266, 0.1080141427607551, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19912683225321814, 0.04747709477491714, -0.00011702299214006178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014335289543783, 0.22472031035488813, 0.5562052394000923, 0.0, 0.042430718224349184, -0.2993775663249582, -2.885124494559544, -1.0473129015067846, -2.155222804147192, -0.1816201348745458, -1.01012474190697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8233031935612874, 0.7177142448998596, 1.4528175204778178, -1.2011759013625687, -1.7179983908228533, -0.374249479327445, 0.8409652330108597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925126832685195, -0.5492244957458804, 0.018635373875526565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011476640421320383, 0.006259288801865879, 0.07308465546476407, 0.0, 0.05343203680756739, -0.027907939636021756, -0.25917730076730283, 0.03812457040667647, 0.28659635011170964, 0.13723192711448282, -0.1505514008437909, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.33695575735921823, -0.09766385451226353, -0.17217551329694306, 0.2999760093229975, -0.2015246897431223, -0.019046038410436672, 0.10660711537420353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906820749928394, 0.05054966559849752, 0.0006221068550801514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014914122512492, 0.22490281905863652, 0.5599181172915517, 0.0, 0.044685009011025914, -0.3007746371064331, -2.897763192892381, -1.0456630527405861, -2.1412454289020606, -0.1747151974114972, -1.0176787139885983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8062133777782159, 0.7127138428914443, 1.4443454795666644, -1.1858927542576552, -1.7281125254817933, -0.37536492761112034, 0.8462267964200866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8024628663707979, -0.5465312346100106, 0.018690277971370874]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011576659374156097, 0.0036501740749680742, 0.0742575578291891, 0.0, 0.04508581573353464, -0.027941415629497295, -0.25277396665674096, 0.03299697532397076, 0.2795475049026293, 0.13809874926097254, -0.15107944163256468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3417963156614319, -0.100008040168305, -0.1694408182230674, 0.30566294209827055, -0.20228269317880074, -0.022308965673506504, 0.10523126818453868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1990036620455675, 0.05386522271739528, 0.0010980819168861728]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20015498241295324, 0.22496358788852341, 0.5636906952949815, 0.0, 0.046523124895129254, -0.30217304171259973, -2.910116870810712, -1.0442383548647112, -2.127617660175425, -0.16766711338600437, -1.025262800625812, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7888816327849963, 0.7076004604520697, 1.4360093419839672, -1.170324783273599, -1.7382632426248827, -0.3766364801543263, 0.8514208330493006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8124095464110179, -0.5436605129536562, 0.018759558823811803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011682375656639517, 0.0012153765977381483, 0.0754515600685947, 0.0, 0.036762317682066795, -0.027968092123332625, -0.2470735583666168, 0.028493957517499034, 0.2725553745327172, 0.1409616805098563, -0.15168173274427474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3466348998643898, -0.10226764878749364, -0.16672275165394146, 0.31135941968112435, -0.20301434286178807, -0.02543105086411955, 0.10388073258428018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19893360080440123, 0.05741443312708689, 0.0013856170488185833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001608631206162, 0.22486724977568132, 0.5675244651508963, 0.0, 0.04804091382447449, -0.3035412422848025, -2.922052328864245, -1.043124700167149, -2.114336383673618, -0.16144541042735452, -1.0328762966158225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7713251667984461, 0.7023538524834112, 1.4278003950431948, -1.1544406355268644, -1.7484541924423087, -0.3780359169281584, 0.8565366409104427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8223535527855577, -0.5406644830067112, 0.018874481121896925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011761415325926333, -0.0019267622568418198, 0.0766753971182944, 0.0, 0.030355778586904754, -0.02736401144405591, -0.23870916107066367, 0.022273093951243095, 0.2656255300361335, 0.1244340591729968, -0.15226991980021082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35112931973100436, -0.10493215937317057, -0.16417893881545068, 0.3176829549346932, -0.20381899634852044, -0.02798873547664122, 0.1023161572228418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19888012749079415, 0.05992059893890097, 0.0022984459617024834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20016679470852397, 0.22461810660336734, 0.5714204886721297, 0.0, 0.0492515606625755, -0.3048795567549562, -2.9335321144560953, -1.0423074447214344, -2.10140738073954, -0.15596642624339424, -1.0405372644415392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7535642511419999, 0.6969653494000717, 1.4197151124779401, -1.1382226627253809, -1.7586848946400433, -0.37953926699620993, 0.8615644584658677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8322950464256667, -0.5375590699744391, 0.019029445546714298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011863175815503065, -0.0049828634462796215, 0.0779204704246687, 0.0, 0.024212936762020215, -0.026766289403073663, -0.229595711837008, 0.01634510891429119, 0.25858005868156314, 0.1095796836792056, -0.15321935651433463, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3552183131289241, -0.10777006166679028, -0.16170565130509318, 0.3243594560296713, -0.2046140439546916, -0.030067001361030556, 0.10055635110850149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1988298728021799, 0.06210826064544102, 0.003099288496347424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200172776239212, 0.2242322692592346, 0.5753793197616183, 0.0, 0.050143828812840734, -0.3061910582581071, -2.944550534505061, -1.041743376056535, -2.0888357341121013, -0.15093367718695333, -1.048277236264781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7356141941268067, 0.691432512186373, 1.4117532741877563, -1.121661763852356, -1.7689514159459603, -0.3811251082443771, 0.86649506189296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8422339086677469, -0.5343440199178914, 0.019210896739374525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001196306137608304, -0.007716746882654741, 0.07917662178977203, 0.0, 0.0178453630053046, -0.026230030063017495, -0.2203684009793198, 0.011281373297985921, 0.25143293254877075, 0.1006549811288182, -0.15479943646483557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3590011403038624, -0.11065674427397341, -0.15923676580367516, 0.3312179774604951, -0.2053304261183416, -0.031716824963344104, 0.09861206854184656, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19877724484160614, 0.06430100113095442, 0.003629023853204522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017880771966834, 0.2237276625238269, 0.5794013303291399, 0.0, 0.050699909006210096, -0.30747661967759615, -2.9551116517246165, -1.0413867886406278, -2.0766216597974223, -0.14608404137141487, -1.0561326296271798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7174848001385788, 0.6857562710597147, 1.4039161304800842, -1.10475315105645, -1.7792470152797084, -0.3827741958966008, 0.871319355442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8521699154814953, -0.5310119017509993, 0.01940522188486421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012062960912663622, -0.01009213470815384, 0.08044021135043324, 0.0, 0.011121603867387315, -0.025711228389780374, -0.21122234439110926, 0.007131748318146876, 0.2442814862935846, 0.09699271631076936, -0.1571078672479778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36258787976455753, -0.11352482253316624, -0.1567428741534436, 0.33817225591812267, -0.20591198667496285, -0.032981753044473566, 0.0964858709840395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.198720136274969, 0.06664236333784118, 0.0038865029097937334]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001848920125801, 0.22311939837896405, 0.5834870489289138, 0.0, 0.05090078540002527, -0.308735882796434, -2.9652229966883774, -1.0411980034684942, -2.064759670416598, -0.14123323192581774, -1.0641371565315465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6991809830148032, 0.679939291147258, 1.3962051220839664, -1.087493451223696, -1.7895626538601601, -0.3844693487373193, 0.8760279613648302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8621028082079024, -0.5275522348262791, 0.01960080649115936]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012168585823553865, -0.012165282897256904, 0.08171437199547749, 0.0, 0.004017527876303342, -0.025185262376756567, -0.2022268992752162, 0.0037757034426703215, 0.23723978761649236, 0.09701618891194237, -0.16009053808733326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3660763424755128, -0.1163395982491342, -0.15422016792235796, 0.34519399665507955, -0.2063127716090326, -0.03390305681437007, 0.09417211845336478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19865785452814178, 0.06919333849440365, 0.003911692125903012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001910339768254, 0.22241740746155528, 0.5876373692829787, 0.0, 0.05072825256032961, -0.3099686862518699, -2.9748947407521658, -1.0411450762759276, -2.0532395768694993, -0.13626393879654164, -1.0723170910833948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6807032804433021, 0.6739849745819401, 1.388621114169803, -1.0698788282800074, -1.7998873562412572, -0.3861952801931571, 0.8806108106665858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8720323358314703, -0.5239535080029184, 0.019788621026410307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012283928490566007, -0.014039818348175664, 0.083006407081299, 0.0, -0.0034506567939130836, -0.024656069108718866, -0.19343488127577046, 0.0010585438513315741, 0.2304018709419729, 0.09938586258552179, -0.1635986910369645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3695540514300244, -0.1190863313063596, -0.15168015828326817, 0.3522924588737728, -0.20649404762193996, -0.03451862911675506, 0.09165698603511138, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19859055247135768, 0.07197453646721513, 0.0037562907050189094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001972276229123, 0.22160015992593438, 0.5918536565550914, 0.0, 0.05023534327615232, -0.31115485912438157, -2.98399731890119, -1.0412776896283897, -2.0420522122641835, -0.1323673535576393, -1.08069297108184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6620730424338469, 0.6678791574614724, 1.3811606617335281, -1.0518815424837384, -1.8102108812872644, -0.3879171685167433, 0.8850471905233438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8819592391097035, -0.5202568933142251, 0.019987756381997294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012387292173853077, -0.016344950712418115, 0.08432574544225284, 0.0, -0.00985818568354585, -0.023723457450233045, -0.1820515629804796, -0.0026522670492431072, 0.22374729210631697, 0.07793170477804703, -0.16751759996890506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3726047601891036, -0.12211634240935253, -0.1492090487254995, 0.35994571592537883, -0.2064705009201449, -0.034437766471724654, 0.08872759713516082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853806556466372, 0.07393229377386722, 0.0039827071117397314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20020347439010194, 0.22066886640840974, 0.5961368789821828, 0.0, 0.04942137616753238, -0.3122911282120764, -2.9924717451619225, -1.0415807058060549, -2.0311924115217646, -0.12926459359144046, -1.0893046900564256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6433087343387187, 0.6616151695062485, 1.3738233634988397, -1.0334828954614335, -1.820518215348053, -0.3896034935502784, 0.8893152917455368, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918837518366295, -0.5164777926262232, 0.020196315181244682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001249353437924127, -0.018625870350492735, 0.0856644485418279, 0.0, -0.0162793421723988, -0.0227253817538959, -0.1694885252146481, -0.0060603235533009635, 0.21719601484837767, 0.06205519932397649, -0.17223437949171228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3752861619025646, -0.12527975910447817, -0.1467459646937689, 0.36797294044609824, -0.20614668121577498, -0.03372650067070167, 0.08536202444386097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984902545385202, 0.07558201376003792, 0.004171175984947794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002097713156489, 0.21963330701260128, 0.6004876430588264, 0.0, 0.04826735161790908, -0.31337521052871675, -3.0002854311434213, -1.042017856951844, -2.020651124882025, -0.12654774583476963, -1.0982068765058308, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6244231401634923, 0.6551909860127477, 1.3666107181270413, -1.014669781954262, -1.830789814952071, -0.3912255494765068, 0.8933920015145673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9018058862955415, -0.5126188329621287, 0.020406874864572447]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001259385109389794, -0.020711187916169344, 0.08701528153287227, 0.0, -0.023080490992466042, -0.021681646332807118, -0.1562737196299728, -0.008743022915782392, 0.21082573279478972, 0.054336955133416694, -0.17804372898810442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37771188350452867, -0.12848366987001567, -0.14425290743596728, 0.3762622701434281, -0.2054319920803594, -0.032441118524568074, 0.08153419538060984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19844268917823923, 0.07717919328188974, 0.004211193666555281]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021612092282184, 0.21850629281013784, 0.6049063830180879, 0.0, 0.04674694556987107, -0.3144054031470295, -3.0074185370116227, -1.0425507553929605, -2.010411408134718, -0.12394384477934386, -1.1074574531963899, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6054236679376318, 0.6486078022609617, 1.3595250401006225, -0.9954321389298569, -1.8410018235275876, -0.3927577856739413, 0.897252692534199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9117255410177183, -0.5086754720012359, 0.020610626904816205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001269921434586169, -0.022540284049268652, 0.08837479918522834, 0.0, -0.030408120960760072, -0.02060385236625595, -0.1426621173640283, -0.01065796882233028, 0.20479433494613986, 0.052078021108515345, -0.18501153381118132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37998944451720995, -0.1316636750357197, -0.1417135605283744, 0.38475286048810226, -0.20424017151033333, -0.030644723948690555, 0.07721382039263426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19839309444353564, 0.07886721921785816, 0.004075040804875125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022253027785625, 0.2172997061063792, 0.6093940275144712, 0.0, 0.044831410138811985, -0.31538213075779564, -3.0138605032598287, -1.0431464819052012, -2.0004478758145035, -0.12130496351048073, -1.1171087473807155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5863125474238096, 0.6418689300364602, 1.3525686390384142, -0.975760852223192, -1.8511263198677277, -0.3941779859496728, 0.9008708398699348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9216425579681401, -0.5046390286167527, 0.020799215252272733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012818710068790215, -0.024131734075172735, 0.08975288992766754, 0.0, -0.03831070862118175, -0.01953455221532188, -0.12883932496411699, -0.011914530244816071, 0.19927064640429257, 0.05277762537726262, -0.1930258836865146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38222241027644466, -0.13477744449003068, -0.13912802124416684, 0.39342573413329984, -0.20248992680280403, -0.02840400551462917, 0.07236294671471433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19834033900843503, 0.08072886768966328, 0.0037717669491305742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022900860672177, 0.21602149077378158, 0.6139508566643666, 0.0, 0.04249304529260065, -0.3163082802897171, -3.019609641149978, -1.0437794882828788, -1.9907280811770776, -0.11855834742913957, -1.127203397503628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56708689339683, 0.6349787981933329, 1.3457432785905576, -0.9556459545254953, -1.8611315315344155, -0.39546708486206655, 0.9042174428273831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9315567687691604, -0.5004987690426352, 0.020966024033625068]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012956657731027664, -0.02556430665195258, 0.09113658299790565, 0.0, -0.04676729692422672, -0.01852299063842921, -0.11498275780298244, -0.012660127553552256, 0.1943958927485175, 0.054932321626823176, -0.20189300245824846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38451308053959093, -0.13780263686254624, -0.136507208957131, 0.4022979539539349, -0.20010423333375432, -0.02578197824787499, 0.06693205914896853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982842160204063, 0.08280519148234991, 0.003336175627046675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20023567613729168, 0.21468232598148812, 0.618579669380404, 0.0, 0.039716685832498946, -0.3170317589450412, -3.0246594038591277, -1.0443415770723183, -1.9812217011084206, -0.11567135386636834, -1.13777905015814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477513703633965, 0.6279428756470102, 1.3390496574407549, -0.9350758302929199, -1.8709811549442146, -0.39660843413451846, 0.9072602766909373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9414681136338643, -0.49624739219259395, 0.02109857982582755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013335061139804465, -0.02678329584586907, 0.09257625432074831, 0.0, -0.05552718920203407, -0.014469573106482808, -0.1009952541829951, -0.011241775788790789, 0.19012760137314005, 0.05773987125542451, -0.21151305309023985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3867104606686719, -0.14071845092645366, -0.13387242299605406, 0.4114024846515084, -0.1969924681959818, -0.022826985449038478, 0.06085667727108461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982268972940784, 0.08502753700082558, 0.0026511158440496816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024248448796664, 0.2132817010339462, 0.6232850539165122, 0.0, 0.03648736491123274, -0.3176151113242534, -3.029022659188296, -1.0448138848933215, -1.9718877847713319, -0.11262628356749618, -1.1488617258468545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.52829997285123, 0.6207655905849384, 1.332488202871619, -0.914035823072634, -1.8806351577949825, -0.39758655139198784, 0.909962810616463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.951376543075006, -0.49187641030852547, 0.02119267081108958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013616701349902424, -0.028012498950838564, 0.0941076907221639, 0.0, -0.06458641842532403, -0.011667047584244146, -0.08726510658336331, -0.009446156420062756, 0.1866783267417718, 0.060901405977443104, -0.2216535137742917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3890279502433304, -0.1435457012414359, -0.1312290913827172, 0.42080014440571706, -0.19308005701535966, -0.01956234514938717, 0.054050678510513796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19816858882283422, 0.08741963768137005, 0.0018818197052405962]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024942643988033, 0.21179744237757436, 0.6280614356300516, 0.0, 0.032837414321974116, -0.31812578977269435, -3.0326111904443955, -1.0452508930410527, -1.9626876112700173, -0.11087403638981642, -1.1604767590735159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5087462976732324, 0.6134391523867183, 1.3260590187239967, -0.8924938010822095, -1.8900486175493625, -0.3983666197484187, 0.9122756140155615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9612828171656946, -0.48741756737242403, 0.021263334940033223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001388390382738015, -0.029685173127436876, 0.09552763427078588, 0.0, -0.07299901178517247, -0.010213568968818868, -0.07177062512199014, -0.008740162954621399, 0.18400347002629233, 0.035044943553595116, -0.23230066453322595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.391073503559951, -0.14652876396440218, -0.1285836829524449, 0.430840439808488, -0.1882691950876016, -0.015601367128617337, 0.04625606798196829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1981254818137743, 0.0891768587220289, 0.0014132825788728686]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025648617165462, 0.2102159997234052, 0.6329105085744566, 0.0, 0.02877294974059154, -0.31860398466958934, -3.0353794732601376, -1.0456722544572943, -1.9535790164030598, -0.10975106669980453, -1.1726841966576451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48909731099497733, 0.6059579119762081, 1.3197643797852852, -0.8704192973769448, -1.8991693651637631, -0.39891412960312955, 0.9141417636527343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711873739518471, -0.4828893418700921, 0.0213193368087825]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001411946354858873, -0.03162885308338303, 0.09698145888810075, 0.0, -0.08128929162765157, -0.009563897937899444, -0.05536565631484504, -0.008427228324830742, 0.18217189733915135, 0.022459393800237974, -0.24414875168258673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39297973356510235, -0.1496248082102037, -0.12589277877422897, 0.44149007410529506, -0.1824149522880104, -0.01095019709421708, 0.03732299274345578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19809113572304787, 0.0905645100466391, 0.0011200373749855554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20026365067228066, 0.20853153423470647, 0.6378348053398177, 0.0, 0.024287414359991967, -0.31906383544072553, -3.03730358821359, -1.0460803808476857, -1.944506846300838, -0.10880336925481057, -1.1855679286607015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46935386567918885, 0.5983182674664688, 1.3136084475674703, -0.8477824018146772, -1.9079370164244762, -0.3991966785218747, 0.9154962070713135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9810904491676253, -0.47830120746567945, 0.021365983100818976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014329001252086628, -0.0336893097739748, 0.09848593530722288, 0.0, -0.08971070761199146, -0.009197015422723371, -0.03848229906904507, -0.008162527807830557, 0.18144340204443837, 0.018953948899879114, -0.2576746400611291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39486890631576926, -0.1527928901947863, -0.12311864435629659, 0.4527379112453502, -0.17535302521426147, -0.005650978374902695, 0.02708886837158525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19806150431556513, 0.09176268808825254, 0.0009329258407294982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002709181633583, 0.2067445984866543, 0.6432883074780156, 0.0, 0.019368020415770022, -0.319506030596099, -3.0383767612417256, -1.0464716606443134, -1.93539817392384, -0.10785793321986444, -1.1992183447754208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.449511737566043, 0.5905186190172917, 1.30759712755751, -0.8245528155742337, -1.9162819395303767, -0.39918565990323196, 0.9162647015301013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9909921334418351, -0.4736560022976525, 0.021405717349798476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014534982155259296, -0.035738714961043055, 0.1090700427639566, 0.0, -0.0983878788844389, -0.008843903107469055, -0.021463460562710514, -0.007825595932554615, 0.1821734475399597, 0.018908720698922653, -0.2730083222943843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39684256226291714, -0.15599296898354148, -0.1202264001992059, 0.46459172480887045, -0.1668984621180081, 0.0002203723728545822, 0.015369889175756525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19803368548419537, 0.09290410336053989, 0.000794684979589968]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20027829438051795, 0.20485868510348465, 0.6490013560727583, 0.0, 0.014002434650858962, -0.31992610835046786, -3.0386077281967667, -1.0468412358708508, -1.9261612032181843, -0.10686461645591573, -1.2137239690189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295630481332781, 0.5825587072681266, 1.3017382359732208, -0.8006983855868464, -1.9241240546061331, -0.39885668361580096, 0.9163618604901093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0008924345494923, -0.4689530184259971, 0.02143932756822293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001475243431933699, -0.037718267663393076, 0.11426097189485505, 0.0, -0.10731171529822119, -0.008401555087377478, -0.0046193391008222465, -0.007391504530747066, 0.18473941411311273, 0.01986633527897399, -0.2901124848695834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39897378865529753, -0.15919823498330188, -0.11717783168578469, 0.4770885997477463, -0.15684230151512948, 0.006579525748620504, 0.0019431792001582751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980060221531453, 0.09405967743310696, 0.0006722043684891009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028578925979554, 0.20287743274338085, 0.6547406686796089, 0.0, 0.008185018820865536, -0.32031794640898287, -3.0380197116706626, -1.0471838245626715, -1.9166848868198592, -0.10581108299932915, -1.2291713152384198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.409497880984442, 0.5744384300934184, 1.2960420336682963, -0.7761829962429637, -1.9313712603623479, -0.39818884409194577, 0.9156880981674309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0107913532621287, -0.46419123734401335, 0.021467110255929775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014989758555187285, -0.03962504720207571, 0.11478625213701081, 0.0, -0.11634831659986852, -0.007836761170300528, 0.011760330522081603, -0.0068517738364139965, 0.18952632796650123, 0.02107066913173159, -0.30894692439039756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4013033429767219, -0.16240554349416467, -0.11392404609848922, 0.49030778687765375, -0.1449441151242955, 0.013356790477103832, -0.01347524645356626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19797837425272766, 0.09523562163967537, 0.0005556537541368603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20029341668299114, 0.20080310284452807, 0.6604121090446456, 0.0, 0.001921849586408484, -0.3206748265522026, -3.036649950845352, -1.0474931959378289, -1.9068372060650318, -0.10469342341170036, -1.2456491252742798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38930633750726457, 0.5661566921582276, 1.2905223641067847, -0.750964653980663, -1.9379170515353874, -0.3971633693842987, 0.9141253637504341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0206889396240197, -0.45937220777499244, 0.021489539567299338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015254846391213545, -0.04148659797705568, 0.11342880730073404, 0.0, -0.12526338468914103, -0.007137602864394741, 0.027395216506216978, -0.006187427503146391, 0.1969536150965476, 0.022353191752575823, -0.32955620071719854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.403830869543549, -0.16563475870381658, -0.11039339123023295, 0.5043668452460132, -0.13091582346079012, 0.020509494152941406, -0.03125468833993677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979517272378216, 0.09638059138041875, 0.00044858622739128284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030119568854826, 0.19863638606599057, 0.6660139722038477, 0.0, -0.0047654859416252715, -0.32098958444084497, -3.034549899605448, -1.047761372718335, -1.8964610837443059, -0.10350850752967147, -1.2632545889497222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3689808614367368, 0.5577104480698207, 1.2851985271167368, -0.7249939125996567, -1.9436369605967867, -0.39576205076792975, 0.9115313297721367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305853548399064, -0.45450238080270544, 0.021507407707782908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015558011114232356, -0.04333433557074981, 0.1120372631840425, 0.0, -0.1337467105606751, -0.006295157772847987, 0.04200102479807478, -0.005363535610125525, 0.207522446414517, 0.023698317640577764, -0.3521092735088453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40650952141055535, -0.16892488176813872, -0.10647673980095607, 0.5194148276201257, -0.11439818122798806, 0.028026372327378497, -0.05188067956594836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792830431773525, 0.09739653944573959, 0.0003573628096714333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030914634140978, 0.19637390500117713, 0.6715828451201916, 0.0, -0.011823845857501004, -0.32125109674842384, -3.0317232352621573, -1.047993758889174, -1.8853759253989026, -0.10350850752923797, -1.282109695006647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34853531759768974, 0.5490903893140774, 1.2800996783217704, -0.6982100150772024, -1.9483808813828611, -0.3939543090524812, 0.9077272656514751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0404812611623253, -0.44961272326613566, 0.021525033954934155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001590130572305638, -0.045249621296268805, 0.11137745832687744, 0.0, -0.14116719831751465, -0.005230246151577747, 0.056533286865820584, -0.004647723416777062, 0.22170316690806577, 8.670054257864379e-12, -0.37710212113849784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4089108767809417, -0.17240117511486672, -0.10197697589932689, 0.535677950449087, -0.09487841572149006, 0.036154834308971096, -0.07608128241323243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19791812644837758, 0.09779315073139577, 0.00035252494302495706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003172693409572, 0.1940175527107981, 0.6771603689056768, 0.0, -0.019193679667741763, -0.321440476638921, -3.028179268613157, -1.0481732072969074, -1.8733471366727263, -0.10350850752836022, -1.3024202699248018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3279913270141919, 0.5402847239915176, 1.2752683565321803, -0.670544663390444, -1.9519661143688292, -0.39170631156022995, 0.9024892898828979, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0503774344917505, -0.4447394511672975, 0.021544256271463894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016245999094805286, -0.047127045807580724, 0.11155047570970374, 0.0, -0.1473966762048152, -0.0037875978099430434, 0.07087933298000587, -0.003588968154669996, 0.24057577452352463, 1.7555029717154477e-11, -0.40621149836309306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4108798116699565, -0.17611330645119624, -0.09662643579180089, 0.5533070337351663, -0.07170465971936085, 0.04495994984502532, -0.10475951537154438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792346658850413, 0.09746544197676281, 0.000384446330594774]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032562408611035, 0.19157898268789894, 0.6827789936632113, 0.0, -0.02680877064690194, -0.32154935222513786, -3.0239496911498267, -1.048269333871253, -1.8600634801830365, -0.10350850752892245, -1.3244520270897273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3073749799692585, 0.5312801892863821, 1.2707653820007925, -0.641920890359514, -1.9541671935741474, -0.38898616714406864, 0.8955337475218497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0602746926488202, -0.43992003567794874, 0.02156267750140531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016709490306319699, -0.04877140045798318, 0.11237249515069075, 0.0, -0.15230181958320357, -0.002177511724336902, 0.0845915492666035, -0.0019225314869087012, 0.2656731297937968, -1.1244587338957728e-11, -0.440635143298511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41232694089866834, -0.18009069410271097, -0.09005949062775538, 0.5724754606185991, -0.04402158410636586, 0.05440288832322622, -0.13911084722096373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979451631413971, 0.09638830978697575, 0.0003684245988282738]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003343827899983, 0.18908234189505516, 0.6884591475134899, 0.0, -0.03458886264762535, -0.32156845280526186, -3.019089507224257, -1.0482170064255085, -1.8451117116401439, -0.10350850752801133, -1.348545726744807, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.28671800434849704, 0.5220618657484017, 1.2666775150992649, -0.6122492040576393, -1.9547005956772974, -0.38576786993113416, 0.886494070350839, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0701739237493035, -0.4351940617873942, 0.02157207271245176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017517407775899616, -0.04993281585687589, 0.11360307700557186, 0.0, -0.15560184001446814, -0.0003820116024801435, 0.09720367851139555, 0.0010465489148875277, 0.29903537085785037, 1.8222420301728088e-11, -0.48187399310159584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4131395124152298, -0.18436647075960821, -0.08175733803055242, 0.5934337260374951, -0.010668042062998706, 0.06436594425868974, -0.18079354342021137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19798462200966607, 0.09451947781108981, 0.00018790422092902821]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003437113012565, 0.1865590655037719, 0.6942110743842566, 0.0, -0.042433366863801565, -0.32148710723549906, -3.013687044176947, -1.0479506258393319, -1.8279278250508226, -0.10350850752730906, -1.3751539477281702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26605257839378216, 0.5126101957533383, 1.263130067889564, -0.5814169572975708, -1.953201116026987, -0.38203307191891245, 0.8748821920655593, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0800761664844183, -0.43060595297904586, 0.021563618093416753]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018657022516393627, -0.05046552782566498, 0.11503853741533392, 0.0, -0.15689008432352433, 0.0016269113952556665, 0.10804926094620285, 0.00532761172353181, 0.34367773178642597, 1.4045463697372213e-11, -0.5321644196672647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41330851909429756, -0.1890333999012687, -0.07094894419401514, 0.6166449352013684, 0.02998959300620538, 0.07469596024443391, -0.23223756570559562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19804485470229513, 0.09176217616696702, -0.00016909238070013938]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20035384746092152, 0.18404512675042728, 0.7000380490622289, 0.0, -0.050212851054079896, -0.32129764731835564, -3.007872020375405, -1.047408573474381, -1.807714696520507, -0.1035085075265131, -1.4049158957652377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24540734864367067, 0.5028965248793075, 1.260308356335637, -0.5492699698748068, -1.949181545315102, -0.3777738292535714, 0.8600228144996451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899826588460824, -0.42620844655981927, 0.021530459334271956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020272319330068492, -0.050278775066892704, 0.11653949355944743, 0.0, -0.1555896838055666, 0.003789198342868636, 0.11630047603084057, 0.01084104729901766, 0.4042625706063127, 1.5919110619624917e-11, -0.5952389607413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41290459500222965, -0.19427341748061752, -0.0564342310785417, 0.6429397484552792, 0.08039141423770374, 0.08518485330682168, -0.2971875513182835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19812984723328245, 0.08795012838453235, -0.0006631751828959446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036843163460358, 0.18136281953048786, 0.7059390781648229, 0.0, -0.057767388905325394, -0.3210710738639323, -3.0019894450633307, -1.0466631557182662, -1.7833826261393904, -0.10350850752649103, -1.4386498684378064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22607875701511615, 0.49392618538752037, 1.2587569083891101, -0.5184133404197366, -1.941897647938553, -0.3738639731587597, 0.8417880744913834, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0998962708048692, -0.4221692529637803, 0.021686362584224045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002916834736410404, -0.053646144398788474, 0.1180205820518809, 0.0, -0.1510907570249099, 0.0045314690884670624, 0.1176515062414791, 0.014908355122296033, 0.4866414076223328, 4.4136456503999646e-13, -0.6746794534513738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3865718325710906, -0.17940678983574165, -0.03102895893053481, 0.6171325891014039, 0.1456779475309793, 0.07819712189623458, -0.36469480016523564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19827223917573664, 0.08078387192078006, 0.0031180649990417805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003942537113021, 0.17828529615059197, 0.7119086970749711, 0.0, -0.06481104577349599, -0.32095649077276867, -2.9965751754981027, -1.0458472146225162, -1.753576222358894, -0.10350850752557518, -1.476720268237994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21045717232158523, 0.4874910167006223, 1.2591597974561297, -0.492597068932329, -1.930827428581285, -0.371992393713558, 0.821011277691062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1098211641847406, -0.4187433454099081, 0.02231639502794631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000516441533970284, -0.061550467597917866, 0.11939237820296275, 0.0, -0.14087313736341175, 0.0022916618232726514, 0.10828539130455896, 0.016318821914997908, 0.5961280756099278, 1.8317036250482457e-11, -0.7614079960037541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.31243169387061864, -0.12870337373796226, 0.008057781340389522, 0.5163254297481521, 0.22140438714536217, 0.03743158890403379, -0.4155359360064289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984978675974289, 0.06851815107744402, 0.012600648874445338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004388397255267, 0.17485617009380533, 0.7179373658089209, 0.0, -0.0708799625458358, -0.32108736955233547, -2.9921991868446067, -1.0449728458633074, -1.7183656050601326, -0.103508507551078, -1.5186732699592207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20058607313259408, 0.48488016496026076, 1.261770084558291, -0.47557115538422545, -1.9164565911539984, -0.3734251779064008, 0.7994134183993886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1197616468296943, -0.41613950387568394, 0.023478168149860274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008917202844920643, -0.06858252113573299, 0.12057337467899516, 0.0, -0.12137833544679619, -0.002617575591335923, 0.08751977306991583, 0.01748737518417392, 0.70421234597523, -5.100565746783541e-10, -0.8390600344245331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19742198377982317, -0.052217034807230445, 0.052205742043229766, 0.34051827096207177, 0.2874167485457316, -0.028655683856854998, -0.43195718583346787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19880965289907265, 0.0520768306844828, 0.023235462438279234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005152505839828, 0.1713391455780551, 0.7240261343656306, 0.0, -0.0757735884958979, -0.3213355926797959, -2.9889814816028712, -1.0440263392981617, -1.6783008240333939, -0.10350850760301146, -1.5640162619985774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19755116875234574, 0.48665761041572353, 1.2661729829388388, -0.4710855997270218, -1.9005937735528882, -0.3787027586782937, 0.7798707452587533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.129720437439687, -0.4144030404743032, 0.02505428898970948]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015282171691219392, -0.07034049031500482, 0.12177537113419343, 0.0, -0.09787251900124191, -0.004964462549208628, 0.0643541048347083, 0.018930131302915862, 0.8012956205347723, -1.0386692511734449e-09, -0.9068598407871321, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06069808760496673, 0.03554890910925572, 0.08805796761095572, 0.08971111314407304, 0.31725635202220503, -0.10555161543785882, -0.3908534628127065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917581219985286, 0.034729268027614696, 0.03152241679698409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20065601839622627, 0.16807247951426837, 0.7301320595769725, 0.0, -0.07969648408535791, -0.32176962153628585, -2.986607289663825, -1.0431390960024967, -1.6342489992114075, -0.10350850760306361, -1.6122408329025861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20067328395522496, 0.492400892843251, 1.2716015314676967, -0.47859763667929617, -1.8855827822470475, -0.3876223444709693, 0.7649963838140723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1396650036073466, -0.41338405076823215, 0.026870077922475817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0028153562448687964, -0.06533332127573466, 0.12211850422683904, 0.0, -0.07845791178920039, -0.008680577129799173, 0.04748383878092355, 0.017744865913298997, 0.881036496439728, -1.042922814899149e-12, -0.9644914180801775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062442304057584455, 0.11486564855054912, 0.10857097057715762, -0.1502407390454879, 0.30021982611681386, -0.1783917158535125, -0.29748722889361945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19889132335319332, 0.02037979412142081, 0.036315778655326744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20096542306793036, 0.1654449932387038, 0.7362508424313801, 0.0, -0.08304710453424663, -0.32573663391034274, -2.9837188757965825, -1.0443762733868391, -1.5870075393538325, -0.10521373332923009, -1.662240832902595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2086725093691195, 0.5012186466235822, 1.2773543946865247, -0.496107667472857, -1.874211870670797, -0.3994081790168006, 0.7573401079606881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1494812901559333, -0.4128914605340995, 0.02866861537375455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006188093434081931, -0.0525497255112915, 0.1223756570881518, 0.0, -0.06701240897777443, -0.07934024748113738, 0.05776827734485358, -0.024743547686851254, 0.9448291971514986, -0.034104514523329695, -1.0000000000001805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998450827789035, 0.17635507560662322, 0.1150572643765603, -0.35020061587121726, 0.22741823152500568, -0.2357166909166251, -0.15312551706768568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1963257309717322, 0.009851804682653769, 0.03597074902557463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20152838728931086, 0.16369481209325562, 0.7423906816198869, 0.0, -0.08691864583703286, -0.3314701379428469, -2.9768146445403336, -1.0486542064114133, -1.5393105615783342, -0.11197817370281932, -1.712240832902578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22038123413262947, 0.5120842470988328, 1.282798670935164, -0.5219493598008356, -1.870009977014743, -0.4126385789809851, 0.7601173661938881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158737285299586, -0.41276466205298745, 0.030274916064017]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011259284427610077, -0.035003622908963465, 0.12279678377013534, 0.0, -0.07743082605572461, -0.11467008065008287, 0.13808462512497643, -0.08555866049148067, 0.9539395555099669, -0.13528880747178448, -0.999999999999657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2341744952701998, 0.21731200950501292, 0.1088855249727857, -0.5168338465595709, 0.08403787312108424, -0.2646079992836903, 0.05554516466400122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18511990287305707, 0.0025359696222403425, 0.03212601380524895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20202627967430978, 0.16284106308747984, 0.7485249734313544, 0.0, -0.09344210826657097, -0.33808688780499263, -2.962144595895054, -1.0563212869545757, -1.4949080658849068, -0.1275518286405913, -1.7622408329025676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2350154259370006, 0.5242289585463547, 1.287687448692728, -0.5546227136632432, -1.873673089113286, -0.42613294628406545, 0.7728950815705997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1674067985535097, -0.41296480272338026, 0.031647632194646884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009957847699978529, -0.017074980115515438, 0.12268583622935114, 0.0, -0.1304692485907622, -0.1323349972429145, 0.29340097290509703, -0.15334161086325052, 0.8880499138684388, -0.31147309875544, -0.9999999999997944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.29268383608742216, 0.24289422895043714, 0.09777555515128335, -0.6534670772481537, -0.0732622419708612, -0.2698873460616072, 0.25555430753423225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17339026507847224, -0.004002813407856775, 0.027454322612597743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.202398800107997, 0.16280683147053426, 0.7545672663418745, 0.0, -0.10236052291981554, -0.34514526068085766, -2.938669555357371, -1.066806922522258, -1.4566519388420978, -0.15099873731396388, -1.8122408329025614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2521359232549917, 0.5371313790297202, 1.2922238548942178, -0.5927613967532037, -1.8839800229080845, -0.4391346299700987, 0.794086424033654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1756525480679787, -0.413549951262761, 0.03278605831622804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007450408673744192, -0.0006846323389115214, 0.12084585821040356, 0.0, -0.17836829306489152, -0.141167457517301, 0.4695008107536621, -0.2097127113536453, 0.7651225408561788, -0.4689381734674513, -0.9999999999998763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3424099463598216, 0.2580484096673115, 0.090728124029795, -0.76277366179921, -0.20613867589596885, -0.26003367372066566, 0.42382684926108727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16491499028938097, -0.01170297078761519, 0.022768522431623063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2027163628310531, 0.163548418785463, 0.7604249409633889, 0.0, -0.1129019331978828, -0.34889525657054227, -2.9078895229271913, -1.0783023625548778, -1.4236392592615992, -0.1812568968502859, -1.862240832902567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27156293012603155, 0.5504404420941427, 1.2967143864739177, -0.6352723432251367, -1.8997476245278966, -0.4511342511228243, 0.8224317087991058, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.18355943573368, -0.4145957872726459, 0.03365033610337059]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006351254461121899, 0.014831746298575024, 0.11715349243028593, 0.0, -0.21082820556134538, -0.07499991779359372, 0.6156006486035991, -0.2299088006523955, 0.6602535916099723, -0.6051631907264403, -1.000000000000111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3885401374207975, 0.26618126128844893, 0.08981063159399902, -0.85021892943866, -0.31535203239624304, -0.23999242305451118, 0.5669056953090346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15813775331402652, -0.020916720197697428, 0.01728555574285116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20300062721202383, 0.16503843169782795, 0.7660373673432823, 0.0, -0.12443766154595379, -0.35264525165413685, -2.8712654969834506, -1.0900256812328397, -1.3939445447531358, -0.217290875746959, -1.9122408329024576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29321619565331164, 0.563902471783936, 1.3017963568395874, -0.6812811004027302, -1.920152501583522, -0.46209018873095564, 0.856740237231522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1912604617573923, -0.41613681364612143, 0.0342114464647145]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005685287619414848, 0.029800258247298695, 0.11224852759786824, 0.0, -0.23071456696141968, -0.07499990167189127, 0.7324805188748166, -0.23446637355923902, 0.5938942901692699, -0.7206795779334619, -0.9999999999978096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4330653105456018, 0.2692405937958666, 0.10163940731339415, -0.92017514355187, -0.4080975411125062, -0.21911875216262716, 0.6861705686483266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1540205204742444, -0.030820527469511003, 0.01122220722687825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20327350143028525, 0.16728785758489248, 0.7713944842449668, 0.0, -0.1366453821212773, -0.35264524971890543, -2.829966276228405, -1.1011813700863278, -1.3659979985495936, -0.25811805886428807, -1.9622408329024688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.317005942110701, 0.5772663034002397, 1.3082663081475974, -0.7300881061447986, -1.9449740073709518, -0.4723040399021917, 0.8960526609708361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1988628223791276, -0.4181387944267183, 0.034438861496440466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005457484365228559, 0.04498851774129044, 0.10714233803369108, 0.0, -0.24415441150647035, 3.8704628849139944e-08, 0.8259844151009157, -0.2231137770697607, 0.5589309240708441, -0.8165436623465813, -1.000000000000223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47579492914778665, 0.26727663232607307, 0.12939902616019983, -0.976140114841369, -0.49643011574859736, -0.2042770234247212, 0.786248474786281, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1520472124347034, -0.040039615611937036, 0.004548300634519246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354427407946665, 0.17029590589764237, 0.7765242390469841, 0.0, -0.14957609567993307, -0.3526452497225634, -2.784926899624365, -1.111502092915575, -1.3387330147559335, -0.30277980535815, -2.012240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3425978958829109, 0.59021135720085, 1.3168912697811177, -0.7800881312000915, -1.9743114642801527, -0.4823756353417002, 0.939502599962036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2064712450597492, -0.42048907395168095, 0.0343385347184016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005415452983628351, 0.06016096625499762, 0.10259509604034556, 0.0, -0.25861427117311553, -7.315934072253455e-11, 0.900787532080797, -0.20641445658494453, 0.5452996758732007, -0.8932349298772394, -0.9999999999999883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5118390754441977, 0.258901076012207, 0.17249923267040806, -1.0000005011058573, -0.5867491381840184, -0.20143190879016956, 0.8689987798239975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15216845361243223, -0.047005590499253035, -0.0020065355607773996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20380902679416726, 0.1740250608263596, 0.7814815414939414, 0.0, -0.16345409175240433, -0.35264524972256756, -2.7368953983411313, -1.1210488685706324, -1.3114909002989157, -0.3505092025532365, -2.062240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3694491359183932, 0.6024375144364038, 1.3280363297310942, -0.8300881562554033, -2.008190975646627, -0.49297056126018424, 0.9862625511421699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2141691199585547, -0.4230301045584226, 0.033953799488170976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005295054294012406, 0.07458309857434448, 0.09914604893914625, 0.0, -0.277559921449425, -8.306185477170416e-14, 0.960630025664667, -0.19093551310114656, 0.544842289140358, -0.954587943901729, -0.9999999999999948, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5370248007096454, 0.2445231447110752, 0.22290119899952948, -1.0000005011062378, -0.6775902273294845, -0.2118985183696804, 0.9351990236026778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15395749797610853, -0.05082061213483312, -0.007694704604612444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20405302516662302, 0.17839110823571697, 0.7863344254845989, 0.0, -0.17851430003789928, -0.35264524972255495, -2.686895373285901, -1.1300227185258729, -1.2838256251509144, -0.40050922760850854, -2.112240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3969237492142522, 0.613741097894437, 1.3415486574536832, -0.8800881813106121, -2.0459772709518442, -0.504647076992953, 1.0355802259860223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2220102602948362, -0.4255933560538981, 0.03335268787598558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004879967449115027, 0.0873209481871476, 0.09705767981314739, 0.0, -0.30120416570989883, 2.525265043987572e-13, 1.000000501104607, -0.17947699910481119, 0.5533055029600262, -1.0000005011054416, -0.9999999999999959, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5494922659171806, 0.22607166916066412, 0.2702465544517814, -1.0000005011041742, -0.7557259061043429, -0.23353031465537516, 0.9863534968770462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15682280672562757, -0.05126502990950946, -0.012022232243707826]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20427427775571064, 0.1832657630480131, 0.7911560606975594, 0.0, -0.19402046241882806, -0.3526452497225476, -2.6369255548772657, -1.1381357395602882, -1.2541818029209706, -0.4505092526637864, -2.1622408329024654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4241780894055525, 0.6240109137311005, 1.3565984597849061, -0.9300882063658712, -2.086394358193773, -0.5175612797107543, 1.085580225986022, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2299439964350036, -0.4280393053467843, 0.03261250819647751]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004425051781752245, 0.09749309624592228, 0.09643270425921166, 0.0, -0.3101232476185755, 1.46698788079243e-13, 0.9993963681727096, -0.16226042068830895, 0.5928764445988757, -1.0000005011055564, -0.9999999999999505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5450868038260062, 0.2053963167332707, 0.3009960466244557, -1.0000005011051827, -0.8083417448385756, -0.2582840543560268, 0.9999999999999947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15867472280334796, -0.04891898585772456, -0.014803593590161389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20448925460959733, 0.1884861482941713, 0.7960013837556438, 0.0, -0.20812797112921447, -0.3526452497225536, -2.590735943115225, -1.1442111287049983, -1.2195158208931738, -0.5005092777190392, -2.2122408329024843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4501567220181025, 0.6334540335899963, 1.3712930643842167, -0.9782469378031894, -2.1265963620534154, -0.531072591019149, 1.1355802259860202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2377756105301416, -0.43028076956376143, 0.03180917214483589]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004299537077733934, 0.10440770492316372, 0.09690646116168819, 0.0, -0.28215017420772837, -1.204229784694197e-13, 0.923792235240814, -0.12150778289419997, 0.6933196405559353, -1.0000005011050557, -1.000000000000377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5195726522509989, 0.1888623971779163, 0.29389209198621125, -0.9631746287463633, -0.8040400771928422, -0.2702262261678953, 0.9999999999999597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1566322819027592, -0.04482928433954309, -0.016066721032832413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2047468885177489, 0.19387014210656023, 0.8008866381240283, 0.0, -0.21961803998109392, -0.3521226426517718, -2.5514919148248616, -1.1465010588890092, -1.1798068664050003, -0.5505093027742914, -2.262240832902491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4737450900696767, 0.642079354452608, 1.3843459861892113, -1.0220309843042243, -2.1630376093293977, -0.5443202336407252, 1.1818302260191775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2452004234030019, -0.4322623985728623, 0.031009374273467866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005152678163031458, 0.10767987624777886, 0.09770508736768965, 0.0, -0.2298013770375888, 0.010452141415636393, 0.784880565807272, -0.04579860368021922, 0.794179089763471, -1.0000005011050457, -1.0000000000001337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47176736103148464, 0.17250641725223376, 0.2610584360998941, -0.8756809300207011, -0.7288249455196422, -0.2649528524315232, 0.9250000006631481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14849625745720518, -0.03963258018201765, -0.015995957427360454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2051287495455325, 0.19923065914216656, 0.8057737414679297, 0.0, -0.2281785742138778, -0.35022616837644915, -2.519391471608246, -1.1433405956760947, -1.136039702814632, -0.6005093278295216, -2.3122408329025026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4940033565817461, 0.6497248585809339, 1.3951808982628564, -1.059285479802085, -2.192812112797505, -0.5564281233814546, 1.2207959277732934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2519001603691544, -0.4339526108995303, 0.030265197010617452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007637220555672521, 0.10721034071212654, 0.09774206687802872, 0.0, -0.1712106846556775, 0.03792948550645252, 0.6420088643323169, 0.06320926425829188, 0.8753432718073637, -1.0000005011046043, -1.0000000000002376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4051653302413882, 0.15291008256651703, 0.21669824147290176, -0.7450899099572149, -0.5954900693621484, -0.24215779481458866, 0.7793140350823167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13399473932305103, -0.03380424653335981, -0.014883545257008256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20576022076715375, 0.2043888656870428, 0.8105783890627817, 0.0, -0.2337123229928388, -0.3464879381815168, -2.4940922874295155, -1.1337999009427524, -1.0890259719424475, -0.650509352884751, -2.362240832902516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510514236160238, 0.6564071831994994, 1.403620965527082, -1.0890059379932011, -2.214526068245795, -0.5667107378922177, 1.2507736607049844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2576710963515167, -0.4353477493425074, 0.029610162330812134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012629424432424752, 0.10316413089752449, 0.09609295189704037, 0.0, -0.11067497557922014, 0.07476460389864714, 0.5059836835746102, 0.19081389466684653, 0.9402746174436897, -1.0000005011045867, -1.0000000000002702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33021759156983965, 0.133646492371311, 0.16880134528450907, -0.5944091638223233, -0.43427910896580035, -0.20565229021526063, 0.5995546586338187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11541871964724648, -0.027902768859541856, -0.013100693596106397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064101730111816, 0.20918969614030278, 0.8151985088088208, 0.0, -0.23619468757488218, -0.34091006903492105, -2.475337384198103, -1.1177464421455081, -1.0394149872447274, -0.7005093779400104, -2.412240832902519, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.523403301297924, 0.6622822239167705, 1.4098182069669167, -1.1113813433797564, -2.2283755764191837, -0.5748417513451253, 1.2719013258029221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2624608795377155, -0.43646862893810046, 0.029057378771169932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880557524, 0.09601660906519982, 0.09240239492078313, 0.0, -0.04964729164086727, 0.11155738293191456, 0.375098064628254, 0.3210691759448877, 0.9922196939544017, -1.0000005011051882, -1.0000000000000613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2577813027537198, 0.11750081434542253, 0.1239448287966965, -0.44750810773110444, -0.27699016346777455, -0.16262026905815133, 0.42255330195875485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.095795663723975, -0.022417591911861316, -0.011055671192844046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2070601252552261, 0.2135221305357053, 0.8195134890305069, 0.0, -0.23592775110245523, -0.33388518964591246, -2.462551220837017, -1.0959194558390715, -0.9894149872447394, -0.7505094029952885, -2.4622408329025243, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5333287265246551, 0.667481948193073, 1.4142498397471182, -1.1277963513126714, -2.2360476984196853, -0.5810006042943882, 1.2859313215966783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.266386030912219, -0.4373574993376022, 0.028596672850609083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880889928, 0.08664868790805016, 0.08629960443372142, 0.0, 0.005338729448539366, 0.1404975877801714, 0.25572326722171174, 0.4365397261287322, 0.9999999999997586, -1.0000005011055593, -1.0000000000001035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19850850453462252, 0.10399448552605098, 0.08863265560402797, -0.32830015865830164, -0.1534424400100285, -0.12317705898525709, 0.2805999158751256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07850302749007283, -0.017777407990034997, -0.009214118411216964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20771007749924222, 0.2173234455155467, 0.823412480102414, 0.0, -0.2331721748620815, -0.3259143561449327, -2.4553099141551606, -1.0691483838741687, -0.9394149872447404, -0.8005094280505596, -2.512240832902523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5410462930877361, 0.6720870992422457, 1.4174490504828554, -1.1398783046788483, -2.23955831534367, -0.5855875325806078, 1.2949642850495815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2696122536938677, -0.43805918705077557, 0.028207867985896987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880322287, 0.07602629959682783, 0.0779798214381413, 0.0, 0.05511152480747473, 0.1594166700195956, 0.14482613363713087, 0.5354214392980579, 0.9999999999999802, -1.0000005011054218, -0.9999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15435133126162043, 0.09210302098345298, 0.0639842147147435, -0.2416390673235393, -0.07021233847969158, -0.09173856572439221, 0.18065926905806198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0645244556329731, -0.014033754263467138, -0.007776097294241945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20836002974325324, 0.220580738424814, 0.8268497555052778, 0.0, -0.22776557192265945, -0.3174532650407923, -2.453736299899618, -1.0373651970028064, -0.8894149872447474, -0.8505094531076175, -2.562240832903147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5471275253317054, 0.6760967766719892, 1.419812030834297, -1.1488903227386842, -2.2406049125982195, -0.5889740129652162, 1.3007316657284402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2722569064454363, -0.43861191622931434, 0.02786773997931919]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880220122, 0.06514585818534588, 0.06874550805727751, 0.0, 0.10813205878844129, 0.1692218220828084, 0.03147228511085087, 0.6356637374272478, 0.9999999999998577, -1.0000005011411581, -1.0000000000124751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12162464487938615, 0.08019354859486817, 0.04725960702883106, -0.18024036119671732, -0.020931945090991222, -0.067729607692168, 0.1153476135771768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0528930550313747, -0.011054583570775578, -0.006802560131555889]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20890236731276418, 0.22331947192858484, 0.8299126941352141, 0.0, -0.21963384384261464, -0.3087547466632327, -2.457943386608462, -1.0008838400568223, -0.8394149872448201, -0.9005094781628663, -2.6122408329031273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519614181536695, 0.6795011419163419, 1.4215954927811791, -1.1557017087656305, -2.2403813722918278, -0.5914575442271724, 1.3044574108583427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2744018531044412, -0.43904510173632294, 0.027557092385001702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010846751390218888, 0.05477467007541689, 0.06125877259872422, 0.0, 0.16263456160089598, 0.17397036755119216, -0.08414173417687226, 0.7296271389196829, 0.9999999999985463, -1.0000005011049757, -0.9999999999996081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0966778564392827, 0.06808730488705383, 0.035669238937643385, -0.13622772053892793, 0.004470806127835566, -0.04967062523912445, 0.07451490259804805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04289893318009702, -0.008663710140172066, -0.006212951886349732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924014300176616, 0.22558907526272806, 0.832516028451838, 0.0, -0.2088784119570595, -0.29988190631457157, -2.4679101480898793, -0.9600673236121545, -0.7894149872448852, -0.9505095032181211, -2.6622408329031124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558093246584372, 0.6822883123648255, 1.4229550903934498, -1.1609092407972317, -2.239690744526241, -0.5932717611957165, 1.3069797006688277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2761077168336417, -0.4393805271434575, 0.027263123491609406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006755513780039767, 0.04539206668286434, 0.0520666863324798, 0.0, 0.2151086377111026, 0.17745680697322283, -0.19933522962834466, 0.8163303288933546, 0.9999999999986986, -1.0000005011050965, -0.9999999999997062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07695813009535564, 0.05574340896967034, 0.027191952245415554, -0.10415064063202173, 0.01381255531173049, -0.03628433937087952, 0.050445796209702576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03411727458400836, -0.006708508142691235, -0.00587937786784593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932616161286308, 0.22744569050308344, 0.834826254295132, 0.0, -0.19579154426530776, -0.2908321419076912, -2.483469466430795, -0.9154141104565975, -0.739414987245167, -1.000509528273315, -2.712240832902818, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5588604330257323, 0.6844420565639199, 1.4239877225131137, -1.164969402369256, -2.239103536428652, -0.5946108692553929, 1.3089117387084355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2774277204317501, -0.4396341865431943, 0.02698265280572664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017203722219384116, 0.037132304807107774, 0.04620451686587979, 0.0, 0.2617373538350347, 0.18099528813760773, -0.3111863668183114, 0.8930642631111416, 0.9999999999943651, -1.0000005011038793, -0.9999999999941117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06102216734590005, 0.04307488398188946, 0.020652642393276476, -0.08120323144048687, 0.011744161951782052, -0.0267821611935287, 0.03864076079215309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026400071962168384, -0.005073187994736585, -0.005609413717655272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20933056938417735, 0.228938372466004, 0.8366688095526873, 0.0, -0.18217453223378702, -0.2814297402669101, -2.500887728282853, -0.870306111972243, -0.6931649872445551, -1.0491367343047637, -2.7584908329056668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5612536679267874, 0.6860483734709207, 1.4247430436927009, -1.168155308410831, -2.2387880875171633, -0.595590809248792, 1.3105357742296277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.278425135211993, -0.4398232632180623, 0.02672449963672147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.815542628558227e-05, 0.029853639258411103, 0.03685110515110657, 0.0, 0.2723402406304148, 0.18804803281562182, -0.3483652370411696, 0.9021599696870902, 0.9250000000122373, -0.9725441206289748, -0.9250000000569817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.047864698021103345, 0.032126338140017016, 0.01510642359174525, -0.06371812083149866, 0.006308978229771619, -0.0195987998679837, 0.032480710423844435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01994829560486069, -0.003781533497360421, -0.005163063380103397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932884115003778, 0.23011316550761649, 0.8381225057841533, 0.0, -0.1693528861440909, -0.27255979656795276, -2.518771328661458, -0.8284933281084138, -0.654414987213272, -1.0926411213852207, -2.7972408329494938, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631048045192583, 0.687252723211333, 1.4252317019514358, -1.1706501793212163, -2.2387012797308765, -0.5962762215751217, 1.3119750197448723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2791678862882272, -0.4399629161625189, 0.02649902814853944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.456468279174673e-05, 0.023495860832250186, 0.029073924629319937, 0.0, 0.2564329217939224, 0.17739887397914625, -0.35767200757209533, 0.836255677276582, 0.7750000006256631, -0.8700877416091413, -0.7750000008765425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0370227318494159, 0.024086994808245304, 0.009773165174699198, -0.04989741820770852, 0.001736155725733773, -0.013708246526593065, 0.0287849103048912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014855021524681263, -0.002793058889132289, -0.004509429763640606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932788289126003, 0.23101798821627914, 0.8391026888525631, 0.0, -0.15818501666305668, -0.26483319096932273, -2.5359587088692606, -0.7937257558710759, -0.6250680896836437, -1.1277424437604398, -2.8260974817958933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564512246192544, 0.6882110000970189, 1.4254194277410992, -1.172594032649529, -2.2387410078804804, -0.5966909778580843, 1.3133183993931452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2797159619590375, -0.4400654543891233, 0.026310697312253172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9165175554961214e-05, 0.018096454173253205, 0.0196036613681976, 0.0, 0.22335738962068408, 0.15453211197260083, -0.34374760415605077, 0.6953514447467598, 0.5869379505925651, -0.7020264475043795, -0.5771329769279895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02814883346571545, 0.01916553771371786, 0.0037545157932705603, -0.0388770665662527, -0.0007945629920774432, -0.008295125659251692, 0.02686759296545663, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010961513416206263, -0.002050764532088299, -0.003766616725725312]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209326967977962, 0.23170153162576393, 0.8397180196333647, 0.0, -0.14905358832275853, -0.25852071302748747, -2.5515493738647765, -0.7668782370757354, -0.6040801048930344, -1.1540211237438165, -2.8459557199745085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5655600193084604, 0.6890612677378614, 1.4252544891234067, -1.1741005473302502, -2.2388086006669075, -0.5968383061702716, 1.3146469020890874, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2801180324457406, -0.44014044847222306, 0.0261579683581745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.829826596068004e-05, 0.013670868189695779, 0.01230661561603071, 0.0, 0.1826285668059628, 0.12624955883670494, -0.31181329991032136, 0.5369503759068073, 0.4197596958121855, -0.5255735996675329, -0.397164763572303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02095546231832748, 0.01700535281684921, -0.003298772353851691, -0.030130293614425267, -0.001351855728544265, -0.002946566243744073, 0.02657005391884625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008041409734061587, -0.001499881661994671, -0.003054579081573399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093259380204269, 0.23220977394247713, 0.8400854275917896, 0.0, -0.14197612515217423, -0.2536482214865198, -2.564986775067951, -0.7473180611300209, -0.5895743811466219, -1.1724845390217244, -2.858801959448876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663198497966578, 0.6899025586887599, 1.424707731640309, -1.1752628476276366, -2.2388339068055143, -0.5967248652769541, 1.3160195454508985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2804118817113503, -0.440195155718598, 0.02603609857431136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0599150701613132e-05, 0.010164846334263896, 0.007348159168498353, 0.0, 0.14154926341168605, 0.09744983081935366, -0.2687480240634872, 0.39120351891429056, 0.29011447492825215, -0.36926830555815804, -0.2569247894873526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015196609763948796, 0.016825819017970946, -0.010935149661955473, -0.023246005947725922, -0.0005061227721400406, 0.0022688178663480153, 0.027452867236222957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005876985312195564, -0.0010941449274996567, -0.002437395677262807]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932478082939882, 0.23258303632233118, 0.8403182736213654, 0.0, -0.13673976621698192, -0.25009048605629397, -2.5760634691920976, -0.7338035035911181, -0.5797348308047431, -1.1846861181123198, -2.8666674562661716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5668496073376568, 0.690808718640863, 1.423754695329556, -1.176157114405769, -2.2387707525162717, -0.5963535131611295, 1.3174903452101003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2806261112024597, -0.4402349952513054, 0.02593967049718884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.314382056186457e-05, 0.007465247597081032, 0.004656920591515499, 0.0, 0.10472717870384635, 0.07115470860451609, -0.22153388248293018, 0.2702911507780543, 0.19679100683757533, -0.24403158181190557, -0.1573099363459114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010595150819977833, 0.018123199042062353, -0.019060726215059675, -0.017885335562650054, 0.001263085784849995, 0.007427042316493482, 0.02941599518403489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004284589822188753, -0.0007967906541475968, -0.00192856154245041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932339724114024, 0.2328547249447787, 0.8404844977878413, 0.0, -0.13302175330080057, -0.2476419798401231, -2.5848497946527678, -0.7249578381638652, -0.5731054595349542, -1.1922294288601571, -2.8712263686173403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5671915980120815, 0.6918542953571599, 1.4223367074189475, -1.1768459124727995, -2.2385826009709686, -0.5957045777303653, 1.3191371386595554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2807820429389665, -0.440263974177527, 0.025863793622816735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.76717651716686e-05, 0.0054337724489508295, 0.003324483329518648, 0.0, 0.0743602583236267, 0.048970124323417547, -0.17572650921339994, 0.17691330854505882, 0.13258742539577828, -0.1508662149567478, -0.09117824702337414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006839813488494819, 0.020911534325937276, -0.028359758212169114, -0.013775961340610206, 0.0037630309060581193, 0.012978708615283687, 0.03293586898910326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003118634730133735, -0.000579578524432414, -0.001517537487442093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932160909258068, 0.2330513790842077, 0.840695975766972, 0.0, -0.1304781107382692, -0.24608019902554626, -2.5915906810501066, -0.7195101586413297, -0.5686273915797048, -1.1965227031409893, -2.873712065986655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5673716881041702, 0.6931383151733975, 1.420324885976035, -1.1773812592468422, -2.2382285951112917, -0.5947182660780783, 1.321087474954143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2808954222641762, -0.44028503700835714, 0.025804395699238862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.576297119099514e-05, 0.003933082788579588, 0.004229559582612759, 0.0, 0.05087285125062718, 0.031235616291536917, -0.1348177279467748, 0.1089535904507085, 0.08956135910498746, -0.08586548561664105, -0.04971394738629807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003601801841772482, 0.02568039632475126, -0.0402364288582501, -0.01070693548085521, 0.007080117193534543, 0.019726233045739956, 0.03900672589175434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022675865041934746, -0.000421256616602761, -0.0011879584715574895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931920301568352, 0.2331934293386948, 0.8408585872212334, 0.0, -0.12879737342821995, -0.245203650165338, -2.5966091754426435, -0.7164018528654865, -0.5655782245461377, -1.198687194199383, -2.8749662449540203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56739952898861, 0.6947976467255678, 1.417501623225868, -1.1778071478137369, -2.2376551247952263, -0.5932859412217962, 1.3235316849239758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.280977805635369, -0.4403003384623748, 0.025758135598587646]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.812153794340694e-05, 0.0028410050897417867, 0.0032522290852278627, 0.0, 0.03361474620098516, 0.017530977204165292, -0.10036988785073828, 0.0621661155168642, 0.06098334067134223, -0.04328982116787521, -0.02508357934730481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005568176887978771, 0.033186631043404066, -0.056465255003339654, -0.008517771337891071, 0.011469406321307846, 0.02864649712564206, 0.04888419939665492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016476674238530644, -0.0003060290803538771, -0.0009252020130243051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931618104453162, 0.23329626311703922, 0.8409724071782145, 0.0, -0.12772312341066705, -0.24481395712687198, -2.6002446659971485, -0.7148146095129365, -0.5634795661829842, -1.199550618643628, -2.875531087473784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5672778537988058, 0.6969542188524047, 1.4136642286778873, -1.1781593437099984, -2.2368185258139257, -0.5913055409781842, 1.3266454613493943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810376429208725, -0.44031145120516274, 0.02572219668437234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0439423038208124e-05, 0.002056675566888427, 0.002276399139622121, 0.0, 0.021485000351057923, 0.007793860769319941, -0.07270981109009911, 0.03174486705099942, 0.041973167263069225, -0.01726848888489693, -0.011296850395268064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024335037960834314, 0.04313144253673796, -0.07674789095961343, -0.007043917925231801, 0.016731979626013978, 0.03960800487223917, 0.06227552850837193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011967457100707489, -0.00022225485575790908, -0.0007187782843061262]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093132596300379, 0.2333713576137685, 0.8411024824889938, 0.0, -0.12705684411839407, -0.2447149090405895, -2.602818979415272, -0.7141544056546724, -0.5620128669998177, -1.199683608494942, -2.8757399307150244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5670300950976542, 0.6995436439667067, 1.4089507589655348, -1.1784599753817526, -2.2357609555553686, -0.5888537791612296, 1.3303470237452841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810810937432404, -0.4403195204187482, 0.0256940742681744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.842828987430867e-05, 0.0015018899345859969, 0.0026015062155844244, 0.0, 0.013325585845459686, 0.00198096172564936, -0.0514862683624715, 0.013204077165283132, 0.029333983663330492, -0.002659797026282086, -0.004176864824815902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004955174023030489, 0.05178850228603931, -0.09426939424704964, -0.0060126334350839375, 0.021151405171141162, 0.04903523633909185, 0.07403124791779794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008690164473574144, -0.00016138427170990318, -0.0005624483239587907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931107145574457, 0.23342725960843494, 0.8412299048084414, 0.0, -0.1266536488275151, -0.24475560750623362, -2.6046089182401073, -0.71401434648281, -0.56096890190329, -1.1994554876513186, -2.875785908046203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5667027024736216, 0.7023252529122656, 1.4038254173463194, -1.1787187226710483, -2.234602608355407, -0.5861785294179096, 1.334307758548752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811126383451363, -0.44032537855362475, 0.02567146062408601]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3763485867001316e-05, 0.001118039893328548, 0.002548446388953234, 0.0, 0.008063905817579597, -0.0008139693128823918, -0.035798776496701455, 0.002801183437245544, 0.020879301930553273, 0.004562416872467299, -0.0009195466235717882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006547852480650781, 0.05563217891117837, -0.10250683238430679, -0.005174945785914244, 0.023166943999231908, 0.053504994866400785, 0.07921469606935587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006308920379176483, -0.00011716269753029164, -0.0004522728817677998]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093095357777038, 0.23347030733254687, 0.8413333933949931, 0.0, -0.12641317592168402, -0.2448425633689893, -2.6058359713905936, -0.7141318406218842, -0.5602121250904676, -1.1990895838369133, -2.8757726831399966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663405076834858, 0.7050641520890193, 1.398739313522182, -1.1789408532348258, -2.23345759570976, -0.5835200154982266, 1.3382051322199189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281135535361113, -0.44032963089928073, 0.02565226245036766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0713560815450024e-05, 0.0008609544822384934, 0.002069771731034684, 0.0, 0.00480945811662164, -0.001739117255113497, -0.024541063009727, -0.0023498827814825117, 0.015135536256447077, 0.007318076288105374, 0.0002644981241333316, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007243895802718277, 0.0547779835350745, -0.10172207648274745, -0.004442611275548488, 0.022900252912939713, 0.05317027839365999, 0.07794747342334042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00045794031953013753, -8.504691312025128e-05, -0.0003839634743670364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093083863401872, 0.23350509051701604, 0.8413646252815028, 0.0, -0.12626914210007656, -0.2449286003817336, -2.606668321483937, -0.7143485456589677, -0.5596551025701284, -1.1987097357395833, -2.875750105900365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.565974677304888, 0.7076153731996925, 1.393973547800686, -1.1791313171364814, -2.2323958449919328, -0.5810281181019368, 1.3418399661678189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811521534988537, -0.4403327173759992, 0.025634732928234014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2988750332211854e-05, 0.0006956636893833827, 0.0006246377301939144, 0.0, 0.0028806764321491277, -0.001720740254886341, -0.016647001866865102, -0.004334100741669422, 0.011140450406784304, 0.007596961946602426, 0.0004515447926331461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007316607571954944, 0.051024422213464565, -0.09531531442991814, -0.0038092780331124413, 0.021235014356552527, 0.049837947925796156, 0.07269667895799907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000332362754814236, -6.172953436950594e-05, -0.0003505904426728646]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093074345213319, 0.23353476076684745, 0.8413867836530399, 0.0, -0.12617978319897336, -0.2449968772106131, -2.6072287718098015, -0.714577054554873, -0.559240923775451, -1.1983759739779265, -2.8757378530791198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5656226078371608, 0.7099212289243557, 1.3896443520739996, -1.1792953816447265, -2.2314451351174696, -0.5787651709376522, 1.345133091682759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811642136478232, -0.4403349575490008, 0.02561761009628726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9036377105635495e-05, 0.0005934049966281783, 0.000443167430740441, 0.0, 0.0017871780220643492, -0.0013655365775899187, -0.011209006517291896, -0.0045701779181072716, 0.008283575893547793, 0.006675235233133516, 0.00024505642489917266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007041389354544094, 0.0461171144932648, -0.08658391453372918, -0.003281290164901044, 0.01901419748926482, 0.045258943285691154, 0.06586251029880365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002412029793911311, -4.480346003190916e-05, -0.0003424566389351333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930656804015205, 0.23356129882315158, 0.8413701620718517, 0.0, -0.12612001251429453, -0.24504422559840863, -2.607604653229138, -0.7147753717799153, -0.5589313399745239, -1.1981100556589004, -2.8757403173484275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5652913274534491, 0.7119836069201142, 1.385754835100013, -1.1794382729338133, -2.2306047665306026, -0.5767333927952603, 1.3480873651022844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281172965508997, -0.440336583464336, 0.025600174956988263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7329623597052658e-05, 0.0005307611260826335, -0.00033243162376509416, 0.0, 0.0011954136935767837, -0.0009469677559102456, -0.007517628386735238, -0.003966344500848236, 0.006191676018541968, 0.005318366380524382, -4.928538615713067e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006625607674232605, 0.04124755991517044, -0.077790339479733, -0.0028578257817353727, 0.01680737173734279, 0.040635562847839264, 0.059085468390505325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017503722347327722, -3.2518306703991607e-05, -0.00034870278597991196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930571697289413, 0.23358578927657528, 0.8413301762265463, 0.0, -0.1260756570374459, -0.24507464315984007, -2.6078564227091303, -0.7149285725174833, -0.5586999459037346, -1.1979128602868756, -2.8757551078398103, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5649807970422012, 0.7138384212270887, 1.3822426312907556, -1.1795648525660125, -2.229858153091005, -0.5749001873910619, 1.3507527457911412, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811793163762348, -0.4403377635721811, 0.02558220222703967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.702134515844646e-05, 0.0004898090684743421, -0.000799716906108358, 0.0, 0.0008871095369727812, -0.0006083512286286783, -0.0050353895998431234, -0.0030640147513591332, 0.004627881415787143, 0.003943907440495759, -0.0002958098276514625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006210608224958936, 0.03709628613948982, -0.07024407618514973, -0.0025315926439827795, 0.014932268791951654, 0.036664108083967424, 0.05330761377713449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001270173447574517, -2.360215690101155e-05, -0.00035945459897185014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093048289687132, 0.23360869936906162, 0.8412687929570802, 0.0, -0.12603921694238535, -0.24509250940629626, -2.6080254533918, -0.7150364279503766, -0.5585275030750284, -1.197775332567186, -2.8757778356522703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5646863279103231, 0.7155384116720686, 1.3790120388227531, -1.1796795240936315, -2.229181352658341, -0.5732152525497688, 1.3532028827256402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811839248259298, -0.44033862013547376, 0.02556383189244487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7760083618687023e-05, 0.0004582018497266741, -0.0012276653893209275, 0.0, 0.0007288019012108107, -0.00035732492912375895, -0.0033806136533930773, -0.0021571086578656457, 0.00344885657412393, 0.002750554393789047, -0.00045455624919883757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005889382637561511, 0.03399980889959524, -0.06461184936005213, -0.002293430552380959, 0.013536008653279674, 0.033698696825861935, 0.04900273868997617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.216899389749787e-05, -1.713126585362548e-05, -0.0003674066918959724]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093038618960449, 0.23363013314251516, 0.8412021612596656, 0.0, -0.12600711441060672, -0.24510213748602921, -2.6081395104400515, -0.7151055316030717, -0.5583997009662818, -1.1976850765639133, -2.8758042432433197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5644002197876236, 0.7171431776920782, 1.3759527757440497, -1.1797862949051272, -2.228548011012204, -0.571620595983273, 1.3555215766006095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811872688471595, -0.44033924188535506, 0.02554541065054421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9341453365596536e-05, 0.00042867546907065216, -0.0013326339482925987, 0.0, 0.0006420506355724892, -0.00019256159465898116, -0.0022811409650317937, -0.00138207305390175, 0.0025560421749317797, 0.0018051200654563017, -0.0005281518209890811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005722162453991348, 0.03209532040019296, -0.06118526157406873, -0.002135416229915026, 0.01266683292273626, 0.03189313132991613, 0.04637387749938665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.688042459223199e-05, -1.243499762654782e-05, -0.0003684248380132118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930277955712914, 0.23365003479002197, 0.841142355991144, 0.0, -0.12597786919762735, -0.2451067040304369, -2.608217050437533, -0.7151446630045013, -0.5583056253473476, -1.1976298647099906, -2.875831082964572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564112916098539, 0.718713631945134, 1.3729505868607748, -1.1798888818872901, -2.227932048589906, -0.5700562098209019, 1.3577952065121577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811896953317157, -0.44033969321508903, 0.025527345973332755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1646778315541915e-05, 0.0003980329501363525, -0.0011961053704323751, 0.0, 0.0005849042595874469, -9.133088815418519e-05, -0.0015507999496303946, -0.0007826280285938342, 0.001881512378682125, 0.0011042370784556759, -0.0005367944250410268, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005746073781690693, 0.03140908506111582, -0.06004377766550069, -0.002051739643259896, 0.012319248445959628, 0.03128772324742158, 0.04547259823096527, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.852969112507101e-05, -9.026594679226684e-06, -0.0003612935442291047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930155521577734, 0.23366833009605906, 0.841094961488964, 0.0, -0.12595099681958702, -0.24510830575426978, -2.608270244854492, -0.7151623127094201, -0.5582368711318413, -1.1975992576938694, -2.8758562656040474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5638140257817605, 0.7203079847006745, 1.369895085563649, -1.1799907533268417, -2.227309439495549, -0.5684642412888999, 1.360107104727664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281191456016363, -0.440340020855898, 0.02550999675993775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4486827036107972e-05, 0.0003659061207415492, -0.0009478900435981089, 0.0, 0.0005374475608064811, -3.203447665762285e-05, -0.0010638883391749958, -0.0003529940983749414, 0.0013750843101261174, 0.0006121403224216934, -0.0005036527895113157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0059778063355689585, 0.03188705511080903, -0.061110025942516716, -0.0020374287910290695, 0.012452181887139795, 0.03183937064003895, 0.046237964310127326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.521369294633575e-05, -6.552816180006944e-06, -0.0003469842679000255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930018081720683, 0.23368500968621683, 0.8410609628302775, 0.0, -0.125926388040214, -0.24510836130916702, -2.6083070567133824, -0.7151655660674753, -0.5581869933210988, -1.1975851125906631, -2.875878686583119, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.563493591706401, 0.7219767244682881, 1.3666896025534783, -1.18009501357608, -2.226660223367573, -0.5667941725697253, 1.3625303249008929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811927335841258, -0.44034025872312105, 0.025493606580810426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7487971409974618e-05, 0.00033359180315545664, -0.0006799731737292077, 0.0, 0.0004921755874602552, -1.1110979447739581e-06, -0.0007362371778133676, -6.506716110269497e-05, 0.0009975562148499739, 0.0002829020641273661, -0.0004484195814282261, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006408681507189875, 0.033374795352271634, -0.06410966020341216, -0.002085204984763627, 0.012984322559509329, 0.033401374383493235, 0.04846440346457676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5551355253924737e-05, -4.757344460149128e-06, -0.00032780358254653704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929867884331144, 0.2337001652461733, 0.8410398000736337, 0.0, -0.1259039816055719, -0.24510771241587442, -2.608332691702937, -0.7151597804444204, -0.5581510785125475, -1.1975814871566215, -2.875897971265622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631438560880656, 0.7237552448328658, 1.3632656213457324, -1.180204082582403, -2.225971326545408, -0.5650103653121799, 1.365116883684307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281193660600752, -0.4403404314317798, 0.025478275340491713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0039477908181726e-05, 0.00030311119912921383, -0.00042325513287815654, 0.0, 0.0004481286928418511, 1.2977865851722881e-05, -0.0005126997910942445, 0.00011571246109806768, 0.0007182961710260918, 7.250868083288599e-05, -0.0003856936500588376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006994712366707671, 0.03557040729155468, -0.0684796241549184, -0.002181380126459792, 0.013777936443305007, 0.03567614515090822, 0.051731175668285306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8540332523773255e-05, -3.4541731755088937e-06, -0.00030662480637424854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092971066962968, 0.23371399345663038, 0.8410315183894932, 0.0, -0.12588360240755486, -0.24510639356105499, -2.6083506489147124, -0.7151486795474746, -0.5581253344249605, -1.1975842653907938, -2.875914255468676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5627612462555937, 0.7256557504430601, 1.3595986979929144, -1.180319265356326, -2.225239514424052, -0.5631003451914094, 1.3678858125913502, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811943332514166, -0.44034055684806567, 0.025463959270514265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.144294029240099e-05, 0.000276564209141811, -0.0001656336828101733, 0.0, 0.00040758396034068956, 2.6377096388984554e-05, -0.00035914423550959505, 0.00022201793891585123, 0.0005148817517415824, -5.55646834436625e-05, -0.0003256840610755665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007652196649439385, 0.03801011220388612, -0.07333846705635926, -0.0023036554784603078, 0.014636242427122956, 0.03820040241540994, 0.055378578140861626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3453013296197203e-05, -2.508325717375635e-06, -0.000286321399548956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929554240381656, 0.23372677844954556, 0.8410309175430131, 0.0, -0.12586495439624742, -0.24510451324511714, -2.608363229770946, -0.715134626654381, -0.5581069586289285, -1.1975907620666153, -2.875927934791054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5623475532949853, 0.7276636348005215, 1.355715874881219, -1.1804404942998248, -2.2244724050053057, -0.5610786053208363, 1.3708175312484436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811948213291113, -0.4403406479415184, 0.025450491256586823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.128584960460454e-05, 0.0002556998583034697, -1.2016929603494417e-05, 0.0, 0.00037296022614867746, 3.7606318756892435e-05, -0.0002516171246731703, 0.00028105786187182383, 0.00036751592064140806, -0.00012993351642981148, -0.00027358644755902454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008273859212166279, 0.040157687149229564, -0.07765646223390661, -0.002424578869977944, 0.015342188374920577, 0.040434797411462116, 0.05863437314186746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.7615538926286e-06, -1.8218690544552197e-06, -0.00026936027854881727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209294053398125, 0.23373885868698788, 0.8410335748135789, 0.0, -0.12584763873052435, -0.24510210272088584, -2.6083719747967073, -0.7151189612611795, -0.558093895091273, -1.197599327374643, -2.8759395243000445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.561909294418856, 0.7297428023174414, 1.3516858663276905, -1.1805665121830295, -2.2236858833252864, -0.5589813906049087, 1.3738611251068245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195175474863, -0.4403407141278588, 0.025437617055845567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9780113831033408e-05, 0.00024160474884648138, 5.314541131553214e-05, 0.0, 0.00034631331446133593, 4.821048462616556e-05, -0.00017490051522889565, 0.00031330786403151347, 0.0002612707531080156, -0.00017130616055594606, -0.00023179017981265172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008765177522586246, 0.041583350338396, -0.080600171070569, -0.0025203576640966487, 0.01573043360038643, 0.04194429431855181, 0.060871877167615614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.082915030469657e-06, -1.3237268083657956e-06, -0.0002574840148251435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929267402278356, 0.23375058401338336, 0.8410368464974026, 0.0, -0.1258312071972287, -0.24509912738008263, -2.608377934289759, -0.7151023257509268, -0.5580846474444042, -1.1976090235471704, -2.8759495580003933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5614554637779701, 0.7318480731070073, 1.3475954379145076, -1.180695442257408, -2.222898841005886, -0.5568542851154894, 1.3769520004783893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195432432936, -0.4403407622430411, 0.0254250422090177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7587506829197594e-05, 0.00023450652790980332, 6.543367647447401e-05, 0.0, 0.0003286306659130794, 5.9506816063916064e-05, -0.00011918986102826232, 0.0003327102050529317, 0.00018495293737567448, -0.00019392345054728718, -0.00020067400697726577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009076612817717112, 0.04210541579131824, -0.08180856826365653, -0.0025786014875700805, 0.015740846388008323, 0.04254210978838492, 0.06181750743129771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.139161459139613e-06, -9.623036454801814e-07, -0.0002514969365572958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929140492578405, 0.23376226979364867, 0.8410366838434314, 0.0, -0.1258152304891205, -0.24509561131307556, -2.6083818247290775, -0.7150849474311873, -0.5580781479145169, -1.1976193739597198, -2.875958516984219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5609949280913906, 0.7339380409830827, 1.3435246690204103, -1.180825424830752, -2.22212797938815, -0.5547392558008276, 1.380030415191857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811956188667661, -0.44034079724974484, 0.025412482780436875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.538193999048871e-05, 0.00023371560530605358, -3.2530794247178512e-06, 0.0, 0.0003195341621644069, 7.032134014142217e-05, -7.78087863706458e-05, 0.0003475663947893592, 0.00012999059774529547, -0.00020700825098755003, -0.0001791796765088974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009210713731589496, 0.04179935752150859, -0.08141537788194497, -0.002599651466876533, 0.015417232354719007, 0.042300586293236575, 0.06156829426935478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7286766039075745e-06, -7.001340752734186e-07, -0.0002511885716165004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929022605121414, 0.23377415724123438, 0.8410354043712006, 0.0, -0.12579936807991787, -0.245091880159618, -2.6083840897483874, -0.7150668577609607, -0.55807369540577, -1.197630180755887, -2.8759667720472466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5605345511860355, 0.7359832897091294, 1.3395309574510912, -1.1809550542929945, -2.2213846728043958, -0.552666304106167, 1.3830534858866987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811957541294259, -0.44034082274968717, 0.025399710587983983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3577491398254557e-05, 0.000237748951714319, -2.5589444615739494e-05, 0.0, 0.0003172481840523629, 7.462306915097544e-05, -4.5300386200787526e-05, 0.00036179340453244813, 8.905017493845235e-05, -0.00021613592333979306, -0.0001651012605533446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009207538107104077, 0.040904974520935396, -0.07987423138638482, -0.002592589244853728, 0.01486613167508669, 0.04145903389321194, 0.06046141389683468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7052531964609267e-06, -5.099988465446153e-07, -0.00025544384905784367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092891087142332, 0.2337863889700238, 0.8410360082603573, 0.0, -0.12578335826999573, -0.24508741702397602, -2.6083851827022246, -0.715048050955997, -0.5580706532528865, -1.1976413418152407, -2.8759746453116835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5600783519138955, 0.7379690563802977, 1.3356436247608887, -1.1810835571516842, -2.2206741594981336, -0.5506506833394155, 1.3859992698826669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811958522663727, -0.4403408413557531, 0.025386583483815072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2346739618580776e-05, 0.0002446345757885683, 1.207778313352136e-05, 0.0, 0.0003201961984425355, 8.926271283950733e-05, -2.18590767437206e-05, 0.0003761360992743255, 6.084305766997865e-05, -0.00022322118707697718, -0.00015746528873960834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009123985442799153, 0.03971533342336723, -0.07774665380405146, -0.002570057173793344, 0.014210266125241882, 0.04031241533503041, 0.058915679919361294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9627389349568807e-06, -3.721213176678822e-07, -0.0002625420833782228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928802517115022, 0.23379900514934923, 0.8410349328638245, 0.0, -0.125767081482586, -0.24508231676848866, -2.6083853909718746, -0.7150285610661412, -0.5580686155401812, -1.1976528125791381, -2.8759823294466824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5596274722157201, 0.7398939844199924, 1.3318660572606382, -1.1812107802490412, -2.219996308616668, -0.5486940638167193, 1.3888652079976598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959234561143, -0.4403408549627982, 0.025373054806792944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1670861659835338e-05, 0.00025232358650895104, -2.1507930657501184e-05, 0.0, 0.00032553574819482414, 0.00010200510974724494, -4.1653930017752455e-06, 0.0003897977971152688, 4.075425410771976e-05, -0.0002294152779486388, -0.0001536826999770408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00901759396351018, 0.038498560793894, -0.07555135000501167, -0.002544461947141193, 0.013557017629314352, 0.03913239045392443, 0.05731876229985881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4237948324154929e-06, -2.721409020453415e-07, -0.00027057354044257597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928695084797927, 0.2338119584573455, 0.8410321159752371, 0.0, -0.12575052771739645, -0.2450766126830368, -2.6083849522399776, -0.7150084945107471, -0.558067272264523, -1.1976645422434569, -2.875989934475641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5591806119876536, 0.7417669828489495, 1.3281815578917626, -1.181337083108363, -2.219347098584525, -0.5467876350123405, 1.3916637907816496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959750864783, -0.4403408649438677, 0.025359163293032172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.148646341928201e-05, 0.00025906615992544573, -5.6337771747108655e-05, 0.0, 0.00033107530379099525, 0.00011408170903712871, 8.774637939968811e-06, 0.0004013311078828809, 2.6865513162621074e-05, -0.00023459328637668916, -0.0001521005791680687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00893720456133019, 0.03745996857914207, -0.07368998737751273, -0.002526057186434127, 0.012984200642861312, 0.038128576087575396, 0.05597165567979601, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.032607281879432e-06, -1.9962139030758776e-07, -0.000277830275215461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928586632714155, 0.23382514213019298, 0.8410281279171928, 0.0, -0.1257337701212526, -0.245070380155813, -2.608384056205543, -0.7149880199197897, -0.5580663940860073, -1.1976764629807153, -2.875997503976249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5587346767482065, 0.7436035660074914, 1.3245602911608023, -1.1814631941859728, -2.218720221675862, -0.5449157679568635, 1.3944173987513842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196012518856, -0.4403408722934107, 0.02534500869895688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.169041675451192e-05, 0.0002636734569495852, -7.976116088462764e-05, 0.0, 0.000335151922876737, 0.00012465054447576959, 1.7920688690471714e-05, 0.0004094918191487047, 1.756357031465416e-05, -0.000238414745170206, -0.0001513900121642371, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008918704788940066, 0.036731663170838695, -0.07242533461920501, -0.0025222215521966854, 0.012537538173262038, 0.03743734110954007, 0.05507215939469092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.486475535157642e-07, -1.4699085936223667e-07, -0.0002830918815058249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928475816571282, 0.23383842289331924, 0.8410237772334282, 0.0, -0.12571693075540719, -0.24506380536438543, -2.6083828393500443, -0.7149673371095181, -0.5580658266392596, -1.1976884972615673, -2.876005033477747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5582855023094606, 0.7454223285409701, 1.320966063736913, -1.1815900579661462, -2.2181085407857957, -0.5430595762208513, 1.397153250655472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960396432749, -0.4403408777315123, 0.025330721100861507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2163228574663497e-05, 0.00026561526252498984, -8.701367529104261e-05, 0.0, 0.00033678731690860153, 0.00013149582855127422, 2.4337109971788726e-05, 0.0004136562054321969, 1.134893495327528e-05, -0.00024068561703942797, -0.00015059002995320076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008983488774919038, 0.03637525066957294, -0.07188454847778691, -0.002537275603468942, 0.012233617801327062, 0.03712383472024385, 0.05471703808175564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.424883800536471e-07, -1.0876203281328585e-07, -0.00028575196190749576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928361962021858, 0.233851671975343, 0.8410200329115725, 0.0, -0.12570014481308564, -0.24505718307812926, -2.608381384654628, -0.714946639975147, -0.5580654824178932, -1.19770057133443, -2.87601249037681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5578285987012843, 0.7472417640137283, 1.317362530804653, -1.1817186799421848, -2.217505315958886, -0.5412001596216567, 1.3998987606241629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960592890377, -0.4403408817798127, 0.025316430660225216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2770909884935263e-05, 0.00026498164047559765, -7.488643711521706e-05, 0.0, 0.0003357188464307567, 0.00013244572512316, 2.909390832013645e-05, 0.0004139426874227912, 6.884427328987225e-06, -0.0002414814572513849, -0.00014913798126398273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00913807216352482, 0.036388709455163676, -0.07207065864519666, -0.0025724395207737606, 0.012064496538201786, 0.037188331983892126, 0.054910199373815416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9291525549217034e-07, -8.096600676193637e-08, -0.0002858088127258603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928245108894183, 0.23386478804542368, 0.8410174650185066, 0.0, -0.125683527186835, -0.24505075403237622, -2.6083797446478076, -0.7149260860247941, -0.55806531127179, -1.1977126232930966, -2.876019838179076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.557359873636548, 0.7490775025074466, 1.31371866460612, -1.181849972036363, -2.216905181731572, -0.5393214456994128, 1.402677423283606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960735113084, -0.4403408848165188, 0.025302244240532755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3370625534722936e-05, 0.0002623214016136919, -5.135786131682776e-05, 0.0, 0.000332352525012723, 0.00012858091506071477, 3.280013641051642e-05, 0.0004110790070570588, 3.4229220628398828e-06, -0.000241039173333795, -0.0001469560453180969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00937450129472489, 0.03671476987436629, -0.07287732397065966, -0.0026258418835635637, 0.01200268454627503, 0.03757427844487955, 0.05557325318886109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.844454131390296e-07, -6.07341217716913e-08, -0.0002837283938491854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928125975254663, 0.2338777108130339, 0.8410158630732162, 0.0, -0.1256671439747314, -0.24504447219903447, -2.608377986471098, -0.7149057769458779, -0.5580652503388998, -1.1977246030067663, -2.876027063526532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5568762726491504, 0.7509401348519842, 1.3100131355736913, -1.181984612037136, -2.2163048343526506, -0.5374124503813171, 1.4055054932543025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196083799387, -0.44034088711628594, 0.02528823051558007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3826727904008558e-05, 0.0002584553522042788, -3.203890580907234e-05, 0.0, 0.000327664242072245, 0.00012563666683489575, 3.516353418872416e-05, 0.0004061815783248623, 1.2186578059567068e-06, -0.0002395942733952444, -0.00014450694912265818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009672019747952372, 0.03725264689075036, -0.07411058064857856, -0.002692800015456993, 0.012006947578431529, 0.0381799063619132, 0.056561399413934295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0576157060140677e-07, -4.5995343059355314e-08, -0.0002802744990537038]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928005822107565, 0.23389042542853103, 0.8410148861598132, 0.0, -0.1256510139598323, -0.24503832647630847, -2.608376152939475, -0.7148857485231586, -0.5580652620672273, -1.1977364858353845, -2.8760341665429783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5563762310020239, 0.7528339407988729, 1.3062369547787211, -1.182122942229882, -2.2157033441213, -0.535468624793998, 1.4083899574042051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960912332747, -0.4403408888790849, 0.02527441387595175]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4030629419687853e-05, 0.0002542923099423783, -1.953826805875379e-05, 0.0, 0.00032260029798148945, 0.00012291445452000235, 3.667063245698228e-05, 0.00040056845438629304, -2.3456654998743283e-07, -0.0002376565723656537, -0.00014206032892117383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010000832942529793, 0.037876118937773505, -0.07552361589940103, -0.002766603854918861, 0.012029804627013495, 0.038876511746381424, 0.057689282998053766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.486777525501345e-07, -3.525597893159262e-08, -0.00027633279256637983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927886130024168, 0.2339029581009885, 0.8410143843772253, 0.0, -0.12563511083264114, -0.2450323182141585, -2.6083742664359377, -0.7148659747237618, -0.5580653290243688, -1.1977482722593595, -2.876041161779588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558598237937736, 0.7547568426705952, 1.3023937086428552, -1.182264935247827, -2.21510201780957, -0.5334919482142477, 1.4113283165359392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960965966573, -0.4403408902509209, 0.025260777130170713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.393841667927272e-05, 0.0002506534491489933, -1.0035651758644546e-05, 0.0, 0.0003180625438231048, 0.00012016524299924724, 3.773007074423181e-05, 0.0003954759879352741, -1.339142829504216e-06, -0.0002357284794985124, -0.00013990473219042374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010328144165007061, 0.038458037434445515, -0.07686492271731701, -0.0028398603588998673, 0.012026526234592393, 0.039533531595005764, 0.05876718263468003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0726765329846376e-07, -2.7436719599043683e-08, -0.00027273491562077913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092776824624636, 0.23391536552185, 0.8410144391534922, 0.0, -0.12561937333641351, -0.24502644928800751, -2.608372332749249, -0.714846381459219, -0.5580654492593156, -1.197759983980225, -2.8760480752640456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5553285643804892, 0.7567016476649344, 1.2984972245575668, -1.182410240711934, -2.2145038309831597, -0.5314896916689004, 1.4143103114192785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961004586885, -0.440340891338681, 0.025247270725072626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3576755561743843e-05, 0.0002481484172302796, 1.0955253381353154e-06, 0.0, 0.00031474992455246607, 0.00011737852301981131, 3.8673733772419264e-05, 0.0003918652908572367, -2.4046989356143726e-06, -0.00023423441731272078, -0.00013826968915586324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010625188265690203, 0.03889609988678383, -0.07792968170576704, -0.002906109282138934, 0.011963736528207015, 0.040045130906946655, 0.05963989766678648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.724062164925631e-08, -2.175520169768459e-08, -0.00027012810196172857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927653107197078, 0.23392772070120912, 0.84101540580586, 0.0, -0.12560372148059526, -0.2450207360536313, -2.608370340249683, -0.7148268663770398, -0.5580656368309801, -1.1977716584644167, -2.8760549373458373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5547849118132201, 0.7586582290391126, 1.2945673283683066, -1.1825582987058603, -2.2139125863543287, -0.5294722015989911, 1.417321104001079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961032334704, -0.44034089222072975, 0.02523382607193861]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3027809855934757e-05, 0.0002471035871828815, 1.9333047355637315e-05, 0.0, 0.0003130371163650664, 0.00011426468752416804, 3.984999132486252e-05, 0.00039030164358217097, -3.751433291583298e-06, -0.00023348968383076396, -0.00013724163583012978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010873051345381439, 0.03913162748356494, -0.07859792378520314, -0.0029611598785264674, 0.011824892576616503, 0.04034980139818535, 0.06021585163600526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.5495637686507746e-08, -1.764097494381458e-08, -0.00026889306268031713]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927541131276883, 0.23394009802358995, 0.8410185932189661, 0.0, -0.12558808170539637, -0.24501536003159705, -2.6083682275172504, -0.7148073196989726, -0.5580659552445796, -1.1977833488101328, -2.8760617628774376, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5542316414209236, 0.7606159964722238, 1.2906249655285476, -1.182708483457291, -2.21333203892798, -0.5274503660158455, 1.4203449570214883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196105224699, -0.4403408929544426, 0.025220370236506463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2395184038915284e-05, 0.00024754644761651673, 6.374826212170298e-05, 0.0, 0.0003127955039780514, 0.00010752044068553737, 4.225464864792489e-05, 0.0003909335613460387, -6.368271990569878e-06, -0.00023380691432252473, -0.00013651063200414507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011065407845928948, 0.039155348662223484, -0.07884725679517919, -0.0030036950286129248, 0.011610948526976715, 0.04043671166291232, 0.06047706040818713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.982457199812676e-08, -1.4674257741168563e-08, -0.0002691167086428905]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092743215783537, 0.23395255998394907, 0.8410230051473843, 0.0, -0.1255723470215273, -0.24500948683706794, -2.6083661263330646, -0.7147876519622324, -0.5580662673833868, -1.1977950636282821, -2.8760686341751702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5536712534113452, 0.7625660031818171, 1.2866879830377118, -1.182860236787746, -2.2127652088517054, -0.5254334347642385, 1.4233684315272994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066363056, -0.4403408935819532, 0.025206839486613532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1794688302532136e-05, 0.0002492392071820842, 8.823856836351996e-05, 0.0, 0.00031469367738097055, 0.00011746389058215508, 4.202368371624377e-05, 0.0003933547348035006, -6.242776145484021e-06, -0.00023429636298597504, -0.000137425954647393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011207760191569353, 0.03900013419186768, -0.0787396498167154, -0.0030350666091020382, 0.011336601525492554, 0.04033862503213897, 0.06046949011622329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.823213433133761e-08, -1.2550211904220164e-08, -0.0002706149978586365]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927325796914456, 0.23396514844578484, 0.8410271275585507, 0.0, -0.1255564580338701, -0.24500311691316207, -2.6083640599432076, -0.7147677981657665, -0.5580665472338727, -1.1978068265208242, -2.876075583750252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.553105546653773, 0.7645022849839103, 1.2827683981542415, -1.1830131612272698, -2.2122139963352003, -0.5234276176635633, 1.426382469184317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119610762088, -0.44034089413375943, 0.025193188723775455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1272184183163444e-05, 0.00025176923671551226, 8.244822332876133e-05, 0.0, 0.0003177797531437408, 0.00012739847811768642, 4.132779714126504e-05, 0.0003970759293174542, -5.597009716998422e-06, -0.00023525785083845817, -0.00013899150163114093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011314135151442745, 0.03872563604186414, -0.07839169766940694, -0.0030584887904729547, 0.011024250330098417, 0.04011634201350546, 0.06028075314034978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9691486868662377e-08, -1.1036124096475251e-08, -0.00027301525676155737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927221430519952, 0.23397788059636185, 0.8410270716064849, 0.0, -0.12554039099261471, -0.24499642276078032, -2.608362020589197, -0.7147477276260098, -0.5580668007004707, -1.197818655240422, -2.8760826201722662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5525354056982379, 0.7664223422694074, 1.278871353095892, -1.1831670647227828, -2.2116791073875484, -0.5214355596259588, 1.4293832066465353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961082891086, -0.4403408946317607, 0.025179396447075814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0873278901138924e-05, 0.00025464301154047255, -1.119041316239696e-06, 0.0, 0.0003213408251079206, 0.00013388304763496832, 4.0787080209078265e-05, 0.0004014107951335775, -5.069331957641143e-06, -0.00023657439195773594, -0.00014072844028634236, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011402819110700887, 0.03840114570994267, -0.07794090116698955, -0.003078069910258842, 0.010697778953041907, 0.03984116075209075, 0.06001474924436734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3364573338846698e-08, -9.96002479206681e-09, -0.00027584553399285095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927118397610842, 0.23399075006007178, 0.8410239311303209, 0.0, -0.1255241513808587, -0.24498956199327032, -2.608359996228923, -0.7147274444229025, -0.5580670386222834, -1.1978305548826256, -2.8760897378995463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519607905134508, 0.7683268961315398, 1.2749955209541877, -1.1833219600052314, -2.2111602189092636, -0.5194565663562908, 1.4323716913338567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087239965, -0.44034089509134106, 0.025165464592248835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0606581822150228e-05, 0.00025738927419882105, -6.280952327926157e-05, 0.0, 0.00032479223511994534, 0.00013721535019996331, 4.048720548120468e-05, 0.0004056640621466314, -4.758436254420416e-06, -0.0002379928440712219, -0.00014235454560254028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492303695741828, 0.0380910772426483, -0.07751664283408612, -0.0030979056489716097, 0.010377769565691192, 0.03957986539335971, 0.05976969374642933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.697758470711222e-09, -9.191606961494153e-09, -0.0002786370965395946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927016114082483, 0.23400373210759065, 0.8410194512123002, 0.0, -0.12550776676360897, -0.24498264241683182, -2.6083579783408393, -0.7147069809039911, -0.558067269018674, -1.1978425179494117, -2.8760969224402344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5513808833672721, 0.770219150729859, 1.2711345184463556, -1.1834780299146201, -2.210656286818563, -0.5174873471763168, 1.4353528300773581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961089872947, -0.4403408955231401, 0.025151414134471806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0456705671853165e-05, 0.0002596409503772192, -8.959836041594101e-05, 0.0, 0.00032769234499486994, 0.00013839152876997973, 4.035776167439639e-05, 0.0004092703782273909, -4.607927813112079e-06, -0.00023926133572264456, -0.0001436908137622857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011598142923575108, 0.037845091966384706, -0.0772200501566399, -0.0031213981877756675, 0.010078641814011902, 0.03938438359947973, 0.05962277487002981, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.265964787306103e-09, -8.635980485045285e-09, -0.0002810091555406154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092691414881666, 0.23401679135898465, 0.8410150085045758, 0.0, -0.12549127854671643, -0.24497574505774763, -2.608355960179742, -0.7146863868814608, -0.5580674989080651, -1.1978545284643507, -2.8761041534961382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5507943371419204, 0.7721037991406221, 1.2672788624344777, -1.1836355715101474, -2.2101659072623985, -0.5155230332547469, 1.4383339177750694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091267843, -0.4403408959343855, 0.02513727793862914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0393053164340324e-05, 0.00026118502787984593, -8.885415448636424e-05, 0.0, 0.00032976433785099205, 0.00013794718168371885, 4.036322194714469e-05, 0.0004118804506054077, -4.597787821579858e-06, -0.00024021029877926975, -0.0001446211180774292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011730924507034505, 0.037692968215261316, -0.07711312023755544, -0.003150831910545682, 0.009807591123291796, 0.0392862784313995, 0.059621753954225365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7897920090490064e-09, -8.224908377818695e-09, -0.00028272391685331427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926812261786906, 0.23402988986582984, 0.8410113546364125, 0.0, -0.1254747319744555, -0.24496891110737837, -2.6083539390949957, -0.7146657179611566, -0.5580677317620203, -1.1978665659441785, -2.8761114100393854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5501995705682504, 0.7739859735345267, 1.2634180710725733, -1.1837949304919402, -2.209687661112676, -0.5135582639844605, 1.441323046386029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091769961, -0.44034089633000717, 0.025123092917831803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.037740595119924e-05, 0.00026197013690362075, -7.307736326522295e-05, 0.0, 0.0003309314452189297, 0.00013667900738548018, 4.042169492600479e-05, 0.000413378406083312, -4.657079103848079e-06, -0.00024074959655829772, -0.00014513086494717239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011895331473398937, 0.037643487878091735, -0.07721582723808787, -0.0031871796358551034, 0.009564922994449472, 0.039295385405728384, 0.05978257221919284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0042353279090035e-09, -7.91243332768826e-09, -0.00028370041594671626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209267104140628, 0.2340429943556656, 0.8410087467675743, 0.0, -0.12545816787715466, -0.24496215978482463, -2.6083519141469704, -0.7146450246015063, -0.5580679696948085, -1.1978786103348296, -2.8761186733775808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5495950616600683, 0.7758702989590087, 1.2595425870350851, -1.1839564366614876, -2.2092203933095136, -0.5115881754110759, 1.4443276391989144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091630049, -0.44034089671341636, 0.025108892724971923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0369544821449065e-05, 0.00026208979671518603, -5.215737676477587e-05, 0.0, 0.0003312819460165331, 0.0001350264510744388, 4.049896050569199e-05, 0.00041386719300691855, -4.75865576519643e-06, -0.00024088781302224356, -0.00014526676390855757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012090178163641576, 0.0376865084896394, -0.07750968074976214, -0.0032301233909471402, 0.009345356063242948, 0.039401771467691124, 0.060091856257709055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7982296091932287e-10, -7.668184058429974e-09, -0.00028400385719756733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926608744319491, 0.2340560813647748, 0.84100714592006, 0.0, -0.12544161653442082, -0.244955497567562, -2.6083498843726542, -0.7146243440160265, -0.558068214967887, -1.1978906458593799, -2.8761259294668036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5489795953441095, 0.7777601731303376, 1.2556452680292212, -1.1841203496511143, -2.2087633966761158, -0.50960916074856, 1.447353305741198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091030892, -0.4403408970870755, 0.025094702314994995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0333948661378775e-05, 0.00026174018218340985, -3.20169502866619e-05, 0.0, 0.0003310268546768269, 0.00013324434525306686, 4.059548631981508e-05, 0.0004136117095959833, -4.905461569446624e-06, -0.000240710491007444, -0.0001451217844593823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012309326319177109, 0.03779748342657835, -0.07794638011728017, -0.003278259792533467, 0.009139932667958336, 0.03958029325031823, 0.06051333084567211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1983133136278932e-09, -7.473183279607074e-09, -0.00028380819953853617]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926507518548892, 0.23406913975715812, 0.8410063972109484, 0.0, -0.1254250943916626, -0.24494892316027456, -2.608347847602481, -0.7146036957909659, -0.5580684709624298, -1.197902663376985, -2.8761331701051116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5483524295994947, 0.7796573562743375, 1.2517222633995697, -1.1842868227479875, -2.208316486536265, -0.5076193119658289, 1.450403158759081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961090106299, -0.4403408974528865, 0.025080534974728976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.024515411962932e-05, 0.00026116784766674965, -1.4974182231708038e-05, 0.0, 0.0003304428551644765, 0.00013148814574851165, 4.073540347224048e-05, 0.0004129645012103608, -5.11989085565838e-06, -0.00024035035209954281, -0.00014481276615678032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012543314892294048, 0.03794366287999797, -0.07846009259303048, -0.0033294619374617247, 0.008938202797012384, 0.039796975654622084, 0.06099706035765974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8491878388867557e-09, -7.316219767631447e-09, -0.00028334680532038955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092640706247312, 0.23408217066001355, 0.8410063526322429, 0.0, -0.12540860373294258, -0.2449424304491214, -2.60834579975472, -0.7145830813160546, -0.5580687427240117, -1.1979146611692344, -2.876140392932268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477133581084443, 0.7815619052704538, 1.2477731946150523, -1.184455889736394, -2.207879969820352, -0.5056185028546967, 1.4534776604086994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961088954982, -0.44034089781242836, 0.025066391894913224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.009121515419239e-05, 0.000260618057108365, -8.915741105720763e-07, 0.0, 0.00032981317440052325, 0.00012985422306327325, 4.095695521190876e-05, 0.0004122894982256085, -5.435231639094996e-06, -0.00023995584498924465, -0.00014445654312312013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012781429821006966, 0.03809097992232506, -0.07898137569034647, -0.0033813397681313325, 0.008730334318258284, 0.0400161822226447, 0.06149003299236816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3026331635870013e-09, -7.190836763878865e-09, -0.00028286159631504327]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926307691308385, 0.23409518526677917, 0.8410069402647227, 0.0, -0.1253921349031404, -0.24493601079447763, -2.6083437344912714, -0.7145624864817306, -0.5580690372130511, -1.1979266443344707, -2.8761476003795403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5470626671276048, 0.7834724248618756, 1.2438006829971782, -1.184627475277609, -2.207454529886821, -0.5036081384235395, 1.4565749690388725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087651023, -0.44034089816707767, 0.025052263927612763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.987423294722793e-05, 0.0002602921353122936, 1.1752649594739351e-05, 0.0, 0.00032937659604336363, 0.00012839309287525946, 4.1305268976469446e-05, 0.0004118966864805311, -5.889780787719116e-06, -0.00023966330472836243, -0.00014414894544540635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013013819616792176, 0.03821039182843783, -0.07945023235748334, -0.0034317108242994452, 0.008508798670629213, 0.04020728862314311, 0.061946172603460165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.6079186586223684e-09, -7.0929858090402915e-09, -0.0002825593460092203]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926209653450153, 0.23410820123521298, 0.8410082143246913, 0.0, -0.1253756709732818, -0.24492966907772523, -2.6083416402413238, -0.7145418865534288, -0.5580693663526989, -1.1979386237684981, -2.8761547968083865, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5464010059180497, 0.7853865487005857, 1.2398093933607142, -1.1848014244146543, -2.207041062165461, -0.5015906591196544, 1.4596916611728852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961086252894, -0.44034089851804437, 0.025038134870181875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9607571646466996e-05, 0.0002603193686763777, 2.5481199373799305e-05, 0.0, 0.00032927859717196993, 0.0001268343350481614, 4.188499894923267e-05, 0.00041199856603673615, -6.582792954605186e-06, -0.00023958868055025964, -0.0001439285769249745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013233224191099789, 0.038282476774199756, -0.0798257927292779, -0.003478982740907496, 0.008269354427197501, 0.04034958607770108, 0.06233384268025381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7962567570105424e-09, -7.0193344667182365e-09, -0.00028258114861774437]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926113099265617, 0.234121238526162, 0.8410105984550883, 0.0, -0.1253591947926548, -0.24492346106987012, -2.6083394906020354, -0.7145212518834684, -0.5580697569854639, -1.1979506160215903, -2.8761619827878184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5457292068060542, 0.7873015241020881, 1.2358048465440552, -1.184977542987103, -2.206640501330332, -0.49956893056404467, 1.4628236370430239, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961084815775, -0.4403408988663479, 0.025023985465707808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931083690758048e-05, 0.0002607458189806041, 4.768260794038333e-05, 0.0, 0.00032952361254006915, 0.00012416015710208913, 4.2992785767106124e-05, 0.0004126933992083718, -7.812655299679258e-06, -0.0002398450618418897, -0.0001437195886432252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01343598223991072, 0.03829950803004944, -0.08009093633318079, -0.0035223714489752, 0.008011216702579899, 0.0404345711121948, 0.06263951740277536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8742398780104438e-09, -6.966071248459883e-09, -0.0002829880894813476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926018097379936, 0.23413431550550415, 0.8410167207029203, 0.0, -0.12534271040293332, -0.2449177927150775, -2.608337171986235, -0.7145005514573702, -0.5580703255885383, -1.1979626566472965, -2.876169126106767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5450480973304483, 0.7892147697485378, 1.2317922688863037, -1.1851556392368676, -2.206253675763402, -0.4975456560147912, 1.4659670042325852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961083432173, -0.4403408992127139, 0.025009797299432257]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9000377136226644e-05, 0.0002615395868425685, 0.00012244495664020678, 0.0, 0.00032968779442995655, 0.00011336709585256783, 4.637231600443822e-05, 0.00041400852196258844, -1.1372061487813333e-05, -0.00024081251412407916, -0.00014286637897059832, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013622189512117975, 0.03826491292899262, -0.08025155315503234, -0.003561924995294374, 0.007736511338602989, 0.040465490985068735, 0.06286734379122626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7672025351042834e-09, -6.927319278877532e-09, -0.0002837633255110353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925924473431196, 0.23414744577279814, 0.8410295052634726, 0.0, -0.12532615413129616, -0.24491146594222257, -2.6083348858091493, -0.7144797706276045, -0.5580708638242928, -1.1979747109666614, -2.876176309298787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5443583420276428, 0.7911243028203149, 1.2277756938930156, -1.1853355594288222, -2.205881215621574, -0.49552292125638464, 1.4691187756999138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961081996834, -0.4403408995579558, 0.024995556101940583]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.872478974795834e-05, 0.0002626053458798795, 0.0002556912110465393, 0.0, 0.0003311254327433029, 0.00012653545709845852, 4.5723541721021796e-05, 0.0004156165953142211, -1.0764715090429236e-05, -0.00024108638729753126, -0.00014366384040922283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013795106056110737, 0.038190661435542575, -0.08033149986576091, -0.0035984038390933335, 0.007449202836556653, 0.04045469516813203, 0.06303542934656964, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.870679197150595e-09, -6.904837927637466e-09, -0.00028482394983349996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209258321812838, 0.23416063671814646, 0.8410437398870134, 0.0, -0.12530950693366413, -0.2449045021895959, -2.6083326703868854, -0.7144588979179173, -0.5580713315230594, -1.1979867766771146, -2.876183551344064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5436603401302411, 0.7930289777705635, 1.2237574461151752, -1.1855172087541164, -2.205523515013933, -0.4935019358093305, 1.4722772729752847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196108047214, -0.4403408999025876, 0.02498125341052859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8458429479456307e-05, 0.00026381890696620686, 0.00028469247081648613, 0.0, 0.00033294395264052857, 0.0001392750525336554, 4.430844527807723e-05, 0.0004174541937448723, -9.353975332314504e-06, -0.00024131420906434384, -0.00014484090553941895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013960037948034177, 0.03809349900497107, -0.08036495555680431, -0.003632986505881571, 0.007154012152821098, 0.04041970894108255, 0.06316994550741814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0493887787539148e-09, -6.892636135295253e-09, -0.00028605382823986507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925741079071422, 0.23417388915558981, 0.8410558513561877, 0.0, -0.1252927688848866, -0.24489716620190444, -2.608330514922322, -0.7144379299689384, -0.5580717393380537, -1.1979988583162735, -2.876190849474161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5429541857656108, 0.7949285340699397, 1.219738015378438, -1.1857005597806267, -2.20518074960298, -0.49148297443279904, 1.4754422337730737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961078852034, -0.44034090024685824, 0.02496688719657855]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.822044247553129e-05, 0.00026504874886679614, 0.00024222938348463573, 0.0, 0.00033476097555076287, 0.00014671975382885406, 4.3109291263184026e-05, 0.00041935897957802475, -8.15629988416167e-06, -0.00024163278317604285, -0.00014596260194143167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014123087292605495, 0.0379911259875245, -0.08038861473474176, -0.003667020530205452, 0.006855308219058671, 0.04037922753062938, 0.06329921595578203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.240211931340805e-09, -6.8854117509447195e-09, -0.0002873242790007967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925651016993824, 0.2341871982181353, 0.841064560189934, 0.0, -0.12527594904818817, -0.244889683732324, -2.6083283999322955, -0.7144168718483338, -0.5580721071402739, -1.1980109586672534, -2.8761981945080244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5422396885604397, 0.796823478601238, 1.2157162776406405, -1.1858856473286126, -2.204852931173053, -0.48946549449193955, 1.4786146509471971, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961077143157, -0.440340900590808, 0.024952461212057558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8012415519644415e-05, 0.0002661812509097066, 0.00017417667492830742, 0.0, 0.0003363967339687805, 0.00014964939160868815, 4.22998005336657e-05, 0.0004211624120919971, -7.356044404709993e-06, -0.00024200701959800386, -0.00014690067726872157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014289944103422625, 0.03789889062596692, -0.08043475475595119, -0.003701750959717785, 0.006556368598541364, 0.04034959881719022, 0.06344834348246732, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.417755392511266e-09, -6.878994897202412e-09, -0.0002885196904198138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925561871488957, 0.2342005551099568, 0.8410618129676085, 0.0, -0.12525905888066197, -0.24488214897121363, -2.6083263175041984, -0.7143957352424114, -0.5580724431370468, -1.1980230752117988, -2.876205579243565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5415164409760148, 0.7987148547729442, 1.2116899592973498, -1.1860725531242928, -2.204539981107109, -0.4874483756147806, 1.4817964206867469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196107529577, -0.4403409009345591, 0.024937983419938786]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7829100973510103e-05, 0.00026713783642982983, -5.494444651112204e-05, 0.0, 0.00033780335052389384, 0.00015069522220727264, 4.1648561942064236e-05, 0.00042273211844828475, -6.719935459193817e-06, -0.00024233089091155212, -0.0001476947108070534, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0144649516884974, 0.03782752343412516, -0.08052636686581613, -0.0037381159136050312, 0.006259001318883878, 0.04034237754317851, 0.063635394790993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.6947749940585474e-09, -6.875021760779324e-09, -0.00028955584237541106]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925473569686348, 0.23421394931927147, 0.8410514001986437, 0.0, -0.1252421128803267, -0.24487463982329583, -2.6083242575075474, -0.714374534897885, -0.5580727580383967, -1.1980352043068812, -2.876212994467474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5407839134953499, 0.8006039588567667, 1.207656221940558, -1.186261384604039, -2.2042418051162214, -0.48543021847138557, 1.484989893729473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961073308133, -0.4403409012779771, 0.024923463887919817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.766036052164086e-05, 0.0002678841862932682, -0.0002082553792966759, 0.0, 0.0003389200067054922, 0.00015018295835598537, 4.119993302519067e-05, 0.00042400689052663815, -6.298026998768619e-06, -0.00024258190164787988, -0.00014830447818341125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014650549613298546, 0.037782081676448954, -0.08067474713583679, -0.0037766295949263422, 0.005963519817753503, 0.04036314286790055, 0.06386946085452182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.975271951200736e-09, -6.868360176661031e-09, -0.00029039064037935573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092538608537945, 0.23422737072300479, 0.8410381966315522, 0.0, -0.12522512498451718, -0.24486719520491726, -2.6083222122520726, -0.7143532856264078, -0.558073060175217, -1.1980473414524133, -2.8762204318291222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5400415571601024, 0.802492060683494, 1.203612248263087, -1.1864522523033614, -2.203958355577257, -0.48340964194609903, 1.4881974215808351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961071196258, -0.4403409016208386, 0.024908912697799563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7496861379995055e-05, 0.0002684280746661161, -0.00026407134182844635, 0.0, 0.0003397579161902799, 0.00014889236757115187, 4.0905109493422496e-05, 0.0004249854295460771, -6.042736403583455e-06, -0.00024274291064534188, -0.00014874723296733107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014847126704950253, 0.03776203653454571, -0.08087947354941886, -0.0038173539864452552, 0.005668990779289269, 0.04041153050573016, 0.06415055702724443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.223748727891442e-09, -6.857230398915573e-09, -0.0002910238024050965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092529944076841, 0.23424081134161082, 0.8410256342076418, 0.0, -0.1252081083032503, -0.24485987423481367, -2.6083201681803243, -0.7143319993473054, -0.5580733639668903, -1.19805948425245, -2.876227881748336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5392888952123503, 0.8043801749776589, 1.199555730702428, -1.1866452498983047, -2.203689672700999, -0.4813855291015325, 1.4914209744135996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961069010158, -0.44034090196284364, 0.024894338130268572]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.73289222079557e-05, 0.0002688123721204562, -0.00025124847820875187, 0.0, 0.0003403336253374409, 0.0001464194020714956, 4.088143496894334e-05, 0.00042572558204703276, -6.075833466954572e-06, -0.00024285600073301045, -0.00014899838427806628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015053238955041206, 0.037762285883297685, -0.08113035121317991, -0.00385995189886731, 0.005373657525156167, 0.0404822568913309, 0.06447105665528777, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.372200407588851e-09, -6.840101178064515e-09, -0.00029149135061983824]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925213689002095, 0.2342542662563984, 0.8410156966170897, 0.0, -0.12519107192954645, -0.24485269584579836, -2.6083181143208978, -0.7143106838121357, -0.5580736811329241, -1.1980716312967383, -2.8762353371275893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5385255891694956, 0.8062689141714454, 1.1954851943908478, -1.1868404398340329, -2.2034359013919644, -0.47935718789178705, 1.4946618848676878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066785933, -0.44034090230379175, 0.024879745639150908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.715035326296363e-05, 0.00026909829575125156, -0.00019875181104035377, 0.0, 0.0003407274740771001, 0.00014356778030618733, 4.1077188530469014e-05, 0.0004263107033934446, -6.343320675583013e-06, -0.000242940885769391, -0.00014910758505718826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015266120857095179, 0.03777478387572981, -0.08141072623160639, -0.0039037987145622843, 0.00507542618069157, 0.04056682419490884, 0.06481820908176425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.448451342577258e-09, -6.818962556157126e-09, -0.0002918498223532651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925128903715878, 0.23426773395518843, 0.8410091822802671, 0.0, -0.1251740209093694, -0.24484566153708204, -2.608316039956505, -0.7142893418370708, -0.5580740230314425, -1.1980837830640352, -2.8762427927565875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5377514715302819, 0.8081584355938903, 1.191400123617303, -1.1870378465048221, -2.203197285560948, -0.47732441194759734, 1.4979207434700035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961064552824, -0.44034090264356734, 0.024865137375008096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6957057243526444e-05, 0.00026935397580074723, -0.0001302867364530094, 0.0, 0.00034102040354084764, 0.00014068617432632294, 4.1487287853933165e-05, 0.00042683950129745, -6.8379703677965584e-06, -0.00024303534593528628, -0.0001491125799654512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015482352784273262, 0.037790428448899266, -0.08170141547089317, -0.003948133415784107, 0.004772316620325626, 0.04065551888379408, 0.06517717204631435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4662181708756e-09, -6.795512158578875e-09, -0.00029216528285619614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925045163771558, 0.23428121600255097, 0.841006182580274, 0.0, -0.1251569578582527, -0.2448387886481049, -2.6083139287135433, -0.7142679714400227, -0.5580744067173158, -1.198095943175205, -2.8762502430157117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5369665434085289, 0.8100484778689586, 1.1873008984865836, -1.1872374571208901, -2.202974145462632, -0.47528744564920095, 1.5011974420998633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961062340045, -0.44034090298211515, 0.02485051238883319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.674798886404033e-05, 0.00026964094725063224, -5.999399986235081e-05, 0.0, 0.0003412610223343902, 0.0001374577795425186, 4.2224859239858586e-05, 0.0004274079409619088, -7.673717465437287e-06, -0.00024320222339622167, -0.00014900518248552445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015698562435060924, 0.03780084550136615, -0.08198450261439016, -0.003992212321361882, 0.00446280196632445, 0.04073932596792761, 0.06553397259719447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.425557552529118e-09, -6.770956109758903e-09, -0.000292499723498149]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092496254561651, 0.23429471621174008, 0.8410070818992268, 0.0, -0.12513988917033175, -0.24483220114101195, -2.6083117354932526, -0.7142465662167454, -0.5580748787203342, -1.1981081230145345, -2.876257672920959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5361709421772896, 0.8119384662083703, 1.1831885815751473, -1.1874392290545575, -2.2027668457589105, -0.47324687428874174, 1.5044913358973206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961060191408, -0.4403409033193899, 0.024835867359076832]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6523631009647197e-05, 0.00027000418378232623, 1.7986379055652413e-05, 0.0, 0.00034137375841914824, 0.0001317501418588057, 4.38644058126588e-05, 0.000428104465546681, -9.440060369282882e-06, -0.00024359678659280064, -0.00014859810494164313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01591202462478672, 0.03779976678823284, -0.082246338228728, -0.004035438673345594, 0.004145994074430361, 0.04081142720918442, 0.06587787594914715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.2972752186325556e-09, -6.745495156767535e-09, -0.0002929005951271798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924881037954635, 0.23430823941628123, 0.8410104805760512, 0.0, -0.12512278443502178, -0.24482522520652472, -2.6083095683298225, -0.7142251228420964, -0.5580753276019556, -1.1981203016818394, -2.876265125001612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5353648890732149, 0.8138276562638193, 1.1790646163154206, -1.1876431018294107, -2.2025757636634418, -0.47120347108002103, 1.507801477500176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961058005932, -0.4403409036557102, 0.02482119775785553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6301532375350888e-05, 0.00027046409082271354, 6.797353648898557e-05, 0.0, 0.00034209470619956105, 0.00013951868974477018, 4.334326859974839e-05, 0.0004288674929802702, -8.977632425557614e-06, -0.00024357334609904135, -0.00014904161305743515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016121062081492537, 0.037783801108978735, -0.08247930519453568, -0.004077455497066453, 0.0038216419093723523, 0.04086806417441358, 0.0662028320571086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.370951473633228e-09, -6.7264061167353235e-09, -0.00029339202442599564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924800703709684, 0.23432179057086786, 0.8410220134799768, 0.0, -0.1251056348788504, -0.24481791065265449, -2.608307439769383, -0.7142036343470946, -0.5580757402627518, -1.1981324793969663, -2.876272606590669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5345486301753641, 0.815715283537283, 1.174930509137666, -1.187849009680018, -2.202401260338183, -0.46915803691662905, 1.511126864406344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961055784995, -0.44034090399110765, 0.024806498730338414]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6066848990084677e-05, 0.000271023091732647, 0.0002306580785137615, 0.0, 0.0003429911234276098, 0.00014629107740476386, 4.2571208786319135e-05, 0.00042976990003583957, -8.253215924271817e-06, -0.00024355430253760203, -0.00014963178114351563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01632517795701424, 0.037752545469273785, -0.08268214355509021, -0.00411815701214592, 0.003490066505177751, 0.040908683267839405, 0.06650773812336223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.441875061750068e-09, -6.707948679834676e-09, -0.0002939805503423458]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924721542543817, 0.23433537370842256, 0.8410361863605892, 0.0, -0.12508843718601376, -0.24481039522159975, -2.608305342609468, -0.7141820942853051, -0.5580761239398435, -1.1981446603147465, -2.8762801172878922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5337223806981956, 0.8176006922550547, 1.1707875488863044, -1.1880568938312568, -2.202243664018041, -0.46711126031023903, 1.5144666613670423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961053527348, -0.4403409043256543, 0.024791766155124875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5832233173576852e-05, 0.0002716627510938502, 0.00028345761224643766, 0.0, 0.0003439538567329903, 0.0001503086210947443, 4.194319830212943e-05, 0.000430801235789004, -7.673541835312326e-06, -0.00024361835560364367, -0.00015021394446600118, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01652498954337114, 0.037708174355435345, -0.08285920502723475, -0.004157683024774714, 0.0031519264028380908, 0.040935532127800434, 0.06679593921396432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.515292675017828e-09, -6.690933603425866e-09, -0.00029465150427082805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924643533830425, 0.2343489912932732, 0.8410488218063917, 0.0, -0.12507119063353525, -0.2448027929086804, -2.6083032659665797, -0.7141604982942021, -0.558076489693346, -1.1981568485621175, -2.8762876545351124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5328862835321865, 0.8194834221540722, 1.1666366132028636, -1.1882667114267673, -2.2021032639672424, -0.4650636217414324, 1.5178203558558363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961051233105, -0.4403409046594021, 0.024776997345098726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5601742678380886e-05, 0.0002723516970125972, 0.0002527089160520015, 0.0, 0.00034493104957015075, 0.00015204625838715168, 4.153285776985821e-05, 0.000431919822058675, -7.315070048949514e-06, -0.0002437649474163956, -0.00015074494440707218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0167219433201824, 0.03765459798034946, -0.08301871366881823, -0.004196351910210223, 0.002808001015978366, 0.04095277137613264, 0.06707388977588098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.588484374229094e-09, -6.674955954323654e-09, -0.0002953762005229549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924566647408677, 0.2343626439628206, 0.8410582188776666, 0.0, -0.12505389614320422, -0.2447951709450306, -2.6083012010642563, -0.7141388447389879, -0.5580768464749206, -1.198169046739875, -2.876295215589466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5320403872014193, 0.8213632450124095, 1.1624780814579907, -1.1884784401226691, -2.2019803143826557, -0.46301535181210113, 1.5211878305426285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196104890307, -0.4403409049923652, 0.02476219137471044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5377284349828743e-05, 0.0002730533909486646, 0.00018794142549695913, 0.0, 0.0003458898066202609, 0.00015243927299610655, 4.129804646886761e-05, 0.0004330711042844184, -7.135631492355292e-06, -0.0002439635551490929, -0.00015122108707033406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016917926615343505, 0.03759645716674715, -0.08317063489745692, -0.004234573918034956, 0.002458991691729575, 0.04096539858662546, 0.0673494937358462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.660066937348196e-09, -6.659262154159706e-09, -0.00029611940776575553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924490848327904, 0.23437633061949292, 0.8410560835309228, 0.0, -0.12503655431277882, -0.24478752010214577, -2.6082991495782464, -0.7141171348764142, -0.5580771925424345, -1.1981812541074885, -2.8763028006481965, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5311846441002754, 0.8232401533797046, 1.1583118511849793, -1.1886920782222765, -2.201875045276336, -0.4609664411809146, 1.524569354157154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961046486924, -0.44034090532473663, 0.024747349055800713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.515981615443592e-05, 0.0002737331334461661, -4.2706934877010327e-05, 0.0, 0.0003468366085082563, 0.0001530168576964341, 4.102972019804011e-05, 0.0004341972514756301, -6.921350278078256e-06, -0.0002441473522719288, -0.0001517011746054956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017114862022878714, 0.037538167345899924, -0.08332460546022809, -0.004272761992147246, 0.0021053821263965393, 0.04097821262373043, 0.0676304722905131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.8322945298618424e-09, -6.647428706090912e-09, -0.00029684637819448666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924416111709013, 0.23439004885222628, 0.8410461448202162, 0.0, -0.12501916851060207, -0.24477986099661353, -2.608297108373726, -0.7140953718715477, -0.5580775311962143, -1.1981934700527117, -2.8763104073626153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5303189263193195, 0.8251143119355534, 1.1541374375979159, -1.1889076410571624, -2.2017876764519566, -0.458916691640201, 1.527965505878348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961043974682, -0.44034090565650524, 0.024732472576478384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.494732377830591e-05, 0.00027436465466719494, -0.0001987742141298727, 0.0, 0.00034771604353479976, 0.00015318211064475697, 4.082409040750608e-05, 0.0004352600973289408, -6.773075596842037e-06, -0.0002443189044638289, -0.0001521342883787291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017314355619117806, 0.03748317111697732, -0.0834882717412666, -0.004311256697716052, 0.0017473764875824422, 0.0409949908142728, 0.06792303442387358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.024482560456021e-09, -6.6353721321817925e-09, -0.0002975295864465577]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092434241898101, 0.23440379548519505, 0.8410332845986868, 0.0, -0.12500174317378177, -0.24477220846572847, -2.608295074172032, -0.7140735601679984, -0.5580778659557126, -1.1982056933796754, -2.876318032849949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5294430534430056, 0.8269859865684598, 1.1499541243889762, -1.189125154817421, -2.2017184311773126, -0.45686579217268836, 1.5313770578414172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961041372786, -0.4403409059875701, 0.024717564985329347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4738545600715052e-05, 0.0002749326593754455, -0.0002572044305889292, 0.0, 0.00034850673640610146, 0.0001530506177013048, 4.068403387558512e-05, 0.0004362340709858327, -6.695189967279231e-06, -0.00024446653927346663, -0.00015250974666713418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01751745752627855, 0.037433492658127586, -0.08366626417879379, -0.004350275205172314, 0.0013849054928832506, 0.04101798935025297, 0.0682310392613842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.20379147070437e-09, -6.6212970787305426e-09, -0.0002981518229807454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924269768571976, 0.23441756723256021, 0.8410211936055637, 0.0, -0.12498428656625127, -0.24476466142210812, -2.6082930282445553, -0.7140517040554214, -0.5580782163099339, -1.1982179260165966, -2.876325668360499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5285568258487621, 0.8288554673713606, 1.1457611312938534, -1.1893446493034172, -2.2016675466270863, -0.4548134026388708, 1.5348048426790608, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196103873076, -0.44034090631767464, 0.024702629546660564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4530081806884725e-05, 0.0002754349473032083, -0.00024181986246085216, 0.0, 0.0003491321506098486, 0.00015094087240714833, 4.091854953169874e-05, 0.00043712225154075634, -7.007084426564443e-06, -0.0002446527384237837, -0.00015271021099671814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017724551884869048, 0.03738961605801727, -0.08385986190245388, -0.004389889719921877, 0.0010176910045214236, 0.041047790676350795, 0.06855569675287329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.284054276865303e-09, -6.602091496072119e-09, -0.00029870877337561573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924198163869062, 0.2344313611202062, 0.8410122464977837, 0.0, -0.12496680663473403, -0.2447572764006, -2.608290952109812, -0.7140298075149323, -0.5580786015168077, -1.1982301698893667, -2.8763333053410314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5276600565197247, 0.8307230000548407, 1.141557766052324, -1.1895661509740727, -2.2016352798132326, -0.45275922901337, 1.5382496319416816, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961036089454, -0.44034090664660797, 0.024687669311053716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4320940582745845e-05, 0.00027587775291998173, -0.0001789421555994827, 0.0, 0.000349598630344771, 0.00014770043016274956, 4.152269486684434e-05, 0.0004379308097814693, -7.704137474671007e-06, -0.0002448774554009283, -0.00015273961065152483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017935386580748176, 0.03735065366960045, -0.08406730483058789, -0.004430033413108865, 0.0006453362770783385, 0.04108347251001572, 0.0688957852524162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.282608769722518e-09, -6.578666193878617e-09, -0.00029920471213696226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924127625602892, 0.2344451748886894, 0.8410079530709207, 0.0, -0.12494931498664277, -0.244750168298184, -2.6082888080760194, -0.7140078729634463, -0.5580790606308612, -1.1982424314263758, -2.8763409284529082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5267525963935548, 0.8325887363924743, 1.1373435371498235, -1.1897896775209689, -2.2016219084821045, -0.4507030786006588, 1.5417120444288943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961033496475, -0.4403409069741575, 0.02467268668987216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4107653234047511e-05, 0.00027627536966383934, -8.58685372608118e-05, 0.0, 0.00034983296182516905, 0.00014216204832000084, 4.288067585132707e-05, 0.0004386910297200211, -9.182281072144481e-06, -0.0002452307401810137, -0.0001524622375366768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018149202523398262, 0.0373147267526732, -0.08428457805000901, -0.004470530937921876, 0.00026742662256651394, 0.04112300825422484, 0.06924824974425506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.1859567260439755e-09, -6.5509905493119906e-09, -0.00029965242363114023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092405814221847, 0.23445900711925993, 0.8410076193949413, 0.0, -0.12493180308159409, -0.24474297271213807, -2.6082866415957042, -0.7139859042924999, -0.5580795469753796, -1.1982546995110912, -2.876348553631648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5258343494031532, 0.8344527092342277, 1.1331182132852262, -1.1900152349403026, -2.2016277287256725, -0.44864488862339164, 1.5451924969752042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961030939942, -0.440340907300321, 0.024657683298567584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3896676884206326e-05, 0.0002766446114107791, -6.67351958730456e-06, 0.0, 0.0003502381009738575, 0.0001439117209183849, 4.3329606299553536e-05, 0.00043937341892728914, -9.726890369524963e-06, -0.000245361694308613, -0.0001525035747982607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01836493980803164, 0.037279456835067414, -0.08450647729194553, -0.004511148386673094, -0.00011640487135941536, 0.04116379954534321, 0.06960905092619887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.113067642888294e-09, -6.523269362194304e-09, -0.0003000678260915194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923989737066429, 0.23447285729849482, 0.8410173949544465, 0.0, -0.12491426032710078, -0.2447354537589122, -2.608284502251769, -0.71396390406394, -0.5580800095622412, -1.198266962763555, -2.8763561988785353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5249052765248465, 0.8363148320871545, 1.1288818293044027, -1.1902428166137695, -2.201653048920596, -0.4465847280576006, 1.5486911968215638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961028376508, -0.44034090762510103, 0.024642659859163866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3681030408542761e-05, 0.00027700358469752445, 0.00019551119010394067, 0.0, 0.0003508550898663204, 0.00015037906451729831, 4.27868787103912e-05, 0.00044000457119782273, -9.251737232382818e-06, -0.00024526504927672977, -0.00015290493773938857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018581457566134493, 0.03724245705853732, -0.08472767961646975, -0.004551633469339973, -0.0005064038984640953, 0.041203211315821324, 0.06997399692719035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.126869319532842e-09, -6.495600528856092e-09, -0.0003004687880743624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092392244501384, 0.234486725664656, 0.8410311200160856, 0.0, -0.12489668545552522, -0.24472768583321533, -2.6082823951474987, -0.7139418722212836, -0.5580804432043482, -1.1982792199698034, -2.8763638661337536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5239653889266263, 0.8381749203751567, 1.1246346429876275, -1.1904724048381408, -2.201698183225296, -0.4445227753775335, 1.5522081740767828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961025786713, -0.4403409079485101, 0.024627616319695567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3458410517791e-05, 0.0002773673232235325, 0.00027450123278138414, 0.0, 0.0003514974315111833, 0.00015535851393738803, 4.214208540367673e-05, 0.00044063685312759504, -8.672842140828888e-06, -0.0002451441249686973, -0.00015334510436367145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018797751964405293, 0.037201765760044934, -0.08494372633550343, -0.004591764487425716, -0.0009026860940070896, 0.041239053601341294, 0.07033954510438059, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.179590171708666e-09, -6.4681820872776385e-09, -0.00030087078936595537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092385628245801, 0.23450061290819943, 0.841043974989202, 0.0, -0.12487907955192709, -0.24471978613250056, -2.6082803126668055, -0.7139198076214038, -0.5580808557941545, -1.1982914729840688, -2.87637155287179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5230147331040501, 0.840032726778139, 1.1203770586254933, -1.1907039742031829, -2.201763446439512, -0.44245928030608556, 1.555743342117177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961023164102, -0.4403409082705559, 0.024612552136522255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3232511166461702e-05, 0.0002777448708686309, 0.0002570994623296304, 0.0, 0.0003521180719626334, 0.00015799401429511677, 4.164961386793083e-05, 0.0004412919975958298, -8.251796124645198e-06, -0.0002450602853071114, -0.00015373476072257683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01901311645152213, 0.0371561280596449, -0.08515168724268607, -0.004631387300841511, -0.0013052642843153798, 0.04126990142895847, 0.07070336080788225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.245223065171383e-09, -6.440916079248447e-09, -0.000301283663466211]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923791258923294, 0.23451451984754135, 0.841053839335408, 0.0, -0.124861443738691, -0.24471183909284877, -2.6082782461560727, -0.7138977088744598, -0.5580812562752453, -1.198303724005304, -2.876379256266048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5220533722188224, 0.8418879814421235, 1.1161095379235029, -1.1909374956665297, -2.201849150615711, -0.4403945196928669, 1.5592965689997291, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196102050767, -0.44034090859124075, 0.024597466590461522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3004706942721193e-05, 0.0002781387868381211, 0.00019728692411996905, 0.0, 0.00035271626472192926, 0.00015894079303583724, 4.1330214656937515e-05, 0.00044197493888114875, -8.009621817293962e-06, -0.0002450204247059355, -0.00015406788515755283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019227217704553823, 0.03710509327968975, -0.0853504140398068, -0.004670429266939552, -0.0017140835239768332, 0.041295212264373216, 0.0710645376510457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.312866158655143e-09, -6.413697667347336e-09, -0.0003017109212146423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923727385304727, 0.2345284471820798, 0.8410522138073605, 0.0, -0.12484378254230989, -0.24470398536804427, -2.6082761725991963, -0.7138755742604499, -0.5580816683877518, -1.1983159783207948, -2.876386968121842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5210813675425818, 0.8437404292008875, 1.111832515911148, -1.191172940537945, -2.2019556038910966, -0.4383287562399933, 1.56286774570927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961017818023, -0.44034090891060784, 0.024582359033059612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2774723713286888e-05, 0.00027854669076925285, -3.251056095003856e-05, 0.0, 0.00035322392762227256, 0.00015707449608995283, 4.147113752742501e-05, 0.0004426922801981734, -8.242250128389216e-06, -0.0002450863098167964, -0.00015423711587763197, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01944009352481135, 0.03704895517528012, -0.08554044024709782, -0.004708897428303273, -0.002129065507710266, 0.04131526905747279, 0.07142353419081342, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.379290814927804e-09, -6.3873414308310886e-09, -0.000302151148038187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092366466504449, 0.2345423951962035, 0.8410434472930469, 0.0, -0.12482610237027067, -0.2446963384501182, -2.6082740628509478, -0.7138534024818921, -0.5580821222057958, -1.1983282422944421, -2.8763946777497114, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5200987630336469, 0.8455898577733169, 1.107546335549563, -1.1914102836995266, -2.2020831116149004, -0.4362622067468347, 1.566456840158064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961015123277, -0.44034090922857455, 0.024567229195095627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2544052047728873e-05, 0.0002789602824744588, -0.00017533028627138354, 0.0, 0.00035360344078455975, 0.000152938358521538, 4.2194964967829366e-05, 0.0004434355711551118, -9.0763608804408e-06, -0.000245279472945569, -0.00015419255739288778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019652090178698466, 0.03698857144858722, -0.08572360723169974, -0.004746863231634872, -0.002550154476074551, 0.04133098986317244, 0.07178188897588188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.389492783145938e-09, -6.359334203315072e-09, -0.0003025967592796801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923603119785542, 0.23455636366143515, 0.8410353019987932, 0.0, -0.1248084242584862, -0.24468923095470801, -2.6082718269296277, -0.713831191059617, -0.5580827105398091, -1.1983405351414187, -2.876402351621198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.519105575620468, 0.8474361134617115, 1.1032512099441503, -1.1916495054977405, -2.202231978612754, -0.4341950240570607, 1.5700639289912093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961012491604, -0.4403409095449165, 0.024552077293800822]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2309051789507755e-05, 0.00027936930463274916, -0.00016290588507396475, 0.0, 0.00035356223568931217, 0.00014214990820386725, 4.471842639831812e-05, 0.00044422844550102134, -1.1766680265442813e-05, -0.00024585693952967403, -0.00015347742973165416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019863748263576935, 0.03692511376789492, -0.08590251210825339, -0.004784435964277944, -0.0029773399570713964, 0.04134365379548046, 0.07214177666290271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.26334369806623e-09, -6.326839330366228e-09, -0.00030303802589605624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092354267738185, 0.2345703517593418, 0.841037086357163, 0.0, -0.12479072675782128, -0.24468196978950849, -2.608269562166431, -0.71380894456449, -0.5580833331616019, -1.1983528350359811, -2.87641002529331, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5181017919564832, 0.8492791034645827, 1.0989472139222365, -1.1918905930169712, -2.2024025140696923, -0.4321272937656738, 1.5736892075793183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961010055812, -0.4403409098589737, 0.02453690412215113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2088480738122096e-05, 0.0002797619581327564, 3.568716739713108e-05, 0.0, 0.0003539500132983976, 0.00014522330399074646, 4.529526392674975e-05, 0.0004449299025413268, -1.2452435856533942e-05, -0.00024599789125044413, -0.0001534734422348367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020075673279695384, 0.03685980005742207, -0.08607992043827516, -0.004821750384614016, -0.003410709138764685, 0.04135460582773689, 0.07250557176218154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.871585243622658e-09, -6.281143838603349e-09, -0.0003034634329938299]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923483351000108, 0.23458435821041387, 0.8410433690732536, 0.0, -0.1247729928187537, -0.24467419120495768, -2.6082673488459154, -0.7137866672064415, -0.5580839074054937, -1.198365123797158, -2.87641772791869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5170873720815716, 0.85111878546559, 1.0946343060215737, -1.192133538432852, -2.202595032702884, -0.43005904517215826, 1.5773329717200524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961007619495, -0.4403409101713919, 0.024521710933646846]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1865276348927471e-05, 0.0002801290214417316, 0.00012565432181280977, 0.0, 0.00035467878135150756, 0.0001555716910162052, 4.4266410315425116e-05, 0.0004455471609690459, -1.1484877837322644e-05, -0.00024577522353742175, -0.0001540525076079574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020288397498231026, 0.0367936400201483, -0.0862581580132528, -0.00485890831761699, -0.003850372663837832, 0.04136497187031095, 0.07287528281468234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.872635981013225e-09, -6.248363731130677e-09, -0.00030386377008570877]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923425164787207, 0.2345983814792764, 0.841050347506695, 0.0, -0.12475522292646406, -0.24466603816082416, -2.6082651926888545, -0.713764361211254, -0.5580844274851053, -1.1983773992061868, -2.876425460844925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5160622570306792, 0.8529551512103469, 1.09031236495632, -1.1923783374825825, -2.2028098565664673, -0.4279902694218642, 1.5809955887759293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961005111467, -0.4403409104823721, 0.02450649925825024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.163724258027144e-05, 0.0002804653772501444, 0.0001395686688296028, 0.0, 0.0003553978457929012, 0.0001630608826704875, 4.312314121554707e-05, 0.0004461199037493099, -1.0401592232705189e-05, -0.0002455081805767086, -0.00015465852470114935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02050230101784817, 0.03672731489513667, -0.08643882130507669, -0.004895980994609451, -0.004296477271664276, 0.041375515005881276, 0.073252341117538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.0160564280701034e-09, -6.219605362174422e-09, -0.0003042335079320552]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092336812073117, 0.23461241991371726, 0.8410561678621937, 0.0, -0.12473742219781848, -0.24465770728454195, -2.6082630802066746, -0.7137420285191424, -0.5580849074418099, -1.198389663027904, -2.8764332181693337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5150263785751835, 0.8547882069357311, 1.0859812336661037, -1.1926249875088784, -2.2030473162083246, -0.4259209411969448, 1.5846774624480346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961002514438, -0.44034091079192145, 0.024491270776937437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1408811207364125e-05, 0.0002807686888172977, 0.00011640710997282274, 0.0, 0.00035601457291151454, 0.00016661752564447262, 4.224964359557917e-05, 0.0004466538422316748, -9.599134091982837e-06, -0.0002452764343438294, -0.0001551464881691109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020717569109913524, 0.03666111450768433, -0.08662262580432678, -0.004933000525917938, -0.0047491928371491505, 0.041386564498387415, 0.07363747344210625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.194058572993528e-09, -6.190986860384029e-09, -0.00030456962625612414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092331222669531, 0.23462647193549757, 0.841052066079572, 0.0, -0.12471959924255467, -0.24464941954873765, -2.608260982624077, -0.713719670597397, -0.55808537708744, -1.1984019203027907, -2.8764409883123934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5139796698170055, 0.8566179539149585, 1.0816407643975692, -1.1928734852410094, -2.203307750057057, -0.4238510406151482, 1.5883789956931182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960999830891, -0.44034091110001405, 0.02447602713313368]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1178807172321633e-05, 0.00028104043560611415, -8.203565243488869e-05, 0.0, 0.00035645910527626145, 0.00016575471608629082, 4.195165195554541e-05, 0.00044715843490582383, -9.392912601900415e-06, -0.00024514549773298693, -0.00015540286119064626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02093417516356161, 0.03659493958454977, -0.08680938537068913, -0.004969954642621503, -0.005208676974652198, 0.04139801163593095, 0.07403066490167189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.367093402234195e-09, -6.1618522748371104e-09, -0.0003048728760751354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923257491223984, 0.23464053609047267, 0.8410419055366319, 0.0, -0.12470176364589647, -0.24464133781230815, -2.6082588665282125, -0.7136972887095854, -0.5580858710249742, -1.1984141770704049, -2.8764487579958957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5129220742543645, 0.8584443728070699, 1.077290855772315, -1.1931238248543903, -2.2035915028096063, -0.42178057102604194, 1.5921005596733184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960997096226, -0.440340911406489, 0.024460769881989263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0947094264936601e-05, 0.00028128309950176415, -0.0002032108588002307, 0.0, 0.00035671193316402056, 0.00016163472858988137, 4.232191728334855e-05, 0.0004476377562333042, -9.878750685222405e-06, -0.0002451353522834519, -0.00015539367005093068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021151911252818414, 0.03652837784222549, -0.08699817250508257, -0.005006792267617171, -0.005675055050982058, 0.04140939178212616, 0.07443127960400155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.469333852017078e-09, -6.129498761064716e-09, -0.00030514502288832664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923203945074248, 0.234654611139149, 0.8410329760044956, 0.0, -0.12468393783006151, -0.24463381737345521, -2.608256641870117, -0.7136748820675878, -0.5580864822372624, -1.1984264517189394, -2.876456493033111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5118535520675944, 0.86026741417937, 1.0729314763532303, -1.193375996563004, -2.2038989229339174, -0.4197095700785597, 1.59584247316251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960994386653, -0.4403409117110504, 0.024445500384940443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0709229947061336e-05, 0.0002815009735270556, -0.00017859064272867818, 0.0, 0.0003565163166989832, 0.00015040877705849477, 4.449316191303092e-05, 0.000448132839952295, -1.2224245764281534e-05, -0.00024549297069120405, -0.0001547007443032467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0213704437354033, 0.036460827446003485, -0.08718758838169695, -0.005043434172273638, -0.0061484024862227945, 0.041420018949645344, 0.07483826978383265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.41914580147142e-09, -6.091227530342086e-09, -0.00030538994097642047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923151539108384, 0.23466869601465398, 0.8410369603092293, 0.0, -0.12466610730241652, -0.24462629384666287, -2.6082543779253315, -0.7136524549442156, -0.5580871394853086, -1.1984387281294149, -2.876464218332244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5107740827551385, 0.8620869957374822, 1.0685626721506054, -1.1936299866938658, -2.2042303620937327, -0.41763811324967404, 1.5996049968703707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960991865436, -0.44034091201287073, 0.024430219834777226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0481193173066671e-05, 0.0002816975100991661, 7.968609467351684e-05, 0.0, 0.00035661055289996446, 0.00015047053584673302, 4.5278895708661466e-05, 0.0004485424674445845, -1.3144960923647588e-05, -0.0002455282095096486, -0.00015450598266201668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02158938624911852, 0.03639163116224268, -0.08737608405249829, -0.005079802617235855, -0.006628783196301097, 0.04142913657771301, 0.07525047415721449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.042432717502845e-09, -6.0364069223755525e-09, -0.0003056110032643384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923100283255752, 0.23468278982685334, 0.8410444950602779, 0.0, -0.12464825226265315, -0.24461829692062967, -2.6082521656327224, -0.713630011550289, -0.5580877491526708, -1.198450985861604, -2.8764719670998957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5096836649634202, 0.8639030045311199, 1.0641845631582998, -1.1938857771391707, -2.2045861721409685, -0.4155663116254859, 1.603388334133879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960989332096, -0.44034091231267136, 0.024414929235849793]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0251170526505469e-05, 0.00028187624398724346, 0.0001506950209727834, 0.0, 0.00035710079526729164, 0.00015993852066417723, 4.4245852182918864e-05, 0.0004488678785303976, -1.219334724283644e-05, -0.00024515464378050837, -0.0001549753530299669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021808355834365044, 0.03632017587275478, -0.08756217984611223, -0.005115808906095752, -0.007116200944715079, 0.041436032483762424, 0.07566674527016634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.066679126741525e-09, -5.996012086212419e-09, -0.00030581197854868307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923050216204658, 0.23469689186915452, 0.8410516616188889, 0.0, -0.12463037171473912, -0.24460994079275783, -2.6082500133720026, -0.7136075531239947, -0.5580883027034881, -1.1984632225123395, -2.8764797420544017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5085823128939614, 0.8657153051896176, 1.0597973256827151, -1.194143346163699, -2.2049667038536658, -0.4134943030747915, 1.6071926446615838, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196098671681, -0.44034091261067837, 0.024399629399881436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0013410218914426e-05, 0.00028204084602383465, 0.00014333117222068478, 0.0, 0.00035761095828053827, 0.00016712255743682876, 4.304521440058582e-05, 0.0004491685258869663, -1.1071016345658088e-05, -0.0002447330147117217, -0.00015549909012203795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022027041389176896, 0.03624601316995274, -0.08774474951169516, -0.0051513804905646155, -0.007610634253944473, 0.041440171013887465, 0.07608621055409705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.230571128178997e-09, -5.960140387646349e-09, -0.0003059967193671177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923001346662412, 0.23471100150640223, 0.8410570992865238, 0.0, -0.124612469576945, -0.24460141530682628, -2.6082479078840874, -0.7135850801968361, -0.5580888139089831, -1.1984754403653106, -2.876487537895516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5074700501760492, 0.867523751218759, 1.0554011660280609, -1.1944026698833945, -2.2053723078435907, -0.4114222395388834, 1.6110180667421843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960984004842, -0.440340912906907, 0.024384321059351226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.77390844932557e-06, 0.0002821927449540467, 0.000108753352697927, 0.0, 0.00035804275588250685, 0.00017050971863127144, 4.210975830491218e-05, 0.0004494585431732285, -1.0224109900509904e-05, -0.0002443570594232101, -0.0001559168222916129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022245254358245144, 0.036168920582829035, -0.08792319309308277, -0.005186474393909225, -0.008112079798501207, 0.04144127071816173, 0.07650844161200956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.423937811173064e-09, -5.924572664479066e-09, -0.0003061668106041999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092295368781185, 0.23472511812237018, 0.8410525567244167, 0.0, -0.12459455539927589, -0.24459298694859025, -2.608245811408167, -0.7135625925579099, -0.5580893217995248, -1.1984876469894246, -2.876495340225951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5063469036469429, 0.8693281958882545, 1.0509962948414044, -1.1946637235971365, -2.205803335645199, -0.40935027469185803, 1.6148647387961867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960981211883, -0.440340913201293, 0.024369004918805077]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.531770112582698e-06, 0.0002823323193592111, -9.085124214319048e-05, 0.0, 0.0003582835533821116, 0.00016856716472041987, 4.192951841072784e-05, 0.00044975277852422565, -1.0157810831525628e-05, -0.0002441324822768575, -0.00015604660869718368, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02246293058212572, 0.03608889338990902, -0.08809742373312995, -0.005221074274839436, -0.008620556032167825, 0.04143929694050713, 0.07693344108004997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.585919470088617e-09, -5.8877196347280575e-09, -0.00030632281092298554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922907254402637, 0.23473924097755533, 0.8410430468096177, 0.0, -0.12457664465750391, -0.24458494204825634, -2.6082436611804063, -0.7135400894695607, -0.558089891193906, -1.1984998552367652, -2.8765031252828543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5052128977614048, 0.871128501107967, 1.0465829055964682, -1.194926482883499, -2.2062601412752496, -0.4072785536904651, 1.6187328177432267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960978396832, -0.44034091349359755, 0.024353681801970777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.286681842308948e-06, 0.00028245710370275603, -0.00019019829597943813, 0.0, 0.00035821483543939294, 0.00016089800667815171, 4.3004555210236635e-05, 0.0004500617669834312, -1.1387887624443933e-05, -0.00024416494681227545, -0.00015570113806031218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022680117710762223, 0.03600610439425101, -0.08826778489872511, -0.005255185727246861, -0.009136112601008644, 0.04143442002785773, 0.07736157894079969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.630101619651346e-09, -5.8460912789013415e-09, -0.00030646233668602126]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092286203029788, 0.2347533691199173, 0.8410366097666756, 0.0, -0.12455873906782257, -0.24457712016806227, -2.608241455221437, -0.7135175725101464, -0.5580905242752763, -1.1985120646248903, -2.876510891702536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5040680507202013, 0.872924542990264, 1.042161160418863, -1.1951909245602055, -2.2067430834685604, -0.40520720662076, 1.6226224919949306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960975589218, -0.4403409137837116, 0.02433835273812638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.044820950828083e-06, 0.00028256284723898446, -0.00012874085884307046, 0.0, 0.00035811179362700286, 0.00015643760388143953, 4.411917938666845e-05, 0.0004503391882867604, -1.2661627407282987e-05, -0.00024418776250376096, -0.00015532839362946262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022896940824068145, 0.03592083764594023, -0.08843490355210347, -0.00528883353413279, -0.009658843866211879, 0.0414269413941024, 0.0777934850340786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6152266013673606e-09, -5.802281156345202e-09, -0.0003065812768879271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922817994548892, 0.23476750143913333, 0.8410317368181572, 0.0, -0.12454082133663524, -0.24456902851836237, -2.6082392747393492, -0.713495046101068, -0.5580911374821886, -1.1985242565890923, -2.87651866889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5029123732057359, 0.8747162132660619, 1.0377311860746754, -1.1954570270293148, -2.207252526997856, -0.40313634677010934, 1.6265339855381478, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960972813505, -0.4403409140713817, 0.024323018905498428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.807149797687654e-06, 0.0002826463843210159, -9.74589703665631e-05, 0.0, 0.0003583546237463803, 0.00016183299399782965, 4.360964175396415e-05, 0.00045052818156762596, -1.2264138246990007e-05, -0.0002438392840411457, -0.00015554380207734861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02311355028930857, 0.035833405515955936, -0.0885994868837508, -0.005322049382186002, -0.010188870585910479, 0.04141719701301333, 0.07822987086434155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5514245871595604e-09, -5.753402196005454e-09, -0.000306676652559026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922775208871658, 0.23478163673089025, 0.8410269189424823, 0.0, -0.12452290749927553, -0.2445610802733366, -2.60823705671734, -0.7134725099597611, -0.5580917959042532, -1.1985364438454809, -2.876526432828552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5017458688935809, 0.876503417771528, 1.0332930775127567, -1.1957247695296482, -2.2077888417223948, -0.4010660722071327, 1.6304675538598268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196097005762, -0.44034091435659856, 0.02430768157447591]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.557135447079631e-06, 0.00028270583513837535, -9.63575134987599e-05, 0.0, 0.00035827674719448194, 0.00015896490051578013, 4.4360440186066256e-05, 0.00045072282613815867, -1.3168441291317371e-05, -0.00024374512776992012, -0.00015527871823862847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023330086243100588, 0.03574409010932276, -0.08876217123837545, -0.005354850006668302, -0.010726294490778453, 0.041405491259532884, 0.07867136643357993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5117697080917796e-09, -5.704337183720439e-09, -0.00030674662045039944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092273364795529, 0.23479577360256368, 0.8410267217978544, 0.0, -0.12450499913756155, -0.2445531912725162, -2.6082348019596893, -0.7134499663025892, -0.5580924988772874, -1.1985486250627273, -2.876534182971404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5005685356159986, 0.8782860735546842, 1.0288469036469596, -1.1959941324338006, -2.2083524046662615, -0.3989964689225732, 1.6344234810585367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960967315432, -0.44034091463937164, 0.024292342210012866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.31218327346479e-06, 0.00028273743346835396, -3.942892555852602e-06, 0.0, 0.000358167234279383, 0.00015778001640777447, 4.50951530158411e-05, 0.0004508731434375434, -1.4059460683804483e-05, -0.00024362434492997581, -0.00015500285704769982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02354666555164614, 0.03565311566312634, -0.08892347731593916, -0.005387258083048048, -0.011271258877333048, 0.04139206569119055, 0.07911854397420086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4843783973253375e-09, -5.655461688257759e-09, -0.00030678728926084454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092269328669074, 0.2348099105758585, 0.8410328085718266, 0.0, -0.12448707681038215, -0.2445448705057502, -2.608232602889105, -0.7134274203571955, -0.5580931513025706, -1.1985607790395163, -2.876541952707773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4993803688712595, 0.880064103097541, 1.0243927211786348, -1.1962650965612587, -2.208943599389502, -0.3969276174649741, 1.6384020683100775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960964513507, -0.440340914919795, 0.02427700236992856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.072252910155402e-06, 0.00028273946589653745, 0.00012173547944455026, 0.0, 0.00035844654358794566, 0.0001664153353203612, 4.398141168845759e-05, 0.00045091890787210125, -1.3048505665113734e-05, -0.00024307953578067693, -0.00015539472737960248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023763334894781794, 0.03556059085713516, -0.08908364936649825, -0.005419282549162722, -0.011823894464809255, 0.04137702915198115, 0.07957174503081545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6038510622082095e-09, -5.608466697218602e-09, -0.00030679680168615704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922654166067067, 0.23482404617815011, 0.8410412273442239, 0.0, -0.12446914038951988, -0.24453622390550075, -2.608230468085501, -0.7134048745361499, -0.5580937444931828, -1.1985729027930856, -2.876549744394196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49818136574451966, 0.8818374283976583, 1.019930589651557, -1.1965376419472014, -2.2095628134221337, -0.3948595998606208, 1.6424036197278522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960961632773, -0.44034091519783325, 0.024261663614724982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.824124734902576e-06, 0.0002827120458322431, 0.0001683754479456738, 0.0, 0.0003587284172453867, 0.00017293200498848488, 4.2696072079051175e-05, 0.00045091642091311116, -1.1863812242775575e-05, -0.00024247507138728597, -0.00015583372845762609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023980062534796138, 0.035466506002346784, -0.08924263054155514, -0.00545090771885237, -0.012384280652634735, 0.04136035208706627, 0.08003102835549275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.761465067164659e-09, -5.5607647810329235e-09, -0.00030677510407153255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922616295505392, 0.23483817896123738, 0.8410490852513846, 0.0, -0.12445119489880907, -0.24452743829899679, -2.6082283837711637, -0.7133823305847966, -0.5580942928161348, -1.198584998145203, -2.8765575520800817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4969715275917248, 0.8836059669803608, 1.0154605812500674, -1.196811747499963, -2.2102104377362424, -0.39279250428916135, 1.6464284343560336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095867687, -0.44034091547339604, 0.024246327492719974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.574112335228865e-06, 0.0002826556617451584, 0.00015715814321276875, 0.0, 0.00035890981421632693, 0.00017571213007928167, 4.1686286744317405e-05, 0.0004508790270657108, -1.0966459037819545e-05, -0.00024190704235009058, -0.00015615371771426863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024196763055897286, 0.035370771654048096, -0.08940016802979006, -0.0054821110552363845, -0.012952486282172465, 0.04134191142918913, 0.0804962925636271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.911807805937267e-09, -5.5112561318106675e-09, -0.0003067224401001848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922579680585263, 0.23485230751964287, 0.8410551260082697, 0.0, -0.12443324572456714, -0.24451864694277212, -2.6082263344864067, -0.7133597902155533, -0.5580948123792668, -1.1985970672594228, -2.8765653691833957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49575086226104903, 0.8853696289438552, 1.0109827884664662, -1.1970873906083481, -2.2108868656457132, -0.39072642862796775, 1.65047679939993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960955656938, -0.4403409157463759, 0.024230995521878285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.322984026012576e-06, 0.0002825711681099264, 0.00012081513770211566, 0.0, 0.00035898348483850577, 0.00017582712449362893, 4.098569513964275e-05, 0.0004508073848668016, -1.0391262641673134e-05, -0.00024138228439390562, -0.0001563420662759655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02441330661351502, 0.035273239269888054, -0.0895558556720272, -0.005512862167700783, -0.013528558189413202, 0.04132151322387183, 0.08096730087792933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.039863141520829e-09, -5.459597199002481e-09, -0.00030663941683379875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922544348864547, 0.23486643055305054, 0.8410516600789181, 0.0, -0.12441531025423512, -0.24451022400760422, -2.608224252247095, -0.7133372533672377, -0.558095373430019, -1.198609123703882, -2.876573169694533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4945193854577599, 0.8871283156303824, 1.006497328144911, -1.1973645468070087, -2.2115924913823406, -0.388661482186963, 1.6545489860475655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095262447, -0.44034091601655695, 0.024215669123602613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.066344143356634e-06, 0.0002824606681536391, -6.931858703256564e-05, 0.0, 0.0003587094066402643, 0.00016845870335784188, 4.1644786232455846e-05, 0.00045073696631083623, -1.1221015042756142e-05, -0.00024112888918500513, -0.00015601022275316007, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02462953606578174, 0.035173733730543714, -0.08970920643110362, -0.00554312397321154, -0.014112514732550215, 0.041298928820095435, 0.0814437329527083, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0649334679944005e-09, -5.403621012739874e-09, -0.00030652796551343983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922510287796178, 0.23488054673289557, 0.8410453123797789, 0.0, -0.12439739345231203, -0.24450208979585292, -2.608222123215735, -0.7133147218632591, -0.5580959904178329, -1.198621169241677, -2.876580947616735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4932771206221174, 0.8888819200328602, 1.002004340587019, -1.1976431899810067, -2.2123277102860492, -0.38659778527636235, 1.658645250560513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196094961182, -0.44034091628382155, 0.02420034975651545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.812213673893282e-06, 0.00028232359690059553, -0.00012695398278336715, 0.0, 0.00035833603846176075, 0.00016268423502602524, 4.2580627199534485e-05, 0.00045063007957435767, -1.2339756277197146e-05, -0.00024091075590005698, -0.00015555844404097243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02484529671285001, 0.035072088049553814, -0.08985975115784277, -0.005572863479960354, -0.014704378074173489, 0.04127393821201264, 0.08192529025895022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0252987988901175e-09, -5.345292444117205e-09, -0.0003063873417432767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922477524753944, 0.23489465477246935, 0.8410452074994145, 0.0, -0.12437950954869476, -0.24449439493203598, -2.6082198931027345, -0.7132921961287746, -0.5580967194820536, -1.1986332144417962, -2.87658868200518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4920240985108147, 0.8906303281832448, 0.997503986963954, -1.1979232922787466, -2.2130929177335372, -0.38453546777582476, 1.6627658355278006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960946663445, -0.44034091654796714, 0.02418503883586631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.55260844684948e-06, 0.00028216079147531595, -2.0976072879545196e-06, 0.0, 0.0003576780723454631, 0.00015389727633898903, 4.460226001287e-05, 0.00045051468968865444, -1.4581284414749146e-05, -0.00024090400238012088, -0.00015468776889814983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025060442226055177, 0.03496816300769299, -0.0900070724612974, -0.005602045954796174, -0.015304148949760347, 0.0412463500107513, 0.08241169934575161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.896747979429786e-09, -5.282911832871913e-09, -0.0003062184129828008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922445995118852, 0.23490875335282946, 0.8410484974848362, 0.0, -0.12436162721644259, -0.2444862530313363, -2.6082177053556697, -0.7132696829483258, -0.5580974129435289, -1.1986452270616588, -2.876596425174763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49076035572194887, 0.8923734214703991, 0.9929964432129866, -1.198204825000671, -2.213888511169073, -0.38247466647819256, 1.6669109766511037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960943694733, -0.4403409168091144, 0.024169737799255797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.305927018371171e-06, 0.00028197160720243975, 6.57997084341371e-05, 0.0, 0.00035764664504322043, 0.00016283801399335354, 4.3754941293355606e-05, 0.00045026360897635297, -1.3869229504038548e-05, -0.0002402523972538747, -0.00015486339166848937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025274855777316755, 0.03486186574308656, -0.09015087501934801, -0.005630654438487442, -0.015911868710717047, 0.04121602595264391, 0.0829028224660603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.937423846599186e-09, -5.22294577457969e-09, -0.00030602073221025353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922415758091562, 0.2349228411724104, 0.8410526983818923, 0.0, -0.12434374248924537, -0.24447768873916056, -2.60821558440803, -0.7132471849890912, -0.5580980457685073, -1.19865720078781, -2.8766041854502538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4894859337370256, 0.8941110786251171, 0.9884818963113168, -1.1984877579817428, -2.214714887686934, -0.38041552288820757, 1.6710809034491936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960940678644, -0.4403409170672489, 0.02415444805994494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.047405458144199e-06, 0.0002817563916189022, 8.401794112132126e-05, 0.0, 0.0003576945439442653, 0.00017128584351477422, 4.241895279880636e-05, 0.0004499591846913434, -1.2656499568355628e-05, -0.00023947452302428265, -0.00015520550981206458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025488439698465194, 0.034753143094359555, -0.09029093803339643, -0.005658659621436673, -0.016527530357216394, 0.04118287179970025, 0.08339853596179836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.03217883464038e-09, -5.1626905210071585e-09, -0.00030579478621716805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922386825645328, 0.23493691690624557, 0.8410564512649941, 0.0, -0.1243258594111105, -0.24446889925952728, -2.6082135201018084, -0.7132247038994421, -0.5580986285853954, -1.1986691367474456, -2.8766119583016656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48820087632289133, 0.8958431793631576, 0.983960534776307, -1.1987720604255176, -2.2155724461756536, -0.3783581789414705, 1.6752758485502535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960937612354, -0.4403409173222983, 0.024139171052652106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786489246427161e-06, 0.0002815146767031294, 7.505766203420739e-05, 0.0, 0.00035766156269743726, 0.00017578959266584843, 4.1286124428578224e-05, 0.0004496217929827031, -1.1656337761063967e-05, -0.00023871919271227572, -0.00015545702823389334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025701148282685583, 0.03464201476081067, -0.09042723070019727, -0.005686048875495764, -0.017151169774387676, 0.04114687893474189, 0.08389890202119733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.132577920404379e-09, -5.1009871084421215e-09, -0.00030554014585668624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092235922605165, 0.23495097923899583, 0.8410519427358509, 0.0, -0.12430799797295512, -0.24446039171558423, -2.6082114331239783, -0.7132022392024135, -0.5580992433130904, -1.1986810509852375, -2.8766197135440503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4869052277139634, 0.8975696069788188, 0.9794325421284801, -1.1990577012557722, -2.2164615881936442, -0.37630277396989964, 1.679496053466264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960934548712, -0.4403409175740272, 0.024123908203004432]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.519918735469442e-06, 0.0002812466550050523, -9.017058286262138e-05, 0.0, 0.0003572287631076722, 0.00017015087886112826, 4.173955660569902e-05, 0.00044929394057188977, -1.2294553899290337e-05, -0.00023828475583984556, -0.00015510484769303776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025912972178559337, 0.034528552313223757, -0.09055985295653808, -0.005712816605088591, -0.017782840359812042, 0.04110809943141729, 0.08440409832021027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.127284994485085e-09, -5.034578465706776e-09, -0.0003052569929535026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922332950507752, 0.23496502672304753, 0.841047783413629, 0.0, -0.12429016966556214, -0.24445225590891467, -2.60820928186934, -0.7131797919809006, -0.5580999330293639, -1.1986929512033815, -2.8766274348355845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48559903131642573, 0.8992902496173529, 0.9748980930181969, -1.199344649530385, -2.2173827195828784, -0.3742494430608768, 1.6837417729196484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196093153261, -0.44034091782227236, 0.02410866107571083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.2551087796667704e-06, 0.0002809496810341711, -8.318644443892944e-05, 0.0, 0.00035656614785969763, 0.0001627161333910628, 4.3025092769582105e-05, 0.0004489444302589652, -1.3794325470608606e-05, -0.0002380043628809906, -0.000154425830679982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02612392795075296, 0.03441285277068236, -0.09068898220566399, -0.005738965492258566, -0.018422627784678763, 0.04106661818045598, 0.08491438906769068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0322003801230195e-09, -4.964903312858732e-09, -0.0003049425458720436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922307991070202, 0.23497905786820408, 0.8410556573019119, 0.0, -0.12427237387831729, -0.2444442940500671, -2.608207077567316, -0.7131573652116887, -0.5581006863642975, -1.1987048335720254, -2.8766351253435607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4842823300878567, 0.9010049998697255, 0.9703573543408388, -1.1996328745291291, -2.2183362506259474, -0.3721983176407974, 1.6880132741548193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960928754658, -0.44034091806592374, 0.024093431277851397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.991887509777812e-06, 0.0002806229031311392, 0.00015747776565822725, 0.0, 0.0003559157448970038, 0.00015923717695157525, 4.408604048309066e-05, 0.00044853538423953636, -1.5066698673928943e-05, -0.00023764737287945692, -0.00015381015952641166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026334024571381103, 0.0342950050474507, -0.09081477354716017, -0.005764499974883995, -0.01907062086137703, 0.041022508401587915, 0.08543002470341639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.555908666280711e-09, -4.8730279323739366e-09, -0.00030459595718869284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922284323115387, 0.23499307108162593, 0.8410620224473074, 0.0, -0.12425458744531685, -0.24443588510526554, -2.608204929517324, -0.7131349647765528, -0.5581013908433606, -1.1987166731633414, -2.8766428246415074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48295516731288507, 0.9027137532260882, 0.9658104886496258, -1.1999223453926828, -2.219322595734824, -0.37014952706588417, 1.6923108338763249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960925990926, -0.4403409183058999, 0.024078220512936645]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.7335909628940805e-06, 0.00028026426843671655, 0.00012730290790996507, 0.0, 0.00035572866000864066, 0.00016817889603117935, 4.296099983475214e-05, 0.00044800870271772164, -1.408958126273807e-05, -0.0002367918263207148, -0.00015398595893936561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02654325549943236, 0.034175067127253114, -0.09093731382426007, -0.005789417271074297, -0.019726902177531216, 0.040975811498265485, 0.08595119443011036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527463615746055e-09, -4.799523095846143e-09, -0.0003042152982949902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922261997224498, 0.2350070647912494, 0.8410577045336366, 0.0, -0.12423681243828566, -0.24442719122016499, -2.6082028373758583, -0.7131125929317202, -0.5581020469926288, -1.1987284688445206, -2.876650531726507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48161758806816896, 0.904416406601707, 0.9612576589459293, -1.2002130305739471, -2.2203421712282, -0.36810320061496893, 1.696634732660511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196092317279, -0.44034091854252083, 0.024063030469186026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.465178177833702e-06, 0.00027987419246927657, -8.635827341689408e-05, 0.0, 0.00035550014062387086, 0.00017387770201113094, 4.184282931522522e-05, 0.000447436896650261, -1.3122985361760713e-05, -0.0002359136235845094, -0.0001541416999878178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026751584894322514, 0.034053067512376585, -0.09105659407393087, -0.005813703625287087, -0.020391509867517234, 0.04092652901830437, 0.08647797568372015, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.636273932491716e-09, -4.732419414340443e-09, -0.00030380087501240055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922241016812146, 0.23502103740905048, 0.8410463694385787, 0.0, -0.12421905333043677, -0.24441836995158422, -2.608200790619741, -0.7130902517633231, -0.5581026658436722, -1.198740221602538, -2.8766582417647193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48026963952599694, 0.9061128577303539, 0.9566990298493572, -1.20050489804106, -2.221395396086243, -0.36605946817557733, 1.700985254766309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960920279746, -0.44034091877582304, 0.024047862863995576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.1960824706491225e-06, 0.0002794523560217615, -0.0002267019011576197, 0.0, 0.00035518215697770964, 0.00017642537161540508, 4.0935122353427696e-05, 0.0004468233679431487, -1.2377020867531316e-05, -0.00023505516034913785, -0.00015420076425019393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026958970843440316, 0.03392902257293763, -0.09117258193144308, -0.005837349342256303, -0.02106449716086064, 0.04087464878783213, 0.08701044211595904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786086760284027e-09, -4.666044771786301e-09, -0.00030335210380902497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922221440887018, 0.23503498739762702, 0.841036886455467, 0.0, -0.1242013481825966, -0.24441026653189415, -2.608198632835657, -0.7130679387372286, -0.5581034088108263, -1.1987519639596742, -2.876665895865233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4789113717793767, 0.9078030043511358, 0.9521347702517232, -1.200797914844916, -2.222482690370258, -0.3640184612869564, 1.7053626847014656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196091741422, -0.4403409190052954, 0.024032719370823248]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.915185025717901e-06, 0.0002789997715310093, -0.0001896596622333224, 0.0, 0.00035410295680355535, 0.0001620683938012719, 4.315568167552039e-05, 0.0004462605218899997, -1.4859343083454556e-05, -0.0002348471427225327, -0.00015308201027994006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027165354932404285, 0.03380293241563895, -0.09128519195267903, -0.005860336077119565, -0.021745885680302154, 0.04082013777241842, 0.08754859870313353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.731050726891179e-09, -4.58944610775106e-09, -0.0003028698634465459]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922203164538525, 0.23504891307276912, 0.841032541842507, 0.0, -0.12418366740896726, -0.24440192084839657, -2.6081965020990285, -0.7130456612191032, -0.5581041338020172, -1.1987636644722774, -2.876673544051086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4775428382354116, 0.9094867432162603, 0.9475650547121593, -1.2010920480404839, -2.223604478160592, -0.3619803142765615, 1.7097673090060426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960914598313, -0.4403409192310516, 0.02401760180827296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.655269698775106e-06, 0.00027851350284206105, -8.689225920218913e-05, 0.0, 0.00035361547258678437, 0.00016691366995180907, 4.2614732565614394e-05, 0.00044555036250906017, -1.4499823817667592e-05, -0.00023401025206547227, -0.0001529637170595984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027370670879302096, 0.033674777302491084, -0.09139431079127737, -0.005882663911359049, -0.022435755806672526, 0.04076294020789779, 0.08809248609153901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.631816940030336e-09, -4.515125428379149e-09, -0.0003023512510057976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218624636338, 0.23506281281421168, 0.8410356756575126, 0.0, -0.12416600432264169, -0.24439321694763538, -2.608194436426376, -0.7130234228233399, -0.5581048018148895, -1.1987753136380845, -2.876681199480581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47616409798292436, 0.9111639678647261, 0.9429900709564467, -1.2013872631601683, -2.224761182138141, -0.3599451670496676, 1.7141994056720824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960911738547, -0.44034091945324066, 0.024002511926413173]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383635029025387e-06, 0.00027799482885125325, 6.26763001119526e-05, 0.0, 0.00035326172651137423, 0.0001740780152235415, 4.131345304538199e-05, 0.00044476791526665467, -1.3360257447749238e-05, -0.00023298331614080524, -0.0001531085898994188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027574805049744477, 0.03354449296931504, -0.09149967511425215, -0.005904302393688978, -0.023134079550981332, 0.04070294453787818, 0.08864193332079673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.719530654727784e-09, -4.443781211465503e-09, -0.0003017976371957132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922170704203732, 0.23507668502075083, 0.8410423074849374, 0.0, -0.1241483623155468, -0.244384310557527, -2.6081924300125126, -0.7130012257667365, -0.5581054190160493, -1.1987869114340584, -2.876688859076571, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47477521540227136, 0.9128345692861699, 0.9384100182269607, -1.20168352459866, -2.225953224315494, -0.35791316440846443, 1.7186592461985255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960908809377, -0.44034091967180033, 0.02398745145288188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1084319293768643e-06, 0.00027744413078277237, 0.0001326365484943806, 0.0, 0.00035284014189772793, 0.00017812780216790056, 4.01282772728635e-05, 0.00044394113206605953, -1.2344023195454017e-05, -0.00023195591947688265, -0.00015319191979646822, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02777765161305974, 0.033412028428875376, -0.09160105458971957, -0.0059252287698322425, -0.02384084354705729, 0.04064005282406402, 0.08919681052886042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.858339466261557e-09, -4.371193406864528e-09, -0.00030120947062583256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922156543450052, 0.23509052810004516, 0.8410492694389827, 0.0, -0.12413074689682618, -0.24437535618911002, -2.6081904678915984, -0.712979072046481, -0.5581060010212636, -1.1987984597786585, -2.8766965163409224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47337625952659734, 0.9144984368578705, 0.9338251048857156, -1.2019807958468574, -2.2271810265116145, -0.3558844549669417, 1.7231470978947316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960905813695, -0.44034091988659374, 0.023972422108249798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8321507362843026e-06, 0.00027686158588654494, 0.00013923908090758875, 0.0, 0.00035230837441229307, 0.00017908736833938907, 3.9242418287363135e-05, 0.0004430744051094812, -1.1640104287746735e-05, -0.00023096689200289316, -0.00015314528703072957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02797911751348016, 0.03327735143401081, -0.09169826682490159, -0.00594542496394866, -0.024556043922417028, 0.0405741888304541, 0.08975703392412263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.99136182881903e-09, -4.295868409399808e-09, -0.00030058689264164613]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092214376950768, 0.2351043404631002, 0.841055000947925, 0.0, -0.12411316316685755, -0.24436644803037927, -2.6081885369185116, -0.7129569637734708, -0.5581065615745155, -1.1988099601669355, -2.8767041654304397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4719673035386995, 0.916155459116594, 0.9292355465253229, -1.2022790396236822, -2.228445010501852, -0.3538591902620027, 1.7276632254874882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196090276409, -0.44034092009746506, 0.023957425614455224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.554788474152601e-06, 0.00027624726110047753, 0.00011463017884518368, 0.0, 0.0003516745993725979, 0.000178163174614961, 3.861946173756925e-05, 0.0004421654602037304, -1.1211065038467111e-05, -0.00023000776553994804, -0.0001529817903483625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02817911975795758, 0.033140445174471, -0.09179116720785228, -0.005964875536498757, -0.025279679804751456, 0.04050529409878031, 0.0903225518551289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.099211472283008e-09, -4.217426245952425e-09, -0.00029992987589149664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132402106286, 0.23511812054038544, 0.8410520894025295, 0.0, -0.12409562383109912, -0.2443578314158735, -2.608186590890484, -0.712934902017406, -0.5581071484951111, -1.1988214212369817, -2.8767117882556934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47054842423382764, 0.9178055245993192, 0.9246415639932796, -1.202578217928743, -2.229745597925077, -0.3518375237867856, 1.7322078925422681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196089970556, -0.4403409203040926, 0.023942463678312494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2734802787669106e-06, 0.00027560154570521126, -5.8230907909955594e-05, 0.0, 0.000350786715168619, 0.0001723322901152663, 3.892056055380001e-05, 0.00044123512129748107, -1.1738411910820731e-05, -0.0002292214009220766, -0.0001524565050773675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028377586097436923, 0.033001309654503014, -0.09187965064086771, -0.0059835661012142315, -0.02601174846449523, 0.0404333295043409, 0.09089334109560107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.1170619527525975e-09, -4.1325504136064795e-09, -0.00029923872285463716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922122434115142, 0.23513186671753447, 0.8410480627601596, 0.0, -0.12407813314545002, -0.24434945545829273, -2.608184620574443, -0.7129128891496048, -0.5581077715045112, -1.198832843569758, -2.8767193803773026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4691197012732411, 0.9194485226447213, 0.9200433810360168, -1.2028782923185342, -2.2310832111884804, -0.34981960999287814, 1.7367813640484877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960896649155, -0.44034092050638907, 0.02392753805860094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.993598228687448e-06, 0.0002749235429804493, -8.053284739664491e-05, 0.0, 0.00034981371298213994, 0.00016751915161527365, 3.9406320815882495e-05, 0.0004402573560225493, -1.2460188001387484e-05, -0.00022844665552575148, -0.00015184243218659447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028574459211730487, 0.032859960908041684, -0.09196365914525552, -0.006001487795825586, -0.026752265268074542, 0.04035827587814968, 0.09146943012439056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.112808490593471e-09, -4.045929541332256e-09, -0.00029851239423111863]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211389827854, 0.23514557736365363, 0.8410578585477725, 0.0, -0.12406070988152301, -0.24434158934098602, -2.608182553769859, -0.7128909254979008, -0.5581085052234442, -1.1988442413850604, -2.8767269140492373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4676812169158026, 0.9210843438719359, 0.9154412233761499, -1.2031792237209296, -2.2324582726969604, -0.3478056037279826, 1.741383906369289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960893591872, -0.44034092070432945, 0.023912650529372945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7071673205114855e-06, 0.00027421292238309636, 0.00019591575225744434, 0.0, 0.00034846527854018143, 0.000157322346134472, 4.133609168080293e-05, 0.0004392730340808338, -1.4674378662152341e-05, -0.00022795630604805403, -0.00015067343869631415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02876968714876997, 0.032716424544291745, -0.09204315319733973, -0.006018628047907992, -0.027501230169602837, 0.0402801252979109, 0.09205084641602652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.114568185997018e-09, -3.958807443717854e-09, -0.0002977505845598786]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210672469882, 0.23515925083401482, 0.8410652320488057, 0.0, -0.12404332566823896, -0.24433336627992613, -2.608180522997439, -0.7128690180598636, -0.5581092132659031, -1.1988555845615416, -2.876734437299029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46623305579286745, 0.9227128804080058, 0.9108353175470177, -1.2034809732727259, -2.2338712072731286, -0.3457956600814619, 1.7460157904635891, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960890519567, -0.44034092089783095, 0.02389780286694324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4347159446389079e-06, 0.00027346940722347367, 0.00014747002066334785, 0.0, 0.0003476842656809194, 0.00016446122119761613, 4.0615448397339356e-05, 0.0004381487607450033, -1.4160849177094524e-05, -0.00022686352962361731, -0.00015046499583523993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896322245870369, 0.03257073072139712, -0.09211811658264313, -0.00603499103592687, -0.028258691523363376, 0.04019887293041388, 0.09263768188600079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.144607672069865e-09, -3.870029836860596e-09, -0.0002969532485941604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210100400509, 0.23517288551398433, 0.8410664138041404, 0.0, -0.1240259996089749, -0.24432528532443024, -2.608178454395147, -0.7128471669546982, -0.5581099719448497, -1.198866887773201, -2.8767419218274246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4647753056448859, 0.9243340253193703, 0.9062258936717704, -1.2037835010299036, -2.235322437674143, -0.3437899350125588, 1.750677285561212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960887517417, -0.44034092108648143, 0.023882996819733292]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1441387459766836e-06, 0.0002726935993901465, 2.3635106694689962e-05, 0.0, 0.00034652118528124735, 0.0001616191099181937, 4.1372045842379415e-05, 0.0004370221033072508, -1.5173578930017302e-05, -0.0002260642331865976, -0.00014969056791598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029155002959631346, 0.03242289822728867, -0.09218847750494656, -0.006050555143554061, -0.029024608020289562, 0.04011450137806245, 0.09322990195245989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.004299680337448e-09, -3.7730098884789655e-09, -0.0002961209441989173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092209669726632, 0.23518647970489048, 0.8410609226416369, 0.0, -0.12400872906868333, -0.24431719191532206, -2.608176369004111, -0.7128253755692321, -0.5581107597717642, -1.1988781450453656, -2.876749374387809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4633080561386832, 0.9259476735196431, 0.9016131818317626, -1.2040867669585253, -2.236812388228808, -0.34178858417897373, 1.7553686651971052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960884538656, -0.44034092127040986, 0.023868234227515342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.613477534914119e-07, 0.00027188381812338203, -0.00010982325006922625, 0.0, 0.000345410805831185, 0.00016186818216330927, 4.170782071484811e-05, 0.0004358277093212305, -1.575653829063398e-05, -0.00022514544329536624, -0.0001490512076832327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029344990124054126, 0.03227296400545834, -0.09225423680015506, -0.006065318572435898, -0.02979901109329317, 0.0400270166717004, 0.09382759271786134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.957524940023932e-09, -3.6785690750768175e-09, -0.0002952518443589767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093822929072, 0.2352000317341201, 0.8410524181684602, 0.0, -0.12399151746904731, -0.24430910863530028, -2.608174261444083, -0.7128036463850764, -0.5581115824848359, -1.1988893561534155, -2.876756791973215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46183139963036696, 0.9275537212519152, 0.8969974141792522, -1.2043907305783736, -2.238341482998964, -0.3397917636906221, 1.7600902039997306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960881578726, -0.4403409214495698, 0.0238535169087839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.748674497860114e-07, 0.0002710405845922016, -0.00017008946353326963, 0.0, 0.0003442319927206149, 0.0001616656004355191, 4.215120056168994e-05, 0.00043458368311318613, -1.645426143494226e-05, -0.0002242221609999945, -0.00014835170811919904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029533130166324435, 0.03212095464544021, -0.09231535305020915, -0.006079272396967082, -0.030581895403125385, 0.039936409767033054, 0.09443077605250862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.91986084688446e-09, -3.5831994274456708e-09, -0.0002943463746288033]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373323128, 0.23521353992827793, 0.8410438725266971, 0.0, -0.12397436044111262, -0.244300887496518, -2.6081721601693726, -0.7127819829808627, -0.558112410947662, -1.1989005135506143, -2.876764184099484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4603454313905481, 0.9291520657795702, 0.8923788256592536, -1.204695351075815, -2.239910145922031, -0.33779963049762673, 1.7648421773105925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960878624786, -0.4403409216239188, 0.023838846682848473]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8992118888876934e-07, 0.0002701638831565353, -0.00017091283526128758, 0.0, 0.0003431405586938345, 0.00016442277564585636, 4.202549420018781e-05, 0.00043326808427352663, -1.6569256520598532e-05, -0.00022314794397777974, -0.0001478425253884784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029719364796376244, 0.03196689055310157, -0.09237177039997145, -0.006092409948825406, -0.031373258461334215, 0.03984266385990679, 0.09503946621723514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907879199330411e-09, -3.486980077253522e-09, -0.00029340451870856404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373722798, 0.23522700262504698, 0.8410374403757168, 0.0, -0.12395726578111037, -0.24429269050492022, -2.6081700407288655, -0.7127603871926259, -0.5581132705496118, -1.1989116211622244, -2.8767715407119447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.458850249996433, 0.9307426050694383, 0.8877576552539141, -1.2050005870186693, -2.2415187994729133, -0.3358123427934258, 1.7696248590278236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196087569427, -0.4403409217933179, 0.023824225354744655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.993361838705048e-11, 0.0002692539353811438, -0.00012864301960679008, 0.0, 0.0003418932000452387, 0.00016393983195510124, 4.2388810139131095e-05, 0.0004319157647347982, -1.719203899706572e-05, -0.00022215223220196987, -0.00014713224921229104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029903627882302698, 0.03181078579736128, -0.09242340810678894, -0.006104718857087361, -0.03217307101764898, 0.039745754084018536, 0.09565363434462144, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.861033564134219e-09, -3.387982440439172e-09, -0.0002924265620763873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093803793915, 0.23524041814845156, 0.8410374906842297, 0.0, -0.12394022730095001, -0.2442843307062041, -2.6081679394647272, -0.712738862857545, -0.558114124022187, -1.198922669739127, -2.8767788742441045, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4573459573374052, 0.9323252377254454, 0.8831341459157536, -1.2053063966618953, -2.2431678654292573, -0.33383006012496247, 1.7744385224039096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960872769383, -0.4403409219577329, 0.02380965473961995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.860142235474362e-07, 0.0002683104680918212, 1.0061702575075656e-06, 0.0, 0.0003407696032069348, 0.00016719597432282023, 4.202528276281991e-05, 0.00043048670161862127, -1.706945150298024e-05, -0.0002209715380559683, -0.0001466706431985636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03008585318055555, 0.031652653120141615, -0.09247018676321055, -0.00611619286451865, -0.032981319126879634, 0.039645653369266835, 0.09627326752172037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.849774123333481e-09, -3.2882997372638714e-09, -0.0002914123024940956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922096657396688, 0.2352537848481625, 0.8410424879608319, 0.0, -0.12392323099804707, -0.24427550322994218, -2.608165926451545, -0.7127174147928246, -0.5581148993177725, -1.1989336427949417, -2.876786209655038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4558326592403161, 0.9338998624960788, 0.8785085463058647, -1.2056127377883856, -2.2448577636846556, -0.3318529440691488, 1.7792834377311177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960869837198, -0.44034092211708964, 0.023795136622358486]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.707205544453632e-07, 0.00026733399421898104, 9.99455320436035e-05, 0.0, 0.00033992605805876916, 0.00017654952523818242, 4.026026364787405e-05, 0.00042896129440782137, -1.550591171088359e-05, -0.0002194611162937864, -0.000146708218664564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030265961941782726, 0.03149249541266861, -0.09251199219777764, -0.0061268225298059045, -0.03379796510796265, 0.039542321116274225, 0.09689830654416252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.86437310864071e-09, -3.187134913313221e-09, -0.00029036234522933065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922100965552448, 0.23526710107514773, 0.8410490640684287, 0.0, -0.12390627994451152, -0.2442664026430487, -2.60816399756591, -0.7126960453592284, -0.5581156008578939, -1.198944539937928, -2.8767935444610173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4543104655338203, 0.9354663782831726, 0.8738811111354717, -1.2059195673919778, -2.246588910859805, -0.3298811581868147, 1.7841598707715598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960866898349, -0.4403409222713018, 0.023780672785392188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.616311522513805e-07, 0.0002663245397044324, 0.0001315221519361624, 0.0, 0.000339021070711086, 0.0001820117378696219, 3.857771269517252e-05, 0.0004273886719234314, -1.4030802428831007e-05, -0.00021794285972423394, -0.0001466961195899939, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030443874129915626, 0.031330315741874865, -0.09254870340785973, -0.006136592071843622, -0.03462294350299033, 0.039435717646682064, 0.09752866080883925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.877696582075045e-09, -3.0842428966251893e-09, -0.00028927673932593894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210673237465, 0.235280365187046, 0.8410550975979828, 0.0, -0.12388938100491373, -0.24425724891563522, -2.608162132255566, -0.7126747564615128, -0.5581162500032212, -1.1989553642943187, -2.8768008700700447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4527794894455337, 0.9370246848142204, 0.8692520991614596, -1.2062268420164741, -2.2483617212788136, -0.3279148672301889, 1.7890680851332526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960863958802, -0.4403409224202819, 0.023766265007226756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1533644406949973e-06, 0.00026528223796546833, 0.00012067059108091881, 0.0, 0.00033797879195573256, 0.00018307454826957186, 3.73062068809094e-05, 0.00042577795431106595, -1.2982906544877191e-05, -0.0002164871278149365, -0.00014651218054448473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030619521765731874, 0.031166130620956245, -0.09258023948024134, -0.006145492489924126, -0.03545620838017727, 0.03932581913251551, 0.09816428723385391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.879091789393594e-09, -2.979601671892309e-09, -0.0002881555633086335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211398984335, 0.2352935755878579, 0.8410555050831465, 0.0, -0.12387255996124569, -0.24424862974986714, -2.6081602276898908, -0.7126535474193972, -0.5581169529252559, -1.198966136758033, -2.8768081474179703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4512398472649066, 0.9385746831577152, 0.8646217720329866, -1.20653451772497, -2.2501766065511055, -0.32595423653796046, 1.7940083427031794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960861098235, -0.4403409225636437, 0.023751915023692883]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.451493739797756e-06, 0.0002642080162376779, 8.149703274743813e-06, 0.0, 0.0003364208733607873, 0.00017238331536136223, 3.809131350543452e-05, 0.00042418084231146783, -1.4058440694780964e-05, -0.00021544927428580668, -0.00014554695851592048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03079284361254177, 0.030999966869896325, -0.0926065425694596, -0.00615351416991691, -0.036297705445837984, 0.03921261384456869, 0.09880515139853736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.721133778020836e-09, -2.8672360332484574e-09, -0.00028699967067747945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221227393265, 0.23530673061450377, 0.8410565945129704, 0.0, -0.12385584263010913, -0.24424086611527335, -2.608158181332645, -0.7126324177743517, -0.5581178155082985, -1.1989768780505843, -2.8768153374764402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4496916576505383, 0.9401162761748174, 0.8599903925518251, -1.2068425503342475, -2.252033976608772, -0.3239994313693354, 1.798980905793647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960858334568, -0.4403409227013466, 0.02373762464347082]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.749896630280465e-06, 0.0002631005329173592, 2.1788596477419196e-05, 0.0, 0.00033434662273115046, 0.00015527269187593876, 4.092714491516038e-05, 0.0004225929009102559, -1.7251660853081745e-05, -0.0002148258510234415, -0.00014380116939687583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030963792287366225, 0.03083186034204511, -0.09262758962322996, -0.006160652185548577, -0.037147401153326536, 0.0390961033725009, 0.09945126180934931, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527332100915927e-09, -2.7540586281405656e-09, -0.0002858076044412479]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132919391548, 0.23531982864719386, 0.841063223931719, 0.0, -0.1238392122362804, -0.24423321920061875, -2.6081560758377376, -0.7126113735463446, -0.5581187527877131, -1.1989875685837716, -2.8768224695965015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44813504236501883, 0.941649368224787, 0.8553582259425409, -1.2071508962014381, -2.2539342407502954, -0.3220506177501416, 1.8039860375006576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196085635504, -0.44034092283093423, 0.023723395630806134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.03601300906797e-06, 0.0002619606538019357, 0.0001325883749712573, 0.0, 0.0003326078765743858, 0.000152938293091898, 4.210989814999217e-05, 0.0004208845601416009, -1.8745588290554045e-05, -0.00021381066374907771, -0.00014264240122127474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031132305710390124, 0.030661840999390497, -0.09264333218568391, -0.006166917343814103, -0.03800528283046801, 0.038976272383875785, 0.10010263414021117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.959053397238659e-09, -2.5917525910362977e-09, -0.00028458025329374653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922144519139135, 0.2353328680869434, 0.8410676669346647, 0.0, -0.12382263726512502, -0.24422491913739267, -2.6081540567514145, -0.7125904214700881, -0.5581196148820815, -1.1989981758353803, -2.8768295968508615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4465701270552781, 0.9431738636921824, 0.8507255432224222, -1.207459510790999, -2.2558778039573784, -0.3201079635102819, 1.8090239953968683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960854533182, -0.4403409229545072, 0.023709229726479042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199495176391782e-06, 0.00026078879499084965, 8.886005891627416e-05, 0.0, 0.0003314994231077098, 0.00016600126452181964, 4.038172646392046e-05, 0.00041904152513015484, -1.7241887368174105e-05, -0.0002121450321726098, -0.00014254508720348415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03129830619481516, 0.030489909347908482, -0.09265365440237223, -0.006172291791215753, -0.03887126414166291, 0.038853084797193384, 0.1007591579242136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.643715639193411e-09, -2.4714595723696988e-09, -0.00028331808654188023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922157604694372, 0.23534584736592495, 0.8410668504909772, 0.0, -0.12380612670554354, -0.24421636926187285, -2.6081520936769205, -0.7125695627130906, -0.5581204332535905, -1.1990087053101475, -2.8768367071660017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4449970414885467, 0.94468966757663, 0.8460926213960657, -1.2077683487512805, -2.2578650650041974, -0.3181716381099931, 1.8140950299117282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960852664008, -0.44034092307275113, 0.023695128639661108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6171110473867365e-06, 0.0002595855796310719, -1.6328873750977248e-05, 0.0, 0.0003302111916294966, 0.00017099751039630092, 3.9261489880747366e-05, 0.0004171751399507709, -1.636743018040559e-05, -0.0002105894953461487, -0.00014220630280115963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146171133462829, 0.030316077688951552, -0.09265843652713089, -0.006176759205631756, -0.0397452209363828, 0.038726508005776, 0.1014206902972002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.738346712078653e-09, -2.3648780842152937e-09, -0.00028202173635868386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922172187093444, 0.235358764914175, 0.8410654898822433, 0.0, -0.12378970357889556, -0.24420812020919186, -2.608150095496031, -0.7125487967681349, -0.5581213019711135, -1.1990191755044783, -2.8768437658949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4434159178476597, 0.9461966869587102, 0.8414597384723083, -1.2080773645313565, -2.2598964193485593, -0.31624181071038876, 1.8191993904816701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960850686543, -0.4403409231858745, 0.023681094082104545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.916479814417497e-06, 0.00025835096500088103, -2.721217467799101e-05, 0.0, 0.0003284625329597579, 0.00016498105361986836, 3.996361778996376e-05, 0.00041531889911317413, -1.7374350460272283e-05, -0.00020940388661766464, -0.00014117457796544163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03162247281773904, 0.03014038764160504, -0.09265765847514915, -0.006180315601519984, -0.040627086887241, 0.038596547992087005, 0.10208721139883624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.954931207271424e-09, -2.2624669460461017e-09, -0.00028069115113125986]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218820509567, 0.2353716191701673, 0.8410633476626547, 0.0, -0.1237733545919424, -0.24419974024874178, -2.6081481290056185, -0.7125281285220432, -0.5581221523588407, -1.1990295706059233, -2.8768507967261296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44182689050891993, 0.9476948312002192, 0.8368271724979245, -1.2083865130951508, -2.2619722611590123, -0.31431865007858156, 1.824337328212959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960848777775, -0.44034092329331354, 0.02366712775352238]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2036004456094876e-06, 0.0002570851198458028, -4.28443917725028e-05, 0.0, 0.00032697973906325436, 0.00016759920900176153, 3.932980824228668e-05, 0.000413364921835116, -1.7007754542764683e-05, -0.00020790202889795674, -0.0001406166245909901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03178054677479595, 0.02996288483018038, -0.09265131948767472, -0.006182971275886583, -0.04151683620905522, 0.038463212636144044, 0.10275875462577573, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.817535953222311e-09, -2.1487807233846523e-09, -0.00027932657164330354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221916360722, 0.23538440877937317, 0.84113623431204, 0.0, -0.12375716825404547, -0.24419305877140782, -2.608145824566453, -0.7125075583188882, -0.5581233419857754, -1.1990400234739393, -2.87685766726029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44024420765108996, 0.9491709563510456, 0.832235792593017, -1.208693270166394, -2.2640751584080365, -0.31229657903902314, 1.829464531952495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960847210564, -0.4403409233974491, 0.023653231142714507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.861953054122794e-07, 0.000255792184117114, 0.0014577329877055664, 0.0, 0.00032372675793870207, 0.00013362954667919574, 4.6088783318532606e-05, 0.0004114040630983184, -2.3792538695589267e-05, -0.0002090573603190461, -0.0001374106832015365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03165365715659935, 0.02952250301652904, -0.0918275980981496, -0.006135141424863823, -0.04205794498048291, 0.04044142079116874, 0.10254407479071907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1344232765148914e-09, -2.0827119200966643e-09, -0.00027793221615745386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922201868250198, 0.23539634306990492, 0.8412314006554471, 0.0, -0.12374207508064684, -0.24418789206263306, -2.6081432812967753, -0.7124882530489969, -0.5581248514787112, -1.1990499100341336, -2.8768639699113385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43850370439191116, 0.9507742115167876, 0.8272174784440234, -1.209027128457125, -2.266421303994671, -0.30998379134964577, 1.8351043704068524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846727415, -0.44034092351037646, 0.02364019598329647]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0464356000538463e-06, 0.00023868581063525855, 0.0019033268681426727, 0.0, 0.00030186346797247786, 0.00010333417549517549, 5.0865393554811415e-05, 0.0003861053978273925, -3.0189858715893594e-05, -0.00019773120388399588, -0.00012605302097634758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.034810065183576266, 0.03206510331484076, -0.10036628297987271, -0.006677165814621422, -0.0469229117326932, 0.04625575378754693, 0.11279676908714747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.66298946820811e-10, -2.2585461717950393e-09, -0.0002607031883607115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922216437310262, 0.2354080849464401, 0.8413213449530466, 0.0, -0.12372725721475548, -0.24418254640448694, -2.6081406111655814, -0.7124692442472988, -0.5581265156307138, -1.1990596621045952, -2.8768701100452763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43673363940883975, 0.9523871568461224, 0.8221391334650482, -1.2093648423795467, -2.26884706203803, -0.30766750998431247, 1.840851733829424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846677342, -0.44034092362250954, 0.023627366179124365]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.913812013021153e-06, 0.00023483753070400228, 0.00179888595198974, 0.0, 0.0002963573178272846, 0.00010691316292219053, 5.340262387741816e-05, 0.0003801760339596849, -3.328304005376323e-05, -0.00019504140923134718, -0.00012280267875417538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03540129966142834, 0.03225890658669601, -0.10156689957950295, -0.006754278448434319, -0.0485151608671812, 0.046325627306666436, 0.11494726845142962, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0014635555554529e-10, -2.242661711052622e-09, -0.00025659608344215124]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922230828349167, 0.23542179120280785, 0.8413961196175765, 0.0, -0.1237101320622456, -0.2441748125719034, -2.608137768907168, -0.7124473589817228, -0.5581281884138987, -1.1990708510518875, -2.8768772695111755, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4350979902425157, 0.9538648375688505, 0.8174609802263084, -1.2096783122332178, -2.271137094484585, -0.305621782567045, 1.846191036079717, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960845977244, -0.4403409237343511, 0.02361258903531463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8782077809993562e-06, 0.0002741251273545041, 0.0014954932906001, 0.0, 0.00034250305019766023, 0.0001546766516706125, 5.684516826768007e-05, 0.0004377053115208709, -3.3455663696616285e-05, -0.00022377894584475218, -0.0001431893179887565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03271298332648065, 0.029553614454562817, -0.09356306477479633, -0.006269397073421333, -0.04580064893110514, 0.04091454834535009, 0.10678604500586072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4001961193872394e-09, -2.236830667351529e-09, -0.0002955428761946808]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922243783393282, 0.23543903852997633, 0.8414513434500096, 0.0, -0.12368880508011355, -0.24416378984995993, -2.60813464483527, -0.7124202454252593, -0.5581298364460988, -1.1990846663697565, -2.876886296613515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4336623984435202, 0.9551532708001835, 0.8133606711026311, -1.209957272600563, -2.273199334011333, -0.3039200237919479, 1.850916595958042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196084406267, -0.44034092384720275, 0.023594268486829852]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.591008822977664e-06, 0.0003449465433696476, 0.001104476648661621, 0.0, 0.0004265396426407557, 0.00022045443886932763, 6.248143796103482e-05, 0.0005422711292714019, -3.296064400230728e-05, -0.0002763063573822093, -0.00018054204678421757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02871183597991043, 0.02576866462665916, -0.08200618247354668, -0.00557920734690619, -0.041244790534955666, 0.034035175501941975, 0.09451119756650121, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8291438123780864e-09, -2.2570332791828863e-09, -0.00036641096969553655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922255106794738, 0.23546013123742882, 0.8414867720698173, 0.0, -0.12366286242224352, -0.24414972837577267, -2.6081311939056873, -0.7123873802711952, -0.558131470146458, -1.1991013861642983, -2.876897373484767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43242675695397453, 0.9562573128632461, 0.8098307629874593, -1.2102024622712715, -2.2750240339463406, -0.30252510162345925, 1.8550265512441675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960840910455, -0.44034092395784474, 0.023572049757173866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.26468029088339e-06, 0.0004218541490494525, 0.0007085723961537018, 0.0, 0.0005188531574006369, 0.00028122948374484466, 6.901859164659148e-05, 0.0006573030812827114, -3.267400718439803e-05, -0.0003343958908373568, -0.00022153742504650204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02471282979091402, 0.022080841261251077, -0.07059816230343761, -0.004903793414171123, -0.036493998700152935, 0.027898443369773075, 0.0821991057225074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.304433286892409e-09, -2.2128403986714446e-09, -0.000444374593119745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922265159170025, 0.23548434886488395, 0.8415061255847035, 0.0, -0.1236330840946502, -0.24413351552177873, -2.608127454022146, -0.7123497254554765, -0.5581331059967973, -1.19912053705499, -2.8769101520880205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43135851539591985, 0.9572093754222624, 0.8067750353053372, -1.2104195732844663, -2.276643595151556, -0.3013598281014676, 1.8586187114510089, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960836810974, -0.44034092406159986, 0.023546586131306835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.010475057647412e-06, 0.0004843525491029461, 0.00038707029772529206, 0.0, 0.0005955665518662969, 0.0003242570798786655, 7.479767081710877e-05, 0.0007530963143733585, -3.2717006786872644e-05, -0.00038301781383230676, -0.00025557206506673664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021364831161093535, 0.01904125118032559, -0.06111455364244099, -0.00434222026389549, -0.032391224104307406, 0.023305470439832707, 0.07184320413682947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.19896031598218e-09, -2.0751025149419598e-09, -0.000509272517340654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922274555400075, 0.23551049919664788, 0.8415149219583403, 0.0, -0.12360081504552632, -0.24411619699799172, -2.6081235111311813, -0.712308950582451, -0.5581347560571188, -1.1991412817206182, -2.876924034508455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4304134333681977, 0.9580505897866057, 0.8040671225441811, -1.2106158703853926, -2.2781080914157794, -0.30034361325339415, 1.861827325592487, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960832140596, -0.44034092415520626, 0.023519010503724798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8792460097681025e-06, 0.0005230066352782863, 0.00017592747273691278, 0.0, 0.000645380982477355, 0.00034637047574014696, 7.885781929856352e-05, 0.0008154974605094604, -3.3001206429091666e-05, -0.00041489331256218425, -0.0002776484086882363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018901640554443433, 0.016824287286867967, -0.05415825522312133, -0.003925942018529482, -0.029289925284466382, 0.020324296961469136, 0.06417228282956303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.340756875042724e-09, -1.8721281955298883e-09, -0.0005515125516407263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922283902802277, 0.23553740499180734, 0.8415182253375447, 0.0, -0.12356741262006192, -0.244098656648433, -2.6081194585706613, -0.7122667452605677, -0.5581364278203959, -1.1991627663390112, -2.876938417438849, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295475700577736, 0.9588204602625764, 0.8015834397600468, -1.2107984291261271, -2.2794706522647883, -0.2994086858988451, 1.8647869579812928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960827229942, -0.4403409242374828, 0.02349046859225637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8694804402221444e-06, 0.0005381159031892923, 6.606758408896761e-05, 0.0, 0.000668048509288048, 0.00035080699117424197, 8.105121039951375e-05, 0.0008441064376684413, -3.3435265540814266e-05, -0.0004296923678604655, -0.000287658607876933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01731726620848244, 0.015397409519414065, -0.04967365568268607, -0.003651174814689638, -0.027251216980177163, 0.01869854709098071, 0.059192647776113216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.821306158070047e-09, -1.6455303699486633e-09, -0.0005708382293685547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092229362213521, 0.23556419214109076, 0.8415193673058253, 0.0, -0.12353391477712479, -0.24408145874473222, -2.608115372253596, -0.7122244048578634, -0.5581381237752528, -1.1991843319310758, -2.8769528395699946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42872445430342665, 0.9595510565704616, 0.7992223359452336, -1.2109731199137916, -2.280777720365814, -0.2985065236544123, 1.8676104953770492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196082231266, -0.4403409243088011, 0.02346183822581013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9438665863407815e-06, 0.0005357429856686259, 2.283936561278392e-05, 0.0, 0.0006699568587426542, 0.0003439580740157031, 8.17263413041995e-05, 0.000846808054083768, -3.39190971396814e-05, -0.0004313118412897082, -0.000288442622914387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01646231508693933, 0.01461192615770454, -0.04722207629626339, -0.003493815753291094, -0.026141362020514175, 0.018043244888655965, 0.056470747915129293, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.83456558593435e-09, -1.426367202242299e-09, -0.000572607328924798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922303880110799, 0.23559038168015178, 0.8415199852882396, 0.0, -0.1235009259124147, -0.24406483268837104, -2.6081113018315367, -0.7121826869037292, -0.5581398408669545, -1.1992055894462346, -2.876967032815702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42791895589001544, 0.9602641198930109, 0.7969141609822934, -1.2111440345584141, -2.2820628385253374, -0.2976091306509349, 1.8703766996585587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960817519064, -0.4403409243703063, 0.02343363234899367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0515951175859435e-06, 0.0005237907812203649, 1.2359648284266457e-05, 0.0, 0.0006597772942017476, 0.000332521127223907, 8.140844119091067e-05, 0.0008343590826838142, -3.4341834033013567e-05, -0.0004251503031771353, -0.00028386491415034406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016109968268223928, 0.014261266450985874, -0.04616349925880549, -0.0034182928924479396, -0.02570236319046215, 0.017947860069547936, 0.055324085630191866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.587193975638144e-09, -1.2301036995276342e-09, -0.00056411753632922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922314643975465, 0.23561584225978577, 0.8415206281416071, 0.0, -0.12346865914893124, -0.24404875443383964, -2.6081072718949243, -0.7121418622418272, -0.5581415717556476, -1.1992263960601717, -2.8769809036549896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4271176920472807, 0.9609710640627841, 0.7946219475397546, -1.2113134147462656, -2.2833449298152786, -0.29670604552711033, 1.8731283167796038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960812893364, -0.44034092442329237, 0.023406033978459983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152772933227082e-06, 0.0005092115926796831, 1.2857067350550212e-05, 0.0, 0.0006453352696690721, 0.0003215650906277757, 8.059873225149452e-05, 0.0008164932380410139, -3.461777386295665e-05, -0.00041613227874423325, -0.0002774167857476666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016025276854695188, 0.014138883395464165, -0.045844268850776165, -0.0033876037570306798, -0.025641825798819465, 0.018061702476492185, 0.05503234242090225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.251399377513169e-09, -1.0597212265636223e-09, -0.0005519674106737503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092232580107623, 0.23564067171667163, 0.8415212349419124, 0.0, -0.1234370605731956, -0.24403306406223987, -2.608103288474411, -0.7121018685308353, -0.5581433072688579, -1.1992467787880954, -2.87699447765998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42631633281947695, 0.9616754935931877, 0.792333738387956, -1.2114820654238903, -2.2846310717664897, -0.29579816557776584, 1.8758799956162546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960808423015, -0.4403409244688435, 0.023379000395382613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2314201529564266e-06, 0.0004965891377175496, 1.2136006107188386e-05, 0.0, 0.0006319715147126685, 0.0003138074319952333, 7.966841026668133e-05, 0.000799874219836588, -3.4710264206142476e-05, -0.0004076545584751738, -0.0002714800998085875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016027184556074832, 0.014088590608071366, -0.045764183035973204, -0.003373013552493929, -0.025722839024224495, 0.01815759898688995, 0.055033576733016905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.940694945966608e-09, -9.110227440188435e-10, -0.000540671661547411]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209223372539627, 0.23566506806782841, 0.8415217812975562, 0.0, -0.12340594956291107, -0.24401758090343914, -2.6080993451677648, -0.7120624836986472, -0.5581450407705657, -1.1992668474692554, -2.8770078362267806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42551557505713944, 0.9623767297213253, 0.7900514091170274, -1.2116499838904833, -2.2859214864877115, -0.29489107317242, 1.8786305914415817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960804069877, -0.44034092450770895, 0.023352380809571575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2905772941065556e-06, 0.00048792702313550185, 1.0927112874049084e-05, 0.0, 0.0006222202056907677, 0.00030966317601457835, 7.88661329248291e-05, 0.0007876966437629345, -3.4670034157743676e-05, -0.0004013736231996911, -0.00026717133601586484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01601515524674981, 0.014024722562751344, -0.045646585418570494, -0.003358369331861143, -0.0258082944244407, 0.018141848106916394, 0.055011916506542455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.706274311049773e-09, -7.773093037112224e-10, -0.0005323917162207316]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922348953618178, 0.23568922979927492, 0.8415222566785925, 0.0, -0.123375129465284, -0.24400216448610904, -2.608095430822606, -0.712023463875547, -0.5581467688719711, -1.1992867246130448, -2.8770210672879366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42471767050002407, 0.9630727822489621, 0.7877811163116816, -1.2118169029211905, -2.28721408021122, -0.29399025899148507, 1.8813739028142424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960799793762, -0.4403409245403216, 0.023326009828649293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3399310956571104e-06, 0.00048323462893022737, 9.507620725404603e-06, 0.0, 0.0006164019525410937, 0.00030832834660205323, 7.828690317029863e-05, 0.000780396462003816, -3.456202810875578e-05, -0.0003975428757877269, -0.00026462122312433816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015958091142307503, 0.013921050552737518, -0.045405856106917414, -0.003338380614145172, -0.02585187447017159, 0.018016283618698822, 0.05486622745321367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.552228758823872e-09, -6.522531359252474e-10, -0.000527419618445673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092236089442465, 0.2357133007651516, 0.8415226672037902, 0.0, -0.12334445117290906, -0.24398673651659994, -2.6080915348528966, -0.7119846230807773, -0.5581484910085028, -1.199306504474441, -2.877034237148521, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42392436326708854, 0.9637620898156535, 0.785527656721029, -1.2119826123190947, -2.2885072294691815, -0.29309891318302905, 1.8841050985136476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196079556518, -0.4403409245668912, 0.023299761418517764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.388161294365743e-06, 0.0004814193175336523, 8.210503954310316e-06, 0.0, 0.0006135658474991242, 0.00030855939018207835, 7.791939418756594e-05, 0.0007768158953953921, -3.4442730633713985e-05, -0.0003955972279284372, -0.00026339721168615413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015866144658710776, 0.013786151333827379, -0.045069191813052134, -0.003314187958082865, -0.02586298515922863, 0.01782691616911975, 0.054623913988103075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.457162595218221e-09, -5.313923472491648e-10, -0.0005249682026306076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922373096431715, 0.2357373554602591, 0.8415230305637231, 0.0, -0.12331383313096314, -0.24397127446279795, -2.6080876499174175, -0.71194585879409, -0.5581502083641651, -1.1993262395279525, -2.8770473817984348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4231361474736072, 0.9644441377747965, 0.7832924464386829, -1.2121470755077381, -2.2898008375515504, -0.292217667083622, 1.8868230698752826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960791368715, -0.44034092458751367, 0.023273566174345575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4404014132461273e-06, 0.00048109390215006183, 7.267198659375373e-06, 0.0, 0.0006123608389183291, 0.00030924107603955115, 7.769870958462718e-05, 0.0007752857337444723, -3.4347113243743554e-05, -0.00039470107022578484, -0.0002628929982758232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015764315869626497, 0.013640959182861963, -0.04470420564692132, -0.003289263772868496, -0.025872161647381108, 0.017624921988140904, 0.05435942723269867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.392931709869209e-09, -4.124487802740948e-10, -0.0005239048834437878]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092238558825656, 0.23576141053205174, 0.8415233686300534, 0.0, -0.12328325243654976, -0.2439557920151657, -2.6080837724010726, -0.7119071414159466, -0.5581519227870049, -1.199345945387338, -2.8770605110628282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4223523698543891, 0.9651193702015691, 0.7810737984948897, -1.2123104169868437, -2.2910962516623736, -0.29134533396449097, 1.8895301632215622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960787200638, -0.4403409246022554, 0.023247404124884127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4983649688536877e-06, 0.0004811014358528989, 6.761326606055589e-06, 0.0, 0.0006116138882675735, 0.00030964895264502747, 7.755032689620944e-05, 0.0007743475628682688, -3.4288456795332206e-05, -0.00039411718771227295, -0.0002625852878715163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015675552384362555, 0.013504648535452373, -0.04437295887586491, -0.0032668295821129466, -0.02590828221646176, 0.017446662382620555, 0.054141866925591864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.336152004959027e-09, -2.9483383204032195e-10, -0.0005232409892289644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922398394839423, 0.23578544723407127, 0.8415237008592102, 0.0, -0.12325272323726047, -0.2439403182548261, -2.608079901591061, -0.7118684876951991, -0.5581536360211438, -1.1993656140432984, -2.8770736183330112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42157170330215116, 0.9657887980086253, 0.7788682009049951, -1.2124728538313292, -2.292395659042311, -0.2904799007452496, 1.8922307511121659, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960783064311, -0.44034092461119667, 0.023221286690121322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5613165727152883e-06, 0.00048073404039043435, 6.644583136598058e-06, 0.0, 0.0006105839857859857, 0.0003094752067921484, 7.741620023622234e-05, 0.0007730744149506638, -3.426468277858962e-05, -0.00039337311920644867, -0.00026214540366160043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01561333104475981, 0.013388556141123548, -0.04411195179789197, -0.003248736889710461, -0.025988147598741438, 0.01730866438482799, 0.054011757812075435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.272654326006525e-09, -1.788258857433844e-10, -0.0005223486952560803]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092241153103414, 0.23580943343363525, 0.8415240404833962, 0.0, -0.1232222746465587, -0.24392488207649005, -2.608076038413205, -0.7118299333489168, -0.5581553493164322, -1.1993852276726218, -2.8770866904437438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42079265955417344, 0.9664535785191612, 0.7766716961082093, -1.212634621195772, -2.293701407394966, -0.2896193457177761, 1.8949296662867212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960778965756, -0.440340924614439, 0.02319523811198458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.627238943820995e-06, 0.000479723991279697, 6.792483720689729e-06, 0.0, 0.0006089718140354803, 0.0003087235667211426, 7.726355711621118e-05, 0.000771086925645637, -3.426590576893101e-05, -0.00039227258646606824, -0.0002614422146470036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015580874959554462, 0.013295610210719745, -0.04393009593571532, -0.003235347288853942, -0.02611496705310561, 0.017211100549470552, 0.05397830349110793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.197111136692185e-09, -6.484728093278991e-11, -0.0005209715627347895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092242500054431, 0.23583333917995253, 0.8415243937262556, 0.0, -0.12319193475318685, -0.24390950385004634, -2.6080721843085497, -0.7117915131284361, -0.5581570633418861, -1.1994047687729104, -2.8770997147905937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4200139636292416, 0.9671147104640737, 0.7744808856812928, -1.2127959181453245, -2.295015497776658, -0.28876212112143645, 1.8976310505495397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960774910598, -0.4403409246120918, 0.02316928194668761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6939020335182154e-06, 0.00047811492634575376, 7.064857187734985e-06, 0.0, 0.0006067978674369437, 0.00030756452887392905, 7.70820931088602e-05, 0.0007684044096126242, -3.428050907739793e-05, -0.0003908220057691243, -0.0002604869369985441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015573918498637348, 0.013222638898248726, -0.043816208538330355, -0.00322593899105221, -0.026281807633830957, 0.017144491926792838, 0.05402768525636815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.110315293499276e-09, 4.6944804177953823e-11, -0.0005191233059394407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922438798573534, 0.2358571444272394, 0.8415247611308359, 0.0, -0.12316172246009313, -0.24389419335789833, -2.608068340507095, -0.7117532505645536, -0.558158778287458, -1.199424225430224, -2.8771126829367297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41923473532055916, 0.9677728866796532, 0.7722934161990574, -1.212956881883158, -2.2963393354168686, -0.2879073096273501, 1.9003377944197228, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960770902595, -0.4403409246042542, 0.023143434124516634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7596058447164707e-06, 0.000476104945737298, 7.348091605041611e-06, 0.0, 0.0006042458618744598, 0.00030620984296020646, 7.687602909510037e-05, 0.0007652512776494267, -3.429891143800084e-05, -0.0003891331462746232, -0.00025936292271699256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0155845661736487, 0.013163524311589642, -0.04374938964470688, -0.0032192747566692206, -0.02647675280421163, 0.017096229881726443, 0.054134877403664294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.01600633038393e-09, 1.5675137198967494e-10, -0.0005169564434195082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922452916000858, 0.2358808403621116, 0.8415251397821107, 0.0, -0.12313164583970654, -0.24387895172115687, -2.6080645077163536, -0.711715155813482, -0.5581604940444943, -1.1994435924773454, -2.87712559131105, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41845450336903484, 0.9684284818251855, 0.7701080173027351, -1.2131175865810657, -2.2976737120383386, -0.2870545511453888, 1.9030514941192362, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196076694342, -0.4403409245910031, 0.02311770150108781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8234854651376114e-06, 0.0004739186974440934, 7.573025496729262e-06, 0.0, 0.0006015324077317446, 0.00030483273482931615, 7.66558148236624e-05, 0.0007618950214334908, -3.4315140727767546e-05, -0.0003873409424277983, -0.0002581674864028675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015604639030486773, 0.01311190291064501, -0.043707977926445755, -0.0032140939581541406, -0.026687532429398322, 0.01705516963922575, 0.054273993990267506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.918348766056197e-09, 2.650229335057428e-10, -0.000514652468576475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922467343183218, 0.2359044269142091, 0.8415255254644389, 0.0, -0.12310170444313419, -0.24386377493927877, -2.608060686115852, -0.7116772284471309, -0.5581622103830651, -1.1994628701224501, -2.8771384401500866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4176731159377752, 0.9690816227511331, 0.7679242635833511, -1.2132780573832522, -2.299018936029712, -0.28620385908414797, 1.9057727319204802, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960763033183, -0.440340924572389, 0.023092083757146897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8854364718654023e-06, 0.0004717310419500043, 7.713646564592234e-06, 0.0, 0.0005988279314469956, 0.00030353563756180154, 7.643201002834777e-05, 0.0007585473270231177, -3.4326771416632615e-05, -0.00038555290209570716, -0.00025697678073433646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015627748625193033, 0.013062818518951868, -0.043675074387681916, -0.003209416043731131, -0.02690447982746789, 0.017013841224816428, 0.05442475602487812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.820471259658485e-09, 3.7228274721579084e-10, -0.0005123548788182946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922482072344842, 0.2359279089154134, 0.841525914222004, 0.0, -0.1230718930598605, -0.24384865728966337, -2.608056875514007, -0.7116394620836728, -0.55816392708018, -1.1994820616189485, -2.8771512318041363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4168906142633456, 0.9697322875982185, 0.7657422392854535, -1.2134382896662679, -2.3003750177240807, -0.28535542471059344, 1.90850147292552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960759171188, -0.4403409245484401, 0.023066576541881698]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9458323249921477e-06, 0.00046964002408588835, 7.775151300331361e-06, 0.0, 0.000596227665474031, 0.00030235299230778275, 7.621203690126238e-05, 0.0007553272691621398, -3.433394229827986e-05, -0.0003838299299675208, -0.0002558330809954987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015650033488590995, 0.01301329694170914, -0.043640485957952946, -0.003204645660315158, -0.027121633887366898, 0.016968687471091107, 0.05457482010079753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.723991917998616e-09, 4.789779770359519e-10, -0.0005101443053039941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922487188422875, 0.2359512926173417, 0.8414798981621372, 0.0, -0.12304217007769358, -0.2438328025892432, -2.608053233455713, -0.7116018612972712, -0.5581654649798811, -1.1995011740929382, -2.87716403092832, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41622679897001835, 0.9702865401809379, 0.763883358433907, -1.2135778829397672, -2.3015461478541615, -0.284671909354924, 1.9108411860728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075585609, -0.44034092452713464, 0.023041174375794907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0232156067228836e-06, 0.0004676740385663791, -0.0009203211973347449, 0.0, 0.0005944596433383856, 0.0003170940084034714, 7.284116588084856e-05, 0.0007520157280314512, -3.0757994020575036e-05, -0.0003822494797954897, -0.000255982483672668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013276305866545001, 0.011085051654385976, -0.03717761703092988, -0.002791865469985349, -0.023422602601618707, 0.013670307113389343, 0.04679426294614361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.630193781554256e-09, 4.2610865232925507e-10, -0.0005080433217358516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092248984882419, 0.235974268389336, 0.8414506529541362, 0.0, -0.1230129407403171, -0.24381756337189522, -2.6080496259565082, -0.7115648801886544, -0.5581669870332563, -1.199520018068767, -2.87717661581652, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4157054495725053, 0.970726134875539, 0.7624113404522476, -1.2136924119698704, -2.302488665425653, -0.28416729112142136, 1.9127088918606323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960753270093, -0.44034092451105267, 0.02301618802811448]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.320802629738785e-07, 0.00045951543988579204, -0.0005849041600194818, 0.0, 0.0005845867475296946, 0.00030478434695945265, 7.214998409164552e-05, 0.0007396221723374655, -3.044106750547131e-05, -0.00037687951657553657, -0.00025169776400109383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010426987950260405, 0.00879189389202301, -0.02944035963318739, -0.00229058060206577, -0.018850351429836387, 0.010092364670052284, 0.03735411575610158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.171997670780403e-09, 3.216397380081335e-10, -0.0004997269536085335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922491494170983, 0.23599624983988501, 0.8414483496448353, 0.0, -0.122984921306867, -0.24380364302824198, -2.608046030740962, -0.7115293881312232, -0.5581685710940243, -1.1995381647932162, -2.8771886485782794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4153133445449481, 0.9710617032434499, 0.7612911261863405, -1.2137835548633018, -2.303218483848184, -0.2838093796255577, 1.9141429507514227, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751444154, -0.4403409245013862, 0.022992208098654425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2906935816892777e-07, 0.00043962901098051926, -4.606618601843708e-05, 0.0, 0.0005603886690020853, 0.0002784068730651544, 7.19043109229564e-05, 0.0007098411486224862, -3.1681215360431484e-05, -0.0003629344889806832, -0.00024065523518950488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007842100551144033, 0.006711367358216193, -0.022404285318141592, -0.0018228578686265181, -0.014596368450615259, 0.007158229917273065, 0.02868117781580587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.651877703104973e-09, 1.933301689856042e-10, -0.00047959858920105706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492437373727, 0.23601658623147476, 0.8414590466242347, 0.0, -0.12295889779171289, -0.2437913255747105, -2.608042497371656, -0.7114963632547027, -0.5581702289630247, -1.1995551136100802, -2.8771997770817075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41502627397516445, 0.9713122651738108, 0.760458530364623, -1.2138548491255416, -2.303770441791338, -0.2835593787138501, 1.9152187220931172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119607504069, -0.44034092450048995, 0.02296989711802654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8864054873582224e-07, 0.000406727831794947, 0.0002139395879865806, 0.0, 0.0005204703030823638, 0.00024634907062953237, 7.066738611790935e-05, 0.0006604975304108868, -3.315738000833834e-05, -0.0003389763372812621, -0.0002225700685628714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005741411395673626, 0.005011238607218407, -0.016651916434352116, -0.0014258852447985985, -0.011039158863079185, 0.005000018234151651, 0.02151542683389112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0745040033420788e-09, 1.7924738970382162e-11, -0.00044621961255772425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492933419876, 0.23603475577432742, 0.8414750227616592, 0.0, -0.1229355231945582, -0.2437809814534243, -2.6080390312703785, -0.7114666078848317, -0.5581720073977583, -1.1995704589743537, -2.877209698784248, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4148198000911033, 0.9714968972861152, 0.7598487496944001, -1.2139100078181488, -2.304181407589278, -0.2833847366983969, 1.9160138213012863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960750336107, -0.4403409245145704, 0.02294979900678752]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.920922989975184e-08, 0.00036339085705321047, 0.00031952274849119864, 0.0, 0.00046749194309373803, 0.0002068824257242287, 6.932202555167622e-05, 0.000595107397419589, -3.5568694672535596e-05, -0.00030690728546846455, -0.00019843405081240186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004129477681223238, 0.0036926422460890037, -0.012195613404458027, -0.0011031738521428088, -0.008219315958802705, 0.003492840309064276, 0.015901984163380244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4158986410701592e-10, -2.8160915053321025e-10, -0.0004019622247804496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493099129635, 0.23605046525805473, 0.8414448279092318, 0.0, -0.12291510482198442, -0.2437709778967978, -2.608035990795053, -0.7114406115277784, -0.5581735692497372, -1.1995838798835885, -2.877218364229198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4146730376185007, 0.9716318981989475, 0.7594062208513683, -1.2139523496896159, -2.304484103164397, -0.28326203612539763, 1.916595816208237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751141298, -0.44034092454431645, 0.022932238233061203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.314195200306826e-08, 0.00031418967454627315, -0.0006038970485487139, 0.0, 0.0004083674514753187, 0.0002000711325302667, 6.0809506508185485e-05, 0.0005199271410681618, -3.123703957631058e-05, -0.000268418184694739, -0.0001733088989992726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002935249452052032, 0.0027000182566449277, -0.008850576860634755, -0.0008468374293380021, -0.006053911502375485, 0.0024540114599855816, 0.011639898139017498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6103848084768415e-09, -5.949203318875397e-10, -0.0003512154745262834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493104040848, 0.23606365717311636, 0.8413724547795586, 0.0, -0.12289772275178933, -0.2437611459551833, -2.6080335107422443, -0.711418514534015, -0.5581747862028298, -1.199595274141099, -2.8772257708797935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41456955499475034, 0.9717301605493174, 0.7590869279578832, -1.213984645147714, -2.3047052786869795, -0.2831748818362176, 1.9170190087748016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075219521, -0.4403409245856499, 0.022917307953974907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0" }, - "execution_count": 13, + "execution_count": 8, "metadata": {}, "output_type": "execute_result" } ], "source": [ - "# reset_giskard()\n", + "reset_giskard()\n", "\n", "js = {\n", " # 'torso_lift_joint': 0.2999225173357618,\n", diff --git a/scripts/iai_robots/pr2/pr2_standalone.py b/scripts/iai_robots/pr2/pr2_standalone.py index 5e64f04e5a..09f283557a 100755 --- a/scripts/iai_robots/pr2/pr2_standalone.py +++ b/scripts/iai_robots/pr2/pr2_standalone.py @@ -34,6 +34,6 @@ drive_joint_name, ] ), - behavior_tree_config=StandAloneBTConfig(publish_tf=True, publish_js=True), + behavior_tree_config=StandAloneBTConfig(publish_tf=True, publish_js=True, debug_mode=True), qp_controller_config=QPControllerConfig()) giskard.live() diff --git a/src/giskardpy/goals/feature_functions.py b/src/giskardpy/goals/feature_functions.py index db24719ba6..978d063f6b 100644 --- a/src/giskardpy/goals/feature_functions.py +++ b/src/giskardpy/goals/feature_functions.py @@ -11,6 +11,7 @@ from giskardpy.goals.align_planes import AlignPlanes from typing import Optional, List, Dict, Union +from std_msgs.msg import ColorRGBA class FeatureFunctionGoal(Goal): @@ -33,13 +34,25 @@ def __init__(self, root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) if type(robot_feature) == PointStamped: self.root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) + god_map.debug_expression_manager.add_debug_expression('root_P_robot_feature', + self.root_P_robot_feature, + color=ColorRGBA(r=1, g=0, b=0, a=1)) elif type(robot_feature) == Vector3Stamped: self.root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) + god_map.debug_expression_manager.add_debug_expression('root_V_robot_feature', + self.root_V_robot_feature, + color=ColorRGBA(r=1, g=0, b=0, a=1)) if type(world_feature) == PointStamped: self.root_P_world_feature = cas.Point3(root_world_feature) + god_map.debug_expression_manager.add_debug_expression('root_P_world_feature', + self.root_P_world_feature, + color=ColorRGBA(r=0, g=1, b=0, a=1)) if type(world_feature) == Vector3Stamped: self.root_V_world_feature = cas.Vector3(root_world_feature) + god_map.debug_expression_manager.add_debug_expression('root_V_world_feature', + self.root_V_world_feature, + color=ColorRGBA(r=0, g=1, b=0, a=1)) class PerpendicularFeatureFunction(FeatureFunctionGoal): From ef2cd1b87e23e110ae12b020c39bbb79aeb45687 Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 8 Aug 2024 09:58:54 +0200 Subject: [PATCH 15/43] feature function examples --- scripts/giskard_examples.ipynb | 209 +++++++++++++++++++++++++++++---- 1 file changed, 188 insertions(+), 21 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index b206244eee..ec5ed81560 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -79,6 +79,7 @@ "execution_count": 3, "outputs": [], "source": [ + "# Launch the giskardpy PR2 standalone launch file before this\n", "gs = GiskardWrapper()" ], "metadata": { @@ -90,11 +91,12 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 8, "outputs": [], "source": [ "def reset_giskard():\n", " gs.clear_motion_goals_and_monitors()\n", + " gs.world.clear()\n", " default_pose = {\n", " 'r_elbow_flex_joint': -0.15,\n", " 'r_forearm_roll_joint': 0,\n", @@ -378,22 +380,103 @@ } }, { - "cell_type": "code", - "execution_count": null, - "outputs": [], - "source": [], + "cell_type": "markdown", + "source": [ + "Now for positioning the gripper to grasp a cylindrical object one can use three different feature function constraints\n", + "\n", + "1. Pointing the gripper towards the object center\n", + "2. keeping a suitable distance\n", + "3. constrain the height to be within the dimensions of the objects" + ], "metadata": { "collapsed": false, "pycharm": { - "name": "#%%\n" + "name": "#%% md\n" } } }, { "cell_type": "code", - "execution_count": null, - "outputs": [], - "source": [], + "execution_count": 25, + "outputs": [ + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995221653958, 0.0, 0.0, 0.0, -0.0015703775115318255, 0.003282713647665629, 0.003026158987476063, -0.15000000006019606, 0.0015374000077203185, -0.10001000003167682, 6.429855888227713e-20, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006247115511932974, 0.0004616962537508633, 0.000624999852377246]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044330791465, 0.0, 0.0, 0.0, -0.03140755023063651, 0.06565427295331257, 0.060523179749521254, -1.2039214455783773e-09, 0.030748000154406364, -6.335363548201422e-10, 1.2859711776455427e-18, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012494231023865947, 0.009233925075017265, 0.012499997047544918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990445676024, 0.0, 0.0, 0.0, -0.006755901413791964, 0.008753017198904492, 0.0053284771598860105, -0.15000000006915654, 0.0008622001356011302, -0.10001000003714006, -0.0037499999010584422, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024958366420357193, 0.002013990282373121, 0.0024999995417754797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044804412895, 0.0, 0.0, 0.0, -0.10371047804520278, 0.10940607102477724, 0.046046363448198964, -1.792091831848076e-10, -0.013503997442383762, -1.0926480652581477e-10, -0.07499999802116884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742250181684844, 0.031045880572445155, 0.037499993787964675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985669148155, 0.0, 0.0, 0.0, -0.014744384398796447, 0.015279346312955468, 0.003156957255756268, -0.15000000009040484, -0.005775599367293093, -0.10001000004944276, -0.014999999238081001, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0059176141607758855, 0.004697522503904497, 0.005880900225464659]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044694426184, 0.0, 0.0, 0.0, -0.1597696597000896, 0.13052658228101952, -0.04343039808259485, -4.249661995310357e-10, -0.13275599005788444, -2.4605399786351803e-10, -0.22499998674045113, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06843555037480333, 0.05367064443062752, 0.06761801367378358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980893382729, 0.0, 0.0, 0.0, -0.021787446482147494, 0.0222326984114459, 0.0002615992679069145, -0.15000000009451547, -0.014625998505889616, -0.10001000005168982, -0.02999999801357465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010597863524518143, 0.007900249813603396, 0.010350386544235202]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044846914836, 0.0, 0.0, 0.0, -0.14086124166702096, 0.13906704196980868, -0.05790715975698706, -8.221259503883282e-11, -0.17700798277193047, -4.4941409038965875e-11, -0.2999999755098729, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09360498727484513, 0.06405454619397798, 0.08938972637541083]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976117780566, 0.0, 0.0, 0.0, -0.026653873851331944, 0.028696017227165915, 0.0003924031961315786, -0.15000000009462847, -0.02193899728036525, -0.10001000005175661, -0.04499999622762701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016222696771134453, 0.011007162548498569, 0.015410517283923585]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879567476, 0.0, 0.0, 0.0, -0.09732854738368898, 0.12926637631440027, 0.0026160785644932863, -2.2599334557434373e-12, -0.1462599754895127, -1.3358845254008728e-12, -0.2999999642810472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11249666493232618, 0.06213825469790344, 0.10120261479376766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134210975, 0.0, 0.0, 0.0, -0.029264665764574014, 0.03347298766345755, 0.0072993688221773285, -0.1500000000964399, -0.023964595754733677, -0.10001000005277047, -0.056249993903809026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022548176101336193, 0.013398881926501795, 0.020646939792804873]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044865836936, 0.0, 0.0, 0.0, -0.052215838264841385, 0.09553940872583261, 0.13813931252091496, -3.622864186616696e-11, -0.04051196948736856, -2.0277166286824266e-11, -0.22499995352364038, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12650958660403477, 0.047834387560064515, 0.1047284501776258]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966565872612, 0.0, 0.0, 0.0, -0.030698916801691834, 0.036781136745916945, 0.0191412684915748, -0.15000000011194803, -0.01738277245628061, -0.10001000006168011, -0.0599999928637143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.02940939096061492, 0.01445075572565422, 0.02553196890319519]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044752572424, 0.0, 0.0, 0.0, -0.028685020742356383, 0.0661629816491879, 0.23683799338794945, -3.101625735212342e-10, 0.1316364659690613, -1.7819285107010279e-10, -0.07499997919810561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1372242971855746, 0.021037475983048483, 0.09770058220780634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961790214503, 0.0, 0.0, 0.0, -0.03094022359446766, 0.039194295230485565, 0.03590932499636888, -0.1500000001134369, -0.004486299228333535, -0.10001000006254271, -0.05407310148517385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.036653412085490035, 0.013984549081381468, 0.029893874579441853]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904486837801, 0.0, 0.0, 0.0, -0.0048261358555164655, 0.04826316969137234, 0.33536113009588164, -2.977719576380854e-11, 0.2579294645589415, -1.725194792822288e-11, 0.1185378275708091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1448804224975023, -0.009324132885455031, 0.08723811352493321]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2058495701460289, 0.0, 0.0, 0.0, -0.028541966195731946, 0.04158424263777133, 0.06113270540868164, -0.15000000011375714, 0.017510761783818562, -0.10001000006274377, -0.037884025366766536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04406346987877525, 0.011792833881908733, 0.033882894093707844]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044877677186, 0.0, 0.0, 0.0, 0.04796514797471423, 0.0477989481457153, 0.5044676082462551, -6.4047724819789275e-12, 0.43994122024304194, -4.0213470212477625e-12, 0.3237815223681462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1482011558657042, -0.04383430398945469, 0.07978039028531984]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952236442112, 0.0, 0.0, 0.0, -0.024683106303693775, 0.04769021367659524, 0.09106140973439328, -0.15000000017227058, 0.044858410586010464, -0.10001000009829364, -0.015182764502755287, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05137298421918549, 0.008487441509706446, 0.037407950184213605]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044367844746, 0.0, 0.0, 0.0, 0.07717719784076345, 0.1221194207764782, 0.5985740865142327, -1.1702688663704997e-09, 0.5469529760438381, -7.109972417165659e-10, 0.45402521728022494, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14619028680820487, -0.06610784744404573, 0.07050112181011528]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20714947460838093, 0.0, 0.0, 0.0, -0.020858999806023345, 0.058046323998970736, 0.12194543797350729, -0.15000000017241016, 0.0738066471782457, -0.10001000009837022, 0.010280681106863438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05860462720353032, 0.004690215098383745, 0.040429687397281956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879196259, 0.0, 0.0, 0.0, 0.07648212995340858, 0.20712220644750995, 0.6176805647822803, -2.7919081062526814e-12, 0.5789647318447045, -1.5315994487427349e-12, 0.5092689121923745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14463285968689646, -0.075944528226454, 0.06043474426136707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2077994268501965, 0.0, 0.0, 0.0, -0.018134570423865817, 0.06890263434192896, 0.15003479012617332, -0.1500000001771229, 0.10060547156067459, -0.10001000010102225, 0.034756311462241465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06602790501256466, 0.0010348003189873606, 0.04303379603046195]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836311804, 0.0, 0.0, 0.0, 0.05448858764315058, 0.21712620685916442, 0.5617870430533203, -9.425452062625182e-11, 0.5359764876485777, -5.3040759378980744e-11, 0.48951260710756056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14846555618068683, -0.07310829558792768, 0.05208217266359997]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2084493790941273, 0.0, 0.0, 0.0, -0.01708525644819017, 0.07650914482900094, 0.17157946619240233, -0.15000000017736673, 0.12150488373330834, -0.10001000010116455, 0.05449412656339041, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07379363222107337, -0.0018474606745197764, 0.045349749037888284]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044878616297, 0.0, 0.0, 0.0, 0.020986279513512916, 0.15213020974143948, 0.43089352132458014, -4.876468442942762e-12, 0.41798824345267493, -2.846019531188478e-12, 0.39475630202297884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1553145441701743, -0.05764521987014274, 0.04631906014852671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20909933133720682, 0.0, 0.0, 0.0, -0.017613126548445397, 0.07711585595114098, 0.18282946622975466, -0.15000000017936918, 0.1327548837193033, -0.10001000010244541, 0.06574412642482488, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08182018860532334, -0.0036750923213572824, 0.04748974351651834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861590418, 0.0, 0.0, 0.0, -0.010557402005104521, 0.012134222442800796, 0.22500000074704662, -4.004909909979424e-11, 0.22499999971989926, -2.5617215822644437e-11, 0.22499999722868932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16053112768499928, -0.03655263293675012, 0.04279988957260117]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2097492835792608, 0.0, 0.0, 0.0, -0.017961433437616258, 0.07212268498125661, 0.18753479016897634, -0.1500000001836914, 0.13453306909224536, -0.1000100001049987, 0.06475631116544972, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08998196153562694, -0.005079155093326413, 0.0495838125379807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044841079355, 0.0, 0.0, 0.0, -0.006966137783417199, -0.09986341939768756, 0.09410647878443348, -8.64440654052035e-11, 0.035563707458841326, -5.106580412440603e-11, -0.01975630518750332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1632354586060722, -0.028081255439382613, 0.04188138042924712]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.210399235696626, 0.0, 0.0, 0.0, -0.017336349354425813, 0.06441202604501901, 0.18944541359829328, -0.15000000049395185, 0.13058937748796107, -0.10001000029062612, 0.05268368273895247, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09821210177343816, -0.006688109789839386, 0.051699948567954804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042347304122, 0.0, 0.0, 0.0, 0.012501681663808877, -0.1542131787247519, 0.038212468586338824, -6.205209233944879e-09, -0.07887383208568581, -3.712548254105807e-09, -0.24145256852994498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16460280475622413, -0.032179093930259466, 0.04232272059948208]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2110491878167223, 0.0, 0.0, 0.0, -0.01566087886119214, 0.056227627250662125, 0.1923113049568272, -0.15000000080487622, 0.1246728158709866, -0.10001000047442696, 0.03137363071510729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10650401637349055, -0.009077139244646036, 0.05383154925667112]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042401925898, 0.0, 0.0, 0.0, 0.033509409864673434, -0.16368797588713774, 0.05731782717067806, -6.2184874587217276e-09, -0.11833123233948932, -3.6760167492971274e-09, -0.42620104047690344, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16583829200104783, -0.047780589096132996, 0.042632013774326384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21169914003756007, 0.0, 0.0, 0.0, -0.013136203519607408, 0.04883700270829323, 0.19988246226128245, -0.1500000008623399, 0.11863606571430928, -0.10001000050854808, 0.0023652701545303356, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11483161231922363, -0.01199410907733664, 0.05595489857210957]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044416755284, 0.0, 0.0, 0.0, 0.050493506831694665, -0.14781249084737794, 0.15142314608910537, -1.1492734315868921e-09, -0.12073500313354632, -6.824224889017973e-10, -0.5801672112115391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16655191891466153, -0.058339396653812096, 0.04246698630876896]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21234909228126364, 0.0, 0.0, 0.0, -0.009996518414377473, 0.04273535156098593, 0.215908885222191, -0.15000000086310458, 0.1116744585608232, -0.10001000050901339, -0.03284141825077267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12316562136608956, -0.015097741704376453, 0.05805133257902995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874071369, 0.0, 0.0, 0.0, 0.0627937021045987, -0.12203302294614593, 0.3205284592181714, -1.5294059539376564e-11, -0.13923214306972154, -9.30620393572005e-12, -0.70413376810606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16668018093731854, -0.06207265254079625, 0.04192868013840767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21299904452415347, 0.0, 0.0, 0.0, -0.006331705371242254, 0.03790943535812955, 0.24037723313094952, -0.15000000086586115, 0.10284123930706682, -0.1000100005108645, -0.07300676894792131, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1314859257035349, -0.018250096413792175, 0.06011837155963506]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044857796615, 0.0, 0.0, 0.0, 0.0732962608627044, -0.09651832405712751, 0.4893669581751701, -5.513133716006377e-11, -0.17666438507512774, -3.7022213019124806e-11, -0.8033070139429728, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1664060867489066, -0.06304709418831446, 0.041340779612102134]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21364899674866902, 0.0, 0.0, 0.0, -0.0021310152188000727, 0.03408183068271783, 0.27183783923295674, -0.15000000091315058, 0.09170729336620415, -0.10001000054063608, -0.11713904823135295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13978718735426665, -0.02148522962944596, 0.062165479515142216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904449031127, 0.0, 0.0, 0.0, 0.08401380304884362, -0.07655209350823454, 0.629212122040144, -9.457883126845746e-10, -0.22267891881725335, -5.954313511165483e-10, -0.8826455856686328, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.166025233014635, -0.06470266431307567, 0.04094215911014314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21429894897224797, 0.0, 0.0, 0.0, 0.002618918882544759, 0.03089030739639266, 0.3090062986159122, -0.1500000009636665, 0.07829625545545993, -0.10001000057189699, -0.16444487045810013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14807644600964662, -0.024890531278901576, 0.06420539799268152]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044471579091, 0.0, 0.0, 0.0, 0.09499868202689664, -0.06383046572650333, 0.7433691876591096, -1.0103186766167955e-09, -0.26822075821488434, -6.252182749891895e-10, -0.9461164445349441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16578517310759916, -0.06810603298911234, 0.040798369550785904]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2149489011877622, 0.0, 0.0, 0.0, 0.007887573970318732, 0.027992024360826553, 0.35074106070063243, -0.15000000103470368, 0.06286146034625155, -0.10001000061682119, -0.21428952700062373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15636696266222688, -0.028532363098245243, 0.06624871376591593]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044310284567, 0.0, 0.0, 0.0, 0.10537310175547943, -0.05796566071132215, 0.8346952416944045, -1.4207435090862836e-09, -0.3086959021841675, -8.984841375973418e-10, -0.9968931308504718, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16581033305160503, -0.07283663638687331, 0.04086631546468815]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2155988533756801, 0.0, 0.0, 0.0, 0.013574763609478475, 0.02512004480954612, 0.39612886856468366, -0.1500000011856277, 0.04510614524715473, -0.10001000071089143, -0.26428952665842814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16467173590768128, -0.03240879334063301, 0.06830022544105084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904375835823, 0.0, 0.0, 0.0, 0.11374379278319485, -0.05743959102560865, 0.9077561572810242, -3.018480627462082e-09, -0.3551063019819364, -1.8814046766948426e-09, -0.9999999931560881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16609546490908805, -0.07752860484775541, 0.0410302335026982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624880558416132, 0.0, 0.0, 0.0, 0.0195701845637466, 0.022079443557865976, 0.4444391109026193, -0.15000000128027646, 0.024805426753651952, -0.10001000077052048, -0.3142895262251288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17300153362301599, -0.036489077275742986, 0.07036182699592802]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044169624125, 0.0, 0.0, 0.0, 0.11990841908536248, -0.06081202503360286, 0.9662048467587127, -1.8929750031210578e-09, -0.4060143698700555, -1.1925809209356786e-09, -0.9999999913340133, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16659595430669427, -0.08160567870219951, 0.041232031097543524]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21689875782517948, 0.0, 0.0, 0.0, 0.02507571543406815, 0.019019541055688288, 0.4919217887903812, -0.15000000129044885, 0.005709302944708245, -0.10001000077629935, -0.3642895262142361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18134667132315893, -0.0404091552544216, 0.0723994163209617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044820363286, 0.0, 0.0, 0.0, 0.11011061740643106, -0.06119805004355374, 0.9496535362364198, -2.034479045125849e-10, -0.38192247617887404, -1.155772169569584e-10, -0.999999999782146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16690275400285903, -0.07840155957357217, 0.040751786500673494]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2175487100676129, 0.0, 0.0, 0.0, 0.029566738237343133, 0.016123477460733445, 0.534826901663469, -0.15000000129650115, -0.008432226622555414, -0.10001000077904601, -0.41428952619337234, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18969425976746682, -0.04392129938137812, 0.07438936426831737]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044848668269, 0.0, 0.0, 0.0, 0.08982045606549964, -0.05792127189909688, 0.8581022257141909, -1.2104577163512962e-10, -0.28283059134527316, -5.493327682588649e-11, -0.9999999995827247, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16695176888615754, -0.07024288253913048, 0.03979895894711345]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2181986623086019, 0.0, 0.0, 0.0, 0.03289131700704225, 0.013537664629740438, 0.5694044494975414, -0.15000000130619115, -0.014308749232157287, -0.10001000078430726, -0.46428952615945046, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19803467517427262, -0.04696313308851339, 0.0763249347470274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044819780552, 0.0, 0.0, 0.0, 0.06649157539398237, -0.05171625661986015, 0.6915509151922709, -1.9380019955859497e-10, -0.11753045219203742, -1.0522491493786935e-10, -0.9999999993215625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.166808308136116, -0.06083667414270541, 0.038711409574200446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21884861451131554, 0.0, 0.0, 0.0, 0.035478194901017494, 0.011172048597397682, 0.5994044263852495, -0.15000000141970898, -0.015670159632519286, -0.10001000085700867, -0.5142895256940225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20637256451024763, -0.04973497725553512, 0.07822704641516812]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904405427277, 0.0, 0.0, 0.0, 0.0517375578795048, -0.04731232064685512, 0.5999995377541619, -2.2703566182933645e-09, -0.027228208007239976, -1.4540282671025796e-09, -0.9999999906914403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16675778671950026, -0.055436883340434694, 0.038042233362814364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21949856673946982, 0.0, 0.0, 0.0, 0.037339534981802334, 0.009169766677100004, 0.6219044056770292, -0.1500000014719545, -0.014911802957116527, -0.10001000088843456, -0.5642895255994165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21469855237726354, -0.052246544048200644, 0.08009496639630348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904456308541, 0.0, 0.0, 0.0, 0.03722680161569686, -0.04004563840595356, 0.4499995858355947, -1.0449104583004981e-09, 0.01516713350805518, -6.285177338949042e-10, -0.9999999981078781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1665197573403182, -0.05023133585331048, 0.03735839962270717]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22014851897708723, 0.0, 0.0, 0.0, 0.03825262879767167, 0.007883870238442581, 0.6331543954465214, -0.15000000149538356, -0.01578357000991264, -0.10001000090277094, -0.6142895255626146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22297815887216155, -0.05429578125684771, 0.08190853328103219]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044752348156, 0.0, 0.0, 0.0, 0.018261876317386665, -0.02571792877314846, 0.2249997953898433, -4.685810088265969e-10, -0.017435341055922274, -2.867274976067409e-10, -0.9999999992639639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16559212989796004, -0.040984744172941276, 0.03627133769457415]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22079847107427297, 0.0, 0.0, 0.0, 0.038514727136303564, 0.008636080503649817, 0.6369043948152749, -0.15000000196821664, -0.015892091832484988, -0.10001000117965608, -0.6642895246405037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2311068407568905, -0.055996229889218416, 0.08365449570296689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999041943715052, 0.0, 0.0, 0.0, 0.0052419667726378814, 0.015044205304144718, 0.07499998737507146, -9.456661534829018e-09, -0.0021704364514469766, -5.537702924611543e-09, -0.999999981557782, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16257363769457933, -0.03400897264741405, 0.03491924843869405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22144842330513115, 0.0, 0.0, 0.0, 0.03881945612304942, 0.011154258949750803, 0.6369044035262277, -0.15000000200899574, -0.011487368435089115, -0.10001000120312044, -0.7105395228438393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23911980973135064, -0.05777904746653064, 0.08537276922461005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044617163476, 0.0, 0.0, 0.0, 0.0060945797349171065, 0.05036356892201971, 1.7421905419701122e-07, -8.155819163594632e-10, 0.08809446794791743, -4.692872212561633e-10, -0.9249999640667111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16025937948920266, -0.035656351546244504, 0.03436547043286329]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2220983755470146, 0.0, 0.0, 0.0, 0.03927622762773583, 0.013444607113997054, 0.636904421572609, -0.1500000020153329, 0.0011806001796475871, -0.10001000120694956, -0.749289520174343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24716759046477715, -0.059679297099055464, 0.0871037268156016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044837668753, 0.0, 0.0, 0.0, 0.009135430093728254, 0.04580696328492501, 3.609276266573101e-07, -1.2674293177348148e-10, 0.25335937229473404, -7.658237105106777e-11, -0.7749999466100752, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16095561466853023, -0.03800499265049654, 0.034619151819831114]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22274832779102635, 0.0, 0.0, 0.0, 0.039943362177928536, 0.013315473606233964, 0.6387794305957436, -0.15000000201536612, 0.022987240691859832, -0.10001000120696761, -0.7767895166320455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25540526939811004, -0.06172598241231353, 0.08889130565217934]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880235554, 0.0, 0.0, 0.0, 0.013342691003854046, -0.0025826701552618056, 0.03750018046269218, -6.644023407942464e-13, 0.43613281024424483, -3.6104243104993683e-13, -0.5499999291540503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1647535786666575, -0.040933706265161275, 0.03575157673155471]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22339828003476725, 0.0, 0.0, 0.0, 0.04087015133636385, 0.010472197724812064, 0.6415919351014415, -0.15000000201621036, 0.052409441112288915, -0.10001000120744294, -0.7911568227119044, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2638417197223965, -0.06396724208081127, 0.09074714996818538]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487481819, 0.0, 0.0, 0.0, 0.01853578316870622, -0.05686551762843799, 0.056250090113957416, -1.6884572166468812e-11, 0.5884440084085816, -9.506442957743974e-12, -0.28734612159717715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16872900648572914, -0.04482519336995479, 0.037116886320120765]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22404823227875492, 0.0, 0.0, 0.0, 0.04205826869255579, 0.006020210347790354, 0.6448731873534732, -0.15000000201631575, 0.08794720144778911, -0.1000100012075052, -0.7961414341315546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.27239516640312517, -0.06641290087758284, 0.09264804995694033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879753268, 0.0, 0.0, 0.0, 0.023762347123838862, -0.0890397475404342, 0.06562504504063298, -2.1077957750996635e-12, 0.7107552067100041, -1.245049128519923e-12, -0.09969222839300354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17106893361457268, -0.0489131759354315, 0.038017999775098996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22469818452259974, 0.0, 0.0, 0.0, 0.0434746343659293, 0.0012324043969994094, 0.648388813471059, -0.15000000201684774, 0.12837740970963563, -0.10001000120783675, -0.7890452771596788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2809794167415028, -0.06904429736985032, 0.09456877758265564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876896243, 0.0, 0.0, 0.0, 0.028327313467470038, -0.09575611901581889, 0.07031252235171694, -1.0639689063175307e-11, 0.80860416523693, -6.6311075060323085e-12, 0.14192313943751741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17168500676755247, -0.052627929845349655, 0.03841455251430608]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22534813676605597, 0.0, 0.0, 0.0, 0.04498124675421104, -0.00041792293400597785, 0.6483888134603685, -0.1500000020184312, 0.1727215762752165, -0.10001000120892964, -0.7736183517948714, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28932179414282655, -0.07174845631609757, 0.09643376354809557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869124687, 0.0, 0.0, 0.0, 0.030132247765634834, -0.03300654662010774, -2.1381185710822592e-10, -3.1669148272001986e-11, 0.8868833313116176, -2.1857827975124064e-11, 0.30853850729614873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16684754802647528, -0.05408317892494488, 0.03729971930879857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22599808900899307, 0.0, 0.0, 0.0, 0.044593826822085146, 0.0031113004633590412, 0.6411231873242181, -0.15000000202146163, 0.21722970114480858, -0.10001000121088953, -0.7536106580368721, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29729848163442857, -0.07391233964049636, 0.09806146422326331]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044858741749, 0.0, 0.0, 0.0, -0.007748398642517973, 0.07058446794730037, -0.14531252272300743, -6.060857174788242e-11, 0.8901624973918414, -3.919794325536845e-11, 0.40015387515998607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15953374983204063, -0.04327766648797571, 0.03255401350335468]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22664804125208457, 0.0, 0.0, 0.0, 0.04202925890032289, 0.00887338975426367, 0.6238184988797113, -0.15000000202359706, 0.2581517843186256, -0.10001000121225458, -0.7327721958854393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30511671545928915, -0.07488957768074739, 0.0995012534949413]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861830109, 0.0, 0.0, 0.0, -0.05129135843524501, 0.11524178581809255, -0.34609376889013654, -4.270844153977504e-11, 0.8184416634763412, -2.7301075902664952e-11, 0.4167692430286563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15636467649721122, -0.019544760805020545, 0.028795785433559606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22729799349528942, 0.0, 0.0, 0.0, 0.03752910857169133, 0.01311835411024076, 0.5981479251822706, -0.15000000202597547, 0.2917378257975597, -0.10001000121392567, -0.7148529653400153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31306297671824385, -0.07436448495134006, 0.1008882119442385]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044864096827, 0.0, 0.0, 0.0, -0.09000300657263124, 0.08489928711954182, -0.5134114739488153, -4.756792315581655e-11, 0.6717208295786815, -3.342196495794877e-11, 0.3583846109084795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15892522517909446, 0.01050185458814649, 0.027739168985944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22794794572785398, 0.0, 0.0, 0.0, 0.032348798228694756, 0.013972630551596706, 0.5678614662230811, -0.1500000020603941, 0.31427355695916304, -0.10001000124147666, -0.703602966353249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3211571134798725, -0.0729619388440577, 0.10234616764534651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044651291458, 0.0, 0.0, 0.0, -0.1036062068599315, 0.017085528827118904, -0.605729179183789, -6.883727208212485e-10, 0.4507146232320669, -5.51019783099607e-10, 0.22499997973532485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16188273523257396, 0.028050922145647188, 0.02915911402216031]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22859789797052799, 0.0, 0.0, 0.0, 0.027451337165357068, 0.012241376045067167, 0.5367091219999504, -0.15000000206465502, 0.32950897699869386, -0.10001000124484566, -0.7027721989211999, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32936687935545905, -0.07131210264042123, 0.10390949527706811]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044853480014, 0.0, 0.0, 0.0, -0.09794922126675373, -0.03462509013059077, -0.6230468844626139, -8.521864154374937e-11, 0.30470840079061595, -6.737991098427487e-11, 0.016615348640981714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1641953175117311, 0.032996724072729494, 0.031266552634431934]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22924785021435948, 0.0, 0.0, 0.0, 0.023231430406221817, 0.009398248238906667, 0.5084408925120971, -0.1500000020651964, 0.3411940858667552, -0.10001000124524606, -0.7133298927244414, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3376500754414695, -0.07004128093487509, 0.10554273387207767]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876629973, 0.0, 0.0, 0.0, -0.08439813518270502, -0.05686255612321001, -0.5653645897570648, -1.0827413395217968e-11, 0.2337021773612273, -8.008150535592996e-12, -0.21115387606482938, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656639217202099, 0.025416434110922745, 0.032664771900191215]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22989780245658992, 0.0, 0.0, 0.0, 0.019752184419195993, 0.00663962338252357, 0.4868067777097906, -0.15000000206972072, 0.3521153006632454, -0.10001000124853848, -0.7333779708001987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34592728419467145, -0.0691470221300892, 0.10720611157622553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044844608842, 0.0, 0.0, 0.0, -0.06958491974051646, -0.05517249712766193, -0.4326822960461304, -9.048658930382412e-11, 0.21842429592980428, -6.584833837623878e-11, -0.40096156151514706, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.165544175064038, 0.017885176095717666, 0.03326755408295708]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23054775467701452, 0.0, 0.0, 0.0, 0.01695923501367084, 0.0046139850739449085, 0.47555677701410276, -0.15000000213234777, 0.36160889461267165, -0.10001000129405818, -0.761334701318051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3541447263520311, -0.06850157836240235, 0.10887327525738888]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044408492038, 0.0, 0.0, 0.0, -0.05585898811050306, -0.04051276617157322, -0.22500001391375637, -1.252541023608236e-09, 0.1898718789885241, -9.103939178537349e-10, -0.5591346103570455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16434884314719328, 0.012908875353737045, 0.03334327362326693]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23119770691872243, 0.0, 0.0, 0.0, 0.015108443679219588, 0.003358437716285252, 0.47618177540676676, -0.15000000213859438, 0.3659248681517152, -0.10001000129879484, -0.7957000856811232, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.36230178362013554, -0.06818991729018775, 0.11055061584137026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044834158466, 0.0, 0.0, 0.0, -0.037015826689025005, -0.02511094715319313, 0.012499967853280197, -1.2493217186473585e-10, 0.08631947078087118, -9.473301808023121e-11, -0.6873076872614428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16314114536208946, 0.006233221444291878, 0.03354681167962762]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23184765916274108, 0.0, 0.0, 0.0, 0.014074408407971983, 0.0028643257159356762, 0.48643177215476957, -0.15000000213860648, 0.361326735786973, -0.10001000129880386, -0.8351923931714781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37040268321628145, -0.06817406860428807, 0.11223464015375724]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880372793, 0.0, 0.0, 0.0, -0.0206807054249521, -0.00988224000699152, 0.20499993496005656, -2.4223308007021127e-13, -0.09196264729484463, -1.804787208165055e-13, -0.7898461498070983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16201799192291827, 0.0003169737179937772, 0.03368048624773972]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23249761140674877, 0.0, 0.0, 0.0, 0.013189411911339247, 0.0037822440556639523, 0.5025567672655873, -0.15000000213864853, 0.3477006290567524, -0.10001000129883539, -0.8787862391634265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3783910977643558, -0.06814521553805562, 0.11388663608743756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880153547, 0.0, 0.0, 0.0, -0.017699929932654714, 0.01835836679456552, 0.322499902205311, -8.411210218482996e-13, -0.2725221346044111, -6.306257763603e-13, -0.8718769198389668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15976829096148737, 0.0005770613246488775, 0.033039918673606394]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2331475636497501, 0.0, 0.0, 0.0, 0.01274010671888727, 0.006653638423222915, 0.5230880116977709, -0.15000000214221043, 0.3287965479603944, -0.10001000130158842, -0.9227316236581125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3862352959921521, -0.0683864075684979, 0.11551394489501998]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044860026319, 0.0, 0.0, 0.0, -0.008986103849039537, 0.05742788735117925, 0.41062488864367086, -7.123784629835075e-11, -0.37808162192715994, -5.506070179638836e-11, -0.8789076898937189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15688396455592588, -0.004823840608845435, 0.032546176151648495]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2337975158914001, 0.0, 0.0, 0.0, 0.013038307217587454, 0.010194599707327286, 0.5469239431234003, -0.15000000214892542, 0.3083644924970208, -0.10001000130674031, -0.963278546656329, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3940636233018449, -0.06919891335438824, 0.11716344641027228]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044833000307, 0.0, 0.0, 0.0, 0.00596400997400366, 0.07081922568208743, 0.47671862851258795, -1.3430000596931742e-10, -0.4086411092674719, -1.0303789776927164e-10, -0.8109384599643291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1565665461938554, -0.01625011571780697, 0.03299003030504582]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23444746813074982, 0.0, 0.0, 0.0, 0.013740858263575562, 0.012638223719674792, 0.5703145615424868, -0.15000000216037793, 0.2901544626656275, -0.10001000131645839, -0.9966770081597888, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.40202050257218275, -0.07048310333424881, 0.1188598460112494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044786994532, 0.0, 0.0, 0.0, 0.014051020919762174, 0.04887248024695014, 0.46781236838172946, -2.290498776721859e-10, -0.36420059662786586, -1.943614459247949e-10, -0.6679692300691954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1591375854067563, -0.025683799597211315, 0.03392799201954224]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2350974203737984, 0.0, 0.0, 0.0, 0.014955331032671172, 0.011604165875700762, 0.5934083046299652, -0.15000000216312895, 0.27791645846592034, -0.10001000131853546, -1.0191770081691829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.41027790878090725, -0.07233822458521512, 0.12065641631914688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044860972038, 0.0, 0.0, 0.0, 0.0242894553819122, -0.02068115687948062, 0.4618748617495662, -5.502034853981952e-11, -0.24476008399414345, -4.154146746129631e-11, -0.4500000001878811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1651481241744898, -0.03710242501932607, 0.035931406157949784]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23574737261760623, 0.0, 0.0, 0.0, 0.016394512955013554, 0.006899708590855895, 0.6124551724419617, -0.15000000216374784, 0.27540047989643035, -0.10001000131898254, -1.0272226139092842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4188085067868335, -0.07461658135674354, 0.12255618315726981]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487615656, 0.0, 0.0, 0.0, 0.028783638446847625, -0.09408914569689733, 0.3809373551174139, -1.2377700941062604e-11, -0.05031957138979978, -8.941487090719246e-12, -0.16091211480202472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17061196011852514, -0.045567135430568284, 0.037995336762458636]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23639732486108012, 0.0, 0.0, 0.0, 0.017954208660827902, 0.00038769515953522224, 0.6294786013540644, -0.15000000216533654, 0.28272716086029154, -0.10001000132012605, -1.0245638253795792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4274878491607696, -0.07716158849176591, 0.12450891902828394]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869477736, 0.0, 0.0, 0.0, 0.03119391411628697, -0.13024026862641344, 0.3404685782420551, -3.177427891735283e-11, 0.1465336192772237, -2.287045036912248e-11, 0.05317577059409745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17358684747872202, -0.05090014270044731, 0.03905471742028254]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23704727708853102, 0.0, 0.0, 0.0, 0.019595238382647505, -0.006186210501127249, 0.6407285915987881, -0.15000000221364113, 0.2998098416587551, -0.10001000135554115, -1.014950642557207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.43620007477791106, -0.0799273250719775, 0.12647558585051877]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044549018042, 0.0, 0.0, 0.0, 0.03282059443639208, -0.13147811321324943, 0.22499980489447402, -9.660918503018834e-10, 0.3416536159692719, -7.083020244247227e-10, 0.19226365644744525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17424451234282906, -0.055314731604231726, 0.03933333644469656]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23769722933147222, 0.0, 0.0, 0.0, 0.021193709516988846, -0.01156823698700874, 0.644478586661093, -0.15000000221683743, 0.32529540897289355, -0.10001000135799502, -0.9990899469592981, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.44484646364072694, -0.0827820205050434, 0.12842213723748394]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044858823874, 0.0, 0.0, 0.0, 0.03196942268682679, -0.10764052971762979, 0.07499990124609829, -6.392588302726097e-11, 0.5097113462827683, -4.907738875094875e-11, 0.3172139119581795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17292777725631758, -0.05709390866131789, 0.038931027739303486]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23834718157299928, 0.0, 0.0, 0.0, 0.02259356687578448, -0.013689920189146793, 0.644478586445503, -0.1500000022243237, 0.35768386278143266, -0.10001000136406646, -0.9746227007117132, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45322340294592484, -0.08551520448957664, 0.13028843390253014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044830541071, 0.0, 0.0, 0.0, 0.027997147175912673, -0.04243366404276108, -4.311800125278431e-09, -1.49725125214992e-10, 0.6477690761707817, -1.214286615507006e-10, 0.4893449249516969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1675387861039576, -0.05466367969066488, 0.037325933300923965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23899713381693238, 0.0, 0.0, 0.0, 0.02198794827128701, -0.009807933133245215, 0.6369785909522214, -0.15000000222460222, 0.393225203084402, -0.10001000136429544, -0.9452989038144342, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46112708197048996, -0.0875263341987617, 0.1319055943129928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044878662325, 0.0, 0.0, 0.0, -0.012112372089949378, 0.07763974111803158, -0.1499999098656319, -5.570463667068821e-12, 0.7108268060593866, -4.579807417806986e-12, 0.5864759379455804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15807358049130285, -0.04022259418370118, 0.03234320820925342]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23964708605875154, 0.0, 0.0, 0.0, 0.01924953489751336, -0.0024064016981249605, 0.6194785947113135, -0.1500000022301561, 0.42816942988203055, -0.10001000136860272, -0.914868556267287, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4687257816014547, -0.08816489259751556, 0.13332803047291533]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836383247, 0.0, 0.0, 0.0, -0.05476826747547296, 0.14803062870240508, -0.3499999248181588, -1.1107781478374616e-10, 0.6988845359525706, -8.614543769825366e-11, 0.6086069509429433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15197399261929523, -0.012771167975077217, 0.028448723198450175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24029703830272695, 0.0, 0.0, 0.0, 0.01472591483244424, 0.004764674176395066, 0.5936452645106434, -0.15000000223029936, 0.45876654317432763, -0.1000100013687244, -0.8870816580702633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4764017455822124, -0.08745197305992548, 0.13469279569661563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879508329, 0.0, 0.0, 0.0, -0.0904724013013824, 0.14342151749040052, -0.5166666040134021, -2.864659719662059e-12, 0.6119422658459418, -2.4336255491093905e-12, 0.5557379639404746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15351927961515244, 0.014258390751801565, 0.02729530447400588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24094699054657165, 0.0, 0.0, 0.0, 0.009260006483324704, 0.007955294791641102, 0.5632286003095943, -0.15000000223079013, 0.481266542961808, -0.10001000136918381, -0.8656882092231303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4843298768656265, -0.08599248541580573, 0.13615884028728406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876894301, 0.0, 0.0, 0.0, -0.10931816698239069, 0.06381241230492074, -0.608333284020982, -9.815610189438853e-12, 0.4499999957496069, -9.188178349786448e-12, 0.42786897694266046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1585626256682823, 0.02918975288239512, 0.029320891813368756]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2415969427825432, 0.0, 0.0, 0.0, 0.004012219833836244, 0.006942920278873571, 0.531978602079852, -0.1500000022533208, 0.49425984585428906, -0.1000100013904639, -0.8544382096806061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.492474849984536, -0.0844200048346356, 0.1377734722815161]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044719430934, 0.0, 0.0, 0.0, -0.10495573298976921, -0.02024749025535061, -0.6249999645948462, -4.506131597121238e-10, 0.25986605784962186, -4.2560178950768006e-10, 0.22499999085048222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1628994623781901, 0.03144961162340244, 0.03229263988464072]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24224689502591307, 0.0, 0.0, 0.0, -0.00048814112458583133, 0.003543864738374717, 0.5036452698164533, -0.15000000225511312, 0.5014964503560285, -0.10001000139214415, -0.8563132100543398, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.500787819043769, -0.08321130916375588, 0.1394876043478745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044867397367, 0.0, 0.0, 0.0, -0.0900072191684415, -0.06798111080997707, -0.5666666452679747, -3.5846525830872954e-11, 0.14473209003478998, -3.36050351925568e-11, -0.0375000074746743, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16625938118465913, 0.024173913417594457, 0.03428264132716804]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24289684726806, 0.0, 0.0, 0.0, -0.004168229766679911, -0.0003219529251795852, 0.48197860348883503, -0.1500000022600385, 0.5067262747293185, -0.10001000139657612, -0.8691257103293859, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5091421999015469, -0.0823590808814413, 0.1412363811028138]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904484293847, 0.0, 0.0, 0.0, -0.0736017728418816, -0.07731635327108605, -0.43333332655236567, -9.850760092762137e-11, 0.1045964874658, -8.863933029665228e-11, -0.2562500055009216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16708761715555687, 0.017044565646291587, 0.0349755350987865]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24354679950988234, 0.0, 0.0, 0.0, -0.006888250947228752, -0.00352720357974074, 0.4707286030617599, -0.15000000226590895, 0.5096201197264563, -0.10001000140183516, -0.8910527938526906, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.517447724564752, -0.08184447874476872, 0.14298860405420677]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904483644681, 0.0, 0.0, 0.0, -0.05440042361097681, -0.06410501309122309, -0.22500000854150223, -1.1740913168691173e-10, 0.057876899942755286, -1.0518076615243323e-10, -0.43854167046609543, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16611049326410152, 0.010292042733451518, 0.03504445902785944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24419675175192818, 0.0, 0.0, 0.0, -0.008672049648762434, -0.005648944735906632, 0.4713033959179685, -0.15000000227110377, 0.5090408388385431, -0.10001000140646096, -0.9205753634145297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5256659908531884, -0.08163061162027141, 0.1447306024122858]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044840916844, 0.0, 0.0, 0.0, -0.03567597403067362, -0.042434823123317846, 0.011495857124171532, -1.0389633925641154e-10, -0.011585617758261946, -9.251611829696118e-11, -0.5904513912367821, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16436532576872934, 0.004277342489946094, 0.03483996716158089]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24484670375961787, 0.0, 0.0, 0.0, -0.009649236282535143, -0.00671961444572953, 0.48150646876707304, -0.15000000285772597, 0.5028295100813256, -0.10001000193299572, -0.9561934121253606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.533800844549945, -0.08168334751616103, 0.1464601401128604]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904015379394, 0.0, 0.0, 0.0, -0.019543732675454197, -0.021413394196457967, 0.20406145698209088, -1.173244403942478e-08, -0.12422657514435131, -1.0530695122209537e-08, -0.7123609742166166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16269707393513103, -0.0010547179177925158, 0.03459075401149231]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24549665572200083, 0.0, 0.0, 0.0, -0.010107392188387245, -0.006714201994857078, 0.49941867762422726, -0.15000000356932516, 0.48723627053088364, -0.100010002574971, -0.9966878427374076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5418515809451242, -0.08187682679111444, 0.14816955892984807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999039247659284, 0.0, 0.0, 0.0, -0.009163118117042018, 0.00010824901744903304, 0.3582441771430843, -1.4231983810202587e-08, -0.3118647910088392, -1.283950568919665e-08, -0.8098886122409407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16101472790358415, -0.0038695854990680872, 0.03418837633975339]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24614660796571572, 0.0, 0.0, 0.0, -0.010377610247803867, -0.004767636493328833, 0.5212903254323229, -0.150000003570115, 0.4660111201864633, -0.10001000257567925, -1.0410833872156853, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5497403003809942, -0.08216035164431038, 0.1498322788152291]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874297847, 0.0, 0.0, 0.0, -0.005404361188332428, 0.03893131003056491, 0.43742689730423295, -1.5797053598165124e-11, -0.4245030068884067, -1.4165099103277334e-11, -0.8879108895655533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15777438871739963, -0.005670497063918804, 0.03325439770762069]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24679656020925456, 0.0, 0.0, 0.0, -0.010195590803734318, -0.0011561047988294243, 0.5461313321878922, -0.15000000357149273, 0.44290405904791824, -0.10001000257696065, -1.0856300455603276, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.557508535978402, -0.08279373788033606, 0.15147089576791598]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044870776738, 0.0, 0.0, 0.0, 0.003640388881390984, 0.07223063388998818, 0.4968201351113864, -2.7554565827704738e-11, -0.4621412227709009, -2.562788036423942e-11, -0.8909331668928461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15536471194815493, -0.0126677247205138, 0.03277233905373779]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24744651244974744, 0.0, 0.0, 0.0, -0.00980040929878985, 0.0026811407611621314, 0.5701920008369606, -0.150000003579875, 0.42166508711470707, -0.10001000258577943, -1.1265778177718353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5652999796635733, -0.08374799523424048, 0.15311495318724236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044809857632, 0.0, 0.0, 0.0, 0.00790363009888935, 0.07674491119983112, 0.4812133729186726, -1.6764552904344134e-10, -0.42477943866422324, -1.7637547870830137e-10, -0.8189554442301539, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15582887370342552, -0.01908514707808846, 0.03288114838652776]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24809646469084198, 0.0, 0.0, 0.0, -0.008983763684291723, 0.0037639190099873696, 0.5937324440748326, -0.15000000358810514, 0.4060442043864778, -0.10001000259424908, -1.1601767038505864, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5733606946047325, -0.08519883147721558, 0.15483561533202042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044821890822, 0.0, 0.0, 0.0, 0.01633291228996256, 0.021655564976504754, 0.4708088647574393, -1.646026384417975e-10, -0.31241765456458537, -1.6939307751881575e-10, -0.6719777215750204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16121429882318572, -0.02901672485950179, 0.03441324289556128]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2487464169304844, 0.0, 0.0, 0.0, -0.007944313047067492, 0.0007044563268547351, 0.6130026619101681, -0.15000000359857432, 0.3997914108624564, -0.10001000260569375, -1.182676703797343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5817682839615067, -0.08708266944779683, 0.15667030524756712]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044792848635, 0.0, 0.0, 0.0, 0.02078901274448461, -0.06118925366265268, 0.3854043565962808, -2.0938386449979712e-10, -0.12505587048042807, -2.2889328417987563e-10, -0.4499999989351295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16815178713548443, -0.037676759411625016, 0.03669379831093371]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24939636866964474, 0.0, 0.0, 0.0, -0.006902114365735982, -0.00570625026803921, 0.6242526543376133, -0.15000000445483958, 0.40566466350172675, -0.10001000328112325, -1.1914295802025956, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5904387120262181, -0.08924411062668099, 0.15860229137978665]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999034783206334, 0.0, 0.0, 0.0, 0.020843973626630194, -0.1282141318978789, 0.22499984854890487, -1.7125304837134286e-08, 0.11746505278540734, -1.350859021019295e-08, -0.17505752810505587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17340856129422802, -0.043228823577683186, 0.03863972264439093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2500463209133398, 0.0, 0.0, 0.0, -0.0060506561184218, -0.01289713247522516, 0.6306063122218272, -0.15000000445554768, 0.4199139623046952, -0.1000100032817105, -1.1901853330661696, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5991910197889214, -0.09142313248726645, 0.16055388198092427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044873900675, 0.0, 0.0, 0.0, 0.017029164946283655, -0.143817644143719, 0.127073157684277, -1.4161816640906512e-11, 0.28498597605936826, -1.1745030547207762e-11, 0.02488494272852204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17504615525406536, -0.043580437211709296, 0.03903181202275252]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2506962731178172, 0.0, 0.0, 0.0, -0.005397563568633427, -0.01902707483766551, 0.6358134010941479, -0.15000000456046234, 0.43998241016291806, -0.10001000337675249, -1.1826939623471984, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6078722636958098, -0.09349907653627267, 0.16247600787861916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904408954848, 0.0, 0.0, 0.0, 0.013061850995767451, -0.12259884724880701, 0.10414177744641392, -2.0982932927398097e-09, 0.4013689571644573, -1.9008398997767702e-09, 0.14982741437942454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17362487813776764, -0.0415188809801242, 0.03844251795389762]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2513462253513273, 0.0, 0.0, 0.0, -0.004823088089091537, -0.02349975414795299, 0.6390381938185379, -0.1500000045882679, 0.4672753028764694, -0.10001000340262074, -1.172705468033193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6164230543834146, -0.09551754006144239, 0.16435404335766032]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044670201071, 0.0, 0.0, 0.0, 0.011489509590837802, -0.08945358620574961, 0.06449585448779967, -5.561114383596229e-10, 0.5458578542710268, -5.17364935186227e-10, 0.1997698862801058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17101581375209543, -0.040369270503394436, 0.037560709580823304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25199617753195014, 0.0, 0.0, 0.0, -0.004268154303310389, -0.02638712934007061, 0.6425096591430016, -0.15000000475591305, 0.5011096062155245, -0.1000100035806168, -1.1583913599522733, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6248365040523479, -0.09749544120402881, 0.16618701485665827]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043612456993, 0.0, 0.0, 0.0, 0.01109867571562296, -0.05774750384235234, 0.06942930648927527, -3.352903141673128e-09, 0.6766860667811023, -3.5599212131519184e-09, 0.28628216161839204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16826899337866677, -0.03955802285172845, 0.03665942997995904]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2526461297737612, 0.0, 0.0, 0.0, -0.003795661432659677, -0.025840059903537965, 0.6461203892176793, -0.15000000476435538, 0.5394751103095166, -0.10001000358976507, -1.143501638099991, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6329072411536976, -0.09936363026747207, 0.16792217823073058]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836221465, 0.0, 0.0, 0.0, 0.009449857413014236, 0.010941388730652903, 0.07221460149355459, -1.688464524953272e-10, 0.767310081879841, -1.8296518606956624e-10, 0.2977944370456482, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16141474202699277, -0.037363781268865234, 0.03470326748144654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2532960820177071, 0.0, 0.0, 0.0, -0.004646401928232452, -0.021765843092444774, 0.6461203840426114, -0.15000000476455602, 0.5786218151584571, -0.10001000358995357, -1.131786302476316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6406485298400609, -0.10048794275929654, 0.1695155899713417]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044878917638, 0.0, 0.0, 0.0, -0.017014809911455507, 0.08148433622186385, -1.0350135815073713e-07, -4.012635972534725e-12, 0.7829340969788106, -3.770040695945876e-12, 0.23430671247349766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15482577372726838, -0.02248624983648953, 0.03186823481222253]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25394603423143336, 0.0, 0.0, 0.0, -0.006895452834509845, -0.017740698972948988, 0.638759643640322, -0.15000000484768655, 0.614799720767078, -0.10001000368132468, -1.1269953530423473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6484267484068842, -0.10079636349627738, 0.17106063989428508]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044274525421, 0.0, 0.0, 0.0, -0.044981018125547854, 0.08050288238991571, -0.14721480804578715, -1.662610588068856e-09, 0.7235581121724168, -1.8274220637202932e-09, 0.09581898867937447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15556437133646414, -0.006168414739616806, 0.030900998458867582]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2545959864744359, 0.0, 0.0, 0.0, -0.009950760847136978, -0.016745304251679603, 0.6234004948394937, -0.15000000484979625, 0.6442588271370862, -0.10001000368423207, -1.1328787897953214, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6564849805353146, -0.10069775247460928, 0.17269152124734863]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044860050126, 0.0, 0.0, 0.0, -0.06110616025254266, 0.019907894425387734, -0.3071829760165674, -4.2193815529858164e-11, 0.5891821274001621, -5.814790798825068e-11, -0.11766873505948228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16116464256860855, 0.00197222043336193, 0.03261762706127116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2552459377246717, 0.0, 0.0, 0.0, -0.013195267963204664, -0.018431299649025883, 0.6037929376068366, -0.15000000487543433, 0.6644226156439798, -0.1000100037140889, -1.1468941459961746, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6647703730797146, -0.10054961585287966, 0.17441604925946227]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999025004716764, 0.0, 0.0, 0.0, -0.0648901423213537, -0.03371990794692561, -0.3921511446531417, -5.127616579030929e-10, 0.4032757701378722, -5.971364028593951e-10, -0.2803071240170649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16570785088800064, 0.0029627324345924168, 0.03449056024227303]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25589588996622215, 0.0, 0.0, 0.0, -0.016228992035135757, -0.021303872614366243, 0.5836869719376038, -0.1500000048784462, 0.6777772714893643, -0.10001000371775856, -1.166796538421553, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6731755898880346, -0.10050510625320491, 0.17618232050667443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044831009133, 0.0, 0.0, 0.0, -0.06067448143862185, -0.05745145930680718, -0.40211931338465773, -6.023722949324673e-11, 0.26709311690769166, -7.339329352619006e-11, -0.39804784850757163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16810433616639833, 0.0008901919934949723, 0.035325424944242886]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25654584199944663, 0.0, 0.0, 0.0, -0.018821682248450718, -0.02406620989989246, 0.5668325972003992, -0.15000000514882206, 0.6874138472151763, -0.10001000401790613, -1.1932351417780716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6815721534222468, -0.10060781885612195, 0.17795060461117523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999040664489621, 0.0, 0.0, 0.0, -0.051853804266299215, -0.055246745710524355, -0.33708749474409005, -5.407517433817161e-09, 0.19273151451624104, -6.002951402909067e-09, -0.5287720671303698, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16793127068424282, -0.0020542520583409253, 0.0353656820900163]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2571957942368065, 0.0, 0.0, 0.0, -0.021030526070991526, -0.02583122405480676, 0.5569797803526632, -0.15000000516158715, 0.6935965170272611, -0.10001000403853104, -1.2260927865425424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6898628081806145, -0.10075490095039759, 0.1796898247121083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044747197394, 0.0, 0.0, 0.0, -0.04417687645081614, -0.03530028309828599, -0.19705633695472205, -2.5530202171910014e-10, 0.12365339624169644, -4.1249800761350907e-10, -0.657152895289418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16581309516735432, -0.002941641885512644, 0.03478440201866129]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25784574642766844, 0.0, 0.0, 0.0, -0.023193199089211716, -0.02584941673978691, 0.552586631753888, -0.15000000528853683, 0.6925752814900638, -0.1000100042521587, -1.2643789002499701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6979752964488379, -0.10071916093802642, 0.18137068635731157]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904381723864, 0.0, 0.0, 0.0, -0.043253460364403785, -0.0003638536996029701, -0.08786297197550341, -2.5389933942581746e-09, -0.020424710743946306, -4.27255323824e-09, -0.7657222741485548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1622497653644684, 0.0007148002474231877, 0.033617232904065465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2584956986515413, 0.0, 0.0, 0.0, -0.02479396679382947, -0.023526917884262886, 0.5558542686467571, -0.15000000535675037, 0.68810014052081, -0.10001000434367516, -1.307007788960623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7058356430445942, -0.10085989692740603, 0.18299244497127226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044477457056, 0.0, 0.0, 0.0, -0.032015354092355106, 0.04644997711048044, 0.06535273785738177, -1.364270949504064e-09, -0.08950281938507451, -1.8303290893366554e-09, -0.8525777742130605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15720693191512572, -0.0028147197875922764, 0.03243517227921405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25914565088290237, 0.0, 0.0, 0.0, -0.02566693450687854, -0.019936623504859793, 0.5648674950700266, -0.1500000053931401, 0.6839210941172903, -0.10001000441741272, -1.3502294526759393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7135752476167202, -0.10137984999814018, 0.184593289681007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044627221394, 0.0, 0.0, 0.0, -0.0174593542609814, 0.07180588758806183, 0.18026452846539098, -7.277945399223232e-10, -0.08358092807039383, -1.4747512226103276e-09, -0.8644332743063232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1547920914425192, -0.010399061414682758, 0.032016894194694445]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2597956031263604, 0.0, 0.0, 0.0, -0.025774748556258654, -0.01780445682302976, 0.5781899136583082, -0.15000000539493336, 0.6837881422794766, -0.10001000483271755, -1.3902938913959322, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7214844368774657, -0.10240231562622805, 0.18624795103452463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869160528, 0.0, 0.0, 0.0, -0.0021562809876022396, 0.04264333363660069, 0.26644837176563047, -3.586512766477454e-11, -0.0026590367562732004, -8.306096680008556e-09, -0.8012887743998566, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1581837852149095, -0.020449312561757374, 0.0330932270703528]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2598658852087168, 0.0, 0.0, 0.0, -0.02417105347374379, -0.018942077460056456, 0.5920715244118882, -0.1500000058581311, 0.6914512850049533, -0.10169252931425445, -1.4234511051218284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.729803611555447, -0.10451569445043497, 0.18813570409939795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056416471276301, 0.0, 0.0, 0.0, 0.032073901650297325, -0.02275241274053396, 0.27763221506596825, -9.263955299595153e-09, 0.15326285450953497, -0.03365048963073792, -0.6631442745179232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1663834935596275, -0.042267576484138536, 0.0377550612974664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2598603358381357, 0.0, 0.0, 0.0, -0.02202400190327803, -0.025848615029055704, 0.6063259299086122, -0.15000001787717726, 0.7090872372511039, -0.10370817414853585, -1.4459510938623377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7386427048135271, -0.10735032155569993, 0.1902912404780716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098741162081198, 0.0, 0.0, 0.0, 0.042941031409315204, -0.13813075137998493, 0.28508810993448075, -2.4038092315470945e-07, 0.35271904492301215, -0.0403128966856282, -0.4499997748101875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1767818651616023, -0.05669254210529909, 0.0431107275734735]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25985801560027416, 0.0, 0.0, 0.0, -0.020214435002908024, -0.03559371235320291, 0.6181760778774441, -0.15027348704013516, 0.7333912749795579, -0.1048132576179428, -1.4548134931372068, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7477504944094632, -0.11031579167708203, 0.19256178158061815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.640475723094991e-05, 0.0, 0.0, 0.0, 0.03619133800740016, -0.19490194648294412, 0.23700295937663768, -0.005469383259157716, 0.48608075456907973, -0.022101669388138966, -0.1772479854973803, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1821557919187207, -0.05930940242764186, 0.04541082205093094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25985783795362477, 0.0, 0.0, 0.0, -0.01914926631370249, -0.04442736973464008, 0.6257676971349708, -0.15034678696107948, 0.7614978488738366, -0.10530275890264636, -1.45305751232337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7567200478965508, -0.11285491159674448, 0.1947570197550181]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.552932987545649e-06, 0.0, 0.0, 0.0, 0.02130337378411068, -0.1766731476287434, 0.15183238515053366, -0.0014659984188861268, 0.5621314778855735, -0.009790025694071206, 0.03511961627673374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1793910697417529, -0.05078239839324906, 0.04390476348799888]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25985786735649136, 0.0, 0.0, 0.0, -0.01874579893060344, -0.049482077596133725, 0.6307538165912997, -0.1503467885954998, 0.7944038074411464, -0.10537629818489141, -1.4413325447469143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7652820814043271, -0.114858609128315, 0.19678904466533048]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.880573317755398e-07, 0.0, 0.0, 0.0, 0.008069347661981002, -0.10109415722987282, 0.0997223891265775, -3.268840632550396e-08, 0.6581191713461934, -0.001470785644901081, 0.23449935152911297, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.171240670155526, -0.04007395063141043, 0.0406404982062476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26050781952266383, 0.0, 0.0, 0.0, -0.019583930036423027, -0.048049099453531, 0.6302141944918352, -0.15034678880078067, 0.8283591508099767, -0.10353806952890039, -1.4233885903872465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7731326366810041, -0.11594590930939756, 0.19856856776498627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043323449155, 0.0, 0.0, 0.0, -0.01676262211639175, 0.028659562852054468, -0.010792441989288179, -4.105617712921411e-09, 0.6791068673766075, 0.0367645731198204, 0.35887908719335504, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15701110553353909, -0.021746003621651324, 0.035590461993115614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26115777176225796, 0.0, 0.0, 0.0, -0.02236125756937396, -0.04170637512103204, 0.6203988308394888, -0.15034678881359276, 0.8596138789811012, -0.10353806953984153, -1.4029756492438499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7804519018834217, -0.11574963602150377, 0.20011582256470034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044791882287, 0.0, 0.0, 0.0, -0.05554655065901866, 0.12685448664997923, -0.19630727304692952, -2.5624163825232143e-10, 0.6250945634224909, -2.188227307686752e-10, 0.4082588228679334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14638530404835404, 0.003925465757875682, 0.030945095994281354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.261807724004747, 0.0, 0.0, 0.0, -0.026688774749956515, -0.034203904573014914, 0.6009693611293708, -0.1503467888159505, 0.8844179919545457, -0.10353806954128617, -1.383843721316707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7878314094938836, -0.11459351614808005, 0.20159368555766696]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044849781061, 0.0, 0.0, 0.0, -0.08655034361165108, 0.15004941096034263, -0.3885893942023597, -4.7155321064671516e-11, 0.49608225946889145, -2.8892788967273624e-11, 0.38263855854285644, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14759015220923732, 0.023122397468474356, 0.029557259859332212]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26187800634666525, 0.0, 0.0, 0.0, -0.031533727911692164, -0.029291682645900794, 0.5737364213625592, -0.15174754438186744, 0.8990214940137036, -0.10353808182325872, -1.3697428036929775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7956308157976005, -0.11303804465602316, 0.20341647774533198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056468383654118, 0.0, 0.0, 0.0, -0.09689906323471295, 0.09824443854228238, -0.5446587953362328, -0.028015111318338573, 0.2920700411831571, -2.456394510039133e-07, 0.2820183524745896, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15598812607433857, 0.03110942984113791, 0.036455843753300174]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26187245699306955, 0.0, 0.0, 0.0, -0.03646935087116352, -0.029144166586206322, 0.541526632055496, -0.15468248121517883, 0.9018810938245759, -0.10353808527542419, -1.3644191712358333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8038544899256512, -0.11164247993154357, 0.20566070640730655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0001109870719135308, 0.0, 0.0, 0.0, -0.09871245918942712, 0.002950321193889438, -0.6441957861412642, -0.0586987366662277, 0.057191996217446694, -6.904330948531505e-08, 0.10647264914288174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1644734825610141, 0.027911294489591773, 0.044884573239491694]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26187013675092996, 0.0, 0.0, 0.0, -0.0413971383518849, -0.031251057577658704, 0.5074028613863277, -0.1584889736330377, 0.8957183844188342, -0.10365788700857188, -1.3669620504449431, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8123486975096323, -0.11036797471090136, 0.2080869596978349]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6404842792183927e-05, 0.0, 0.0, 0.0, -0.09855574961442765, -0.042137819829047685, -0.6824754133833661, -0.07612984835717752, -0.12325418811483488, -0.002396034662953854, -0.05085758418219716, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16988415167962173, 0.02549010441284403, 0.048525065810566634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2618699591089978, 0.0, 0.0, 0.0, -0.0465196218576904, -0.03193175666002731, 0.4718185293511527, -0.16129434808582155, 0.8814450821156392, -0.10477586922521916, -1.3776460979375869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8207303711550354, -0.10914159028211846, 0.21041284500792268]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.5528386437629986e-06, 0.0, 0.0, 0.0, -0.10244967011610996, -0.013613981647372052, -0.7116866407035009, -0.0561074890556765, -0.28546604606390097, -0.022359644332945353, -0.2136809498528738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16763347290806171, 0.02452768857565786, 0.04651770620175569]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2625199112062968, 0.0, 0.0, 0.0, -0.05232190415753779, -0.02813769586557966, 0.4385236357297044, -0.16082203578437945, 0.8628111867706117, -0.10345986616196146, -1.397765922976405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8284889534752338, -0.10743731253478052, 0.21242640529267992]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999041945980335, 0.0, 0.0, 0.0, -0.1160456459969478, 0.07588121588895298, -0.6658978724289663, 0.009446246028841684, -0.37267790690054853, 0.026320061265153957, -0.402396500776364, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15517164640396613, 0.03408555494675899, 0.04027120569514496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26316986344983917, 0.0, 0.0, 0.0, -0.05799782284951898, -0.020411801299310438, 0.41126818052191066, -0.15871087963536779, 0.8435666983837111, -0.10345986919047581, -1.4235715255614179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8356711644763805, -0.10527193116889255, 0.21417101264257513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044870847146, 0.0, 0.0, 0.0, -0.11351837383962377, 0.15451789132538443, -0.5451091041558741, 0.042223122980233375, -0.38488976773801237, -6.057028700823253e-08, -0.5161120517002588, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14364422002293442, 0.04330762731775935, 0.0348921469979039]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638198130355039, 0.0, 0.0, 0.0, -0.060630343238567336, -0.012504038986998043, 0.3938021636994627, -0.15578030511294264, 0.8274616169396686, -0.1085139049548833, -1.4513129056978176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8428783647974224, -0.10315233270220363, 0.2162715984536831]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998991713294576, 0.0, 0.0, 0.0, -0.05265040778096719, 0.15815524624624785, -0.34932033644895893, 0.058611490448503105, -0.32210162888085025, -0.10108071528814994, -0.5548276027279956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14414400642083908, 0.04239196933377841, 0.0420117162221593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26389009461883645, 0.0, 0.0, 0.0, -0.060874581884900324, -0.008164408321550364, 0.3898755852540028, -0.15371341282255718, 0.8182459424374798, -0.11783109106975892, -1.477240063386274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8506935690837899, -0.1015836444951585, 0.21906237470241008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056316666514815, 0.0, 0.0, 0.0, -0.004884772926659696, 0.08679261330895359, -0.07853156890919855, 0.04133784580770933, -0.1843134900437745, -0.1863437222975124, -0.5185431537691267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15630408572735097, 0.03137376414090247, 0.05581552497453941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638845444118319, 0.0, 0.0, 0.0, -0.06060900216223089, -0.011140369943549373, 0.3968326881756824, -0.15615056188602797, 0.8196695839111771, -0.12811763682751465, -1.4976030098797966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8590870106409448, -0.10072675303650415, 0.22265959708652802]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011100414009110977, 0.0, 0.0, 0.0, 0.005311594453388689, -0.059519232439980155, 0.13914205843359176, -0.048742981269415675, 0.028472829473944722, -0.20573091515511469, -0.40725892987045376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16786883114309784, 0.017137829173087076, 0.0719444476823588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638822240713975, 0.0, 0.0, 0.0, -0.0602908624161976, -0.019011111589700445, 0.410923472649284, -0.1618319591349285, 0.8279825434747106, -0.13909637762643665, -1.5097609410947894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8679083050354681, -0.10031456351001095, 0.22679450655272088]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6406808688028735e-05, 0.0, 0.0, 0.0, 0.006362794920665866, -0.15741483292302144, 0.281815689472032, -0.11362794497801082, 0.16625919127066946, -0.21957481597844009, -0.24315862429985838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17642588789046668, 0.008243790529864094, 0.082698189323857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638820443668369, 0.0, 0.0, 0.0, -0.0600928702661735, -0.029333819326772002, 0.42839832560302366, -0.16928367193362603, 0.8394382481721426, -0.14993450783639845, -1.5147867538156334, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8770423860537591, -0.10016880859322587, 0.2312417295544335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.594091212859036e-06, 0.0, 0.0, 0.0, 0.0039598430004819125, -0.2064541547414311, 0.34949705907479234, -0.1490342559739504, 0.2291140939486419, -0.21676260419923601, -0.1005162544168812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1826816203658195, 0.0029150983357014368, 0.08894446003425287]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26388207350419796, 0.0, 0.0, 0.0, -0.06048852596243575, -0.038358506980624714, 0.4455073442495497, -0.17475573389070498, 0.8505494695373617, -0.15996639808309465, -1.5164299314005458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8858606361297205, -0.09996212855682184, 0.23537627724381205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.827472219597269e-07, 0.0, 0.0, 0.0, -0.007913113925244953, -0.18049375307705426, 0.3421803729305211, -0.10944123914157863, 0.22222442730438127, -0.20063780493392397, -0.032863551698246216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17636500151923085, 0.004133600728080694, 0.08269095378757108]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26453202574415674, 0.0, 0.0, 0.0, -0.06218876097346721, -0.042335174594095075, 0.4650592911190223, -0.1746537752672726, 0.8602758863621954, -0.16706127047515104, -1.518440473841656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8937319772768367, -0.0992131604801968, 0.2388443292927066]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044799175827, 0.0, 0.0, 0.0, -0.03400470022062929, -0.07953335226940725, 0.39103893738945145, 0.0020391724686476126, 0.19452833649667473, -0.14189744784112776, -0.04021084882220008, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15742682294232296, 0.014979361532500773, 0.06936104097789092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26518197796972154, 0.0, 0.0, 0.0, -0.06496345243509287, -0.041251551693083435, 0.4872751096904221, -0.17095028688431974, 0.8696531306438285, -0.17055343931423667, -1.524568381092403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9008290490391627, -0.09780314328002, 0.24169116947103791]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044511295639, 0.0, 0.0, 0.0, -0.05549382923251316, 0.02167245802023285, 0.4443163714279966, 0.07406976765905722, 0.18754488563266206, -0.06984337678171222, -0.1225581450149387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14194143524651964, 0.028200344003535938, 0.05693680356662625]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26525225987689816, 0.0, 0.0, 0.0, -0.06806769367441134, -0.038857638188476824, 0.5084048002181187, -0.1673952687119612, 0.8811873794433983, -0.17268779149945374, -1.531063653239537, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9079062007523014, -0.09619297742890337, 0.24433949316415937]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056381435322528, 0.0, 0.0, 0.0, -0.062084824786369584, 0.04787827009213223, 0.4225938105539329, 0.07110036344717073, 0.23068497599139504, -0.042687043704341524, -0.12990544294267975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1415430342627738, 0.032203317022332784, 0.05296647386242886]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26524671043880416, 0.0, 0.0, 0.0, -0.07019944023877892, -0.03890343366381969, 0.532198362212003, -0.16773871975256613, 0.8986286325403343, -0.17247913831122683, -1.534176290454848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9156193748733226, -0.09485824573969176, 0.2474143003441742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098876188029173, 0.0, 0.0, 0.0, -0.04263493128735132, -0.0009159095068573403, 0.475871239877686, -0.006869020812098836, 0.34882506193872054, 0.0041730637645380556, -0.06225274430621755, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15426348242042162, 0.026694633784232175, 0.06149614360029639]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2651975921686999, 0.0, 0.0, 0.0, -0.07109478100927807, -0.04513893810818936, 0.5584810318145585, -0.17173305028236951, 0.9244130101201922, -0.17367747969598454, -1.530156292738684, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9240184961820027, -0.09441927214489078, 0.2514943958698442]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0009823654020849597, 0.0, 0.0, 0.0, -0.01790681540998332, -0.12471008888739334, 0.525653392051111, -0.07988661059606798, 0.5156875515971563, -0.02396682769515432, 0.08039995432328009, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16798242617360298, 0.008779471896019582, 0.08160191051340011]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26519129247975004, 0.0, 0.0, 0.0, -0.07197911675947918, -0.053814198661728214, 0.5835028090258175, -0.17640304133191498, 0.9569227453576975, -0.17775559266502539, -1.515556300474317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9325170004238078, -0.09437642662496643, 0.2559547805121902]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00012599377899816851, 0.0, 0.0, 0.0, -0.01768671500402228, -0.17350521107077718, 0.5004355442251787, -0.09339982099090921, 0.6501947047501063, -0.08156225938081704, 0.2919998452873375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1699700848361029, 0.0008569103984870027, 0.08920769284692064]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26584124449638147, 0.0, 0.0, 0.0, -0.07537228283076634, -0.06117921539490391, 0.6035136938472028, -0.17980620529944938, 0.9924078382530588, -0.18188640980758997, -1.49412631366159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9403537553274794, -0.09428772209539708, 0.26017045429408636]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999040332628532, 0.0, 0.0, 0.0, -0.06786332142574326, -0.14730033466351397, 0.40021769639929705, -0.06806327935068802, 0.7097018579072248, -0.08261634285129146, 0.42859973625454206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15673509807343217, 0.001774090591386765, 0.08431347563792303]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26649119673984883, 0.0, 0.0, 0.0, -0.08177957152137558, -0.0634839883275595, 0.614763686275912, -0.17832498128030075, 1.0271182888062864, -0.18231993112543302, -1.4696163323004952, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9467624232572783, -0.09372435066745514, 0.26351641721810887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869346797, 0.0, 0.0, 0.0, -0.12814577381218473, -0.046095458653111765, 0.22499984857418442, 0.02962448038297258, 0.6942090110645525, -0.008670426356861022, 0.49019962722189975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1281733585959774, 0.011267428558838666, 0.06691925848044972]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665614786537338, 0.0, 0.0, 0.0, -0.08988927783543438, -0.0615368626488967, 0.6135027863135067, -0.17383437177118555, 1.057304097017421, -0.17608257334507726, -1.4457763563909898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9517302909428004, -0.09205520635639447, 0.2660082773610143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056382776999818, 0.0, 0.0, 0.0, -0.1621941262811761, 0.03894251357325604, -0.02521799924810597, 0.08981219018230388, 0.6037161642226917, 0.124747155607115, 0.476799518190109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09935735371044103, 0.03338288622121361, 0.04983720285810804]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.266555929069743, 0.0, 0.0, 0.0, -0.09915680370832562, -0.05908783668809774, 0.6012020366787221, -0.17008418746832787, 1.0792152629412575, -0.16484205819247677, -1.4263563858695638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9558622083017572, -0.08914639033983639, 0.2679884640765657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011099167981606884, 0.0, 0.0, 0.0, -0.18535051745782485, 0.0489805192159791, -0.2460149926956934, 0.07500368605715341, 0.43822331847673, 0.22481030305200994, 0.3883994104285193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08263834717913654, 0.05817632033116164, 0.03960373431102801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665536087825353, 0.0, 0.0, 0.0, -0.10774453341693181, -0.059886665718031716, 0.5809664995749114, -0.16996885486529575, 1.089103149661125, -0.1523483818109655, -1.4151063393598062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9598377539983957, -0.08546174143336822, 0.26967838213753276]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6405744154573886e-05, 0.0, 0.0, 0.0, -0.17175459417212388, -0.015976580598679437, -0.40471074207621344, 0.0023066520606424834, 0.19775773439734975, 0.24987345049698906, 0.22500093019514994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07951091393277092, 0.07369297812936326, 0.03379836121934129]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665534310747967, 0.0, 0.0, 0.0, -0.11454376389138017, -0.06252842583117403, 0.5565461679442517, -0.17436363948811437, 1.0903293015534228, -0.14235151692298587, -1.4107570453238016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9638158706779687, -0.08160648281824404, 0.2711614474476636]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.554154773011451e-06, 0.0, 0.0, 0.0, -0.13598460948896723, -0.0528352022628463, -0.4884066326131947, -0.0878956924563721, 0.024523037845955747, 0.1999372977595924, 0.08698588072009233, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07956233359146148, 0.07710517230248372, 0.029661306202616672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26655346032464927, 0.0, 0.0, 0.0, -0.11916571382133744, -0.0654611244902389, 0.5316876742052631, -0.18231851160384674, 1.0858004153289267, -0.1386008057418884, -1.411588975359321, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9677911439095875, -0.07787674227900773, 0.2724878500600121]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.84997052241308e-07, 0.0, 0.0, 0.0, -0.09243899859914517, -0.058653973181297274, -0.49716987477977276, -0.15909744231464762, -0.09057772448992046, 0.07501422362194912, -0.016638600710384296, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07950546463237747, 0.07459481078472607, 0.026528052246969656]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26720341234500505, 0.0, 0.0, 0.0, -0.1216541030911338, -0.0649347653236069, 0.5101410180480295, -0.19008347142539134, 1.079266490696631, -0.1445497233219581, -1.4143819404669564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711528124479258, -0.07440282626085515, 0.27322782229325715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999040407115959, 0.0, 0.0, 0.0, -0.049767785395927244, 0.010527183332640223, -0.43093312314467225, -0.15529919643089174, -0.13067849264591677, -0.11897835160139353, -0.05585930215271177, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06723337076676547, 0.06947832036305181, 0.014799444664901483]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26785336458623626, 0.0, 0.0, 0.0, -0.12241441719596326, -0.05784494184522036, 0.49565619946225337, -0.19390851895850758, 1.0744775276487368, -0.15725695085755323, -1.4222674816128857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9733691848422911, -0.07159882519199075, 0.2734999822674431]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044824624656, 0.0, 0.0, 0.0, -0.015206282096589384, 0.1417964695677307, -0.28969637171552265, -0.07650095066232472, -0.09577926095788361, -0.2541445507119029, -0.15771082291858596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04432744788730506, 0.05608002137728803, 0.0054431994837189305]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26850331682321105, 0.0, 0.0, 0.0, -0.12216537933370626, -0.04789507485126157, 0.49152912033274715, -0.1914585523481791, 1.0751835258728315, -0.17374085283197277, -1.435813328014667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9745840056109065, -0.06941402047173197, 0.273523106393477]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044739496202, 0.0, 0.0, 0.0, 0.0049807572451400425, 0.1989973398791759, -0.08254158259012484, 0.048999332206569726, 0.014119964481894967, -0.3296780394883906, -0.27091692803562556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024296415372308804, 0.04369609440517576, 0.00046248252067780746]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685735988237808, 0.0, 0.0, 0.0, -0.12305063330397298, -0.03883516434149662, 0.49400978066073464, -0.18648357159412424, 1.0776344853741517, -0.19025145223005255, -1.4583515327851377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9752293446802045, -0.06707761161028665, 0.273922194320465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056400113951484, 0.0, 0.0, 0.0, -0.017705079405334258, 0.18119821019529897, 0.04961320655974957, 0.09949961508109746, 0.04901919002640491, -0.33021198796159545, -0.4507640954094163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012906781385959694, 0.046728177228906376, 0.007981758539760332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685680494466895, 0.0, 0.0, 0.0, -0.12406059669747342, -0.03441521031222953, 0.499348180447187, -0.18273357669315082, 1.078080406153933, -0.20307125960738243, -1.4880359556275422, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9760750139773863, -0.06502196047461477, 0.2748110184615617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098754182647767, 0.0, 0.0, 0.0, -0.02019926787000873, 0.08839908058534185, 0.10676799572904727, 0.07499989801946852, 0.008918415595627581, -0.2563961475465978, -0.5936884568480915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016913385943636308, 0.04111302271343776, 0.01777648282193446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685657289038691, 0.0, 0.0, 0.0, -0.12494473365539253, -0.036237859622744034, 0.5037943309699531, -0.1836983816275627, 1.0727713073061589, -0.21194787703928036, -1.5221509477682693, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9776776455752492, -0.06322579579794672, 0.2759020735274177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.641085640818318e-05, 0.0, 0.0, 0.0, -0.01768273915838234, -0.03645298621029003, 0.08892301045532225, -0.01929609868823716, -0.10618197695548287, -0.17753234863795891, -0.6822998428145429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03205263195725846, 0.035923293533360955, 0.021821101317119743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26856555112545394, 0.0, 0.0, 0.0, -0.12575973814404873, -0.04089553545256851, 0.5035983502414102, -0.18756019300334953, 1.058836867231935, -0.2187958994631828, -1.5593437168705004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9797032302196752, -0.0616578376223033, 0.27698101240682466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.555568303593545e-06, 0.0, 0.0, 0.0, -0.016300089773123652, -0.09315351659648952, -0.003919614570857613, -0.07723622751573661, -0.2786888014844763, -0.13696044847804895, -0.743855382044623, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04051169288852141, 0.03135916351286843, 0.021578777588139763]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268565580564015, 0.0, 0.0, 0.0, -0.12752924371210825, -0.04463829182513776, 0.495010238430804, -0.1928873919582791, 1.035974834358312, -0.22509163070746274, -1.6010979315166292, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9815795037391268, -0.05983121762938938, 0.2778456857734703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.887712221352959e-07, 0.0, 0.0, 0.0, -0.0353901113611904, -0.074855127451385, -0.1717622362121244, -0.10654397909859109, -0.4572406574724601, -0.1259146248855985, -0.8350842929225722, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.037525470389033484, 0.03653239985827841, 0.017293467332912444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26856558887551185, 0.0, 0.0, 0.0, -0.12812395147845995, -0.04371613292703018, 0.4817799955253769, -0.19592998377804816, 1.007935208681356, -0.23457100954992574, -1.643663591713776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.982877415718752, -0.058519343748966134, 0.2784616496713446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.662299361517475e-07, 0.0, 0.0, 0.0, -0.01189415532703425, 0.01844317796215167, -0.2646048581085416, -0.0608518363953813, -0.5607925135391192, -0.1895875768492601, -0.8513132039429374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02595823959250348, 0.02623747760846499, 0.012319277957486389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685655917460417, 0.0, 0.0, 0.0, -0.12526970460294906, -0.03828103130359932, 0.46765762152434637, -0.192958380246224, 0.9784679902006503, -0.25098400224482226, -1.68329069746257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9834914509686726, -0.05840325652943024, 0.2794538869832973]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.741059789166804e-08, 0.0, 0.0, 0.0, 0.057084937510217704, 0.10870203246861718, -0.2824474800206116, 0.05943207063648296, -0.5893443696141121, -0.3282598538979301, -0.7925421149758815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012280704998412264, 0.002321744390717787, 0.019844746239054308]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268565591942793, 0.0, 0.0, 0.0, -0.119363559815941, -0.032082986431909294, 0.4563931164255143, -0.18597731322860184, 0.9513231789147965, -0.2759114959845611, -1.716229248765284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9841988133606524, -0.05991131422319352, 0.2812794110553384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.935026102377918e-09, 0.0, 0.0, 0.0, 0.11812289574016112, 0.1239608974338005, -0.22529010197664168, 0.13962134035244325, -0.5428962257170787, -0.49854987479477636, -0.6587710260542775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01414724783959576, -0.03016115387526554, 0.03651048144082083]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26856559185623186, 0.0, 0.0, 0.0, -0.11156631226867404, -0.02887199821873325, 0.45173648022280527, -0.178736782725157, 0.9302507748210604, -0.30560349142562565, -1.7387292456282257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9856118928191073, -0.06288027029446329, 0.28397439603832764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7312234661301311e-09, 0.0, 0.0, 0.0, 0.15594495094533928, 0.06421976426352086, -0.0931327240541801, 0.14481061006889664, -0.42144808187472105, -0.5938399088212908, -0.4499999372588349, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02826158916909812, -0.05937912142539535, 0.05389969965978522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268428283599272, 0.0, 0.0, 0.0, -0.10353744778848128, -0.032398066022733166, 0.4546470167482712, -0.17498678800223172, 0.9190007772097162, -0.33630998863773404, -1.7470406884585261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9881622254363183, -0.06652947922735258, 0.28691385081540427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002746165139196418, 0.0, 0.0, 0.0, 0.16057728960385526, -0.07052135607999827, 0.05821073050931841, 0.07499989445850562, -0.22499995222688607, -0.6141299442421679, -0.16622885660600883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.051006652344217876, -0.0729841786577858, 0.05878909554153232]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2684103158440533, 0.0, 0.0, 0.0, -0.09590789773193015, -0.04212871852634535, 0.4613747779499957, -0.1766098341858334, 0.9154029479647217, -0.364280990813621, -1.7449135770556008, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9917335998398077, -0.07023629018782934, 0.28970425195067584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.000359355104374385, 0.0, 0.0, 0.0, 0.1525910011310227, -0.19461305007224378, 0.13455522403449008, -0.0324609236720335, -0.07195658489988935, -0.5594200435177387, 0.04254222805850438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0714274880697878, -0.0741362192095352, 0.05580802270543109]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2683580871799354, 0.0, 0.0, 0.0, -0.08869054127649784, -0.05437845602447167, 0.46889222968356015, -0.1830022774896997, 0.9162239085623636, -0.3887675432718657, -1.735993711007398, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9959487245622577, -0.07345693995832629, 0.29221293353553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0010445732823567092, 0.0, 0.0, 0.0, 0.14434712910864622, -0.24499474996252646, 0.15034903467128855, -0.12784886607732565, 0.016419211952837354, -0.48973104916489396, 0.17839732096405803, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08430249444900087, -0.06441299540993903, 0.05017363169708376]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268351662308612, 0.0, 0.0, 0.0, -0.08296452140775495, -0.06539727851844616, 0.48094937192273435, -0.1904141179172502, 0.9177136609658914, -0.4097275847284972, -1.724031090312019, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0000234805164536, -0.07577541457725127, 0.29381489636310953]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00012849742646767973, 0.0, 0.0, 0.0, 0.11452039737485759, -0.2203764498794899, 0.24114284478348358, -0.14823680855100996, 0.029795048070555552, -0.41920082913263, 0.23925241390757893, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08149511908391918, -0.046369492378499556, 0.03203925655159049]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26835200658202424, 0.0, 0.0, 0.0, -0.07798318720745022, -0.07143518604873789, 0.49833416540057324, -0.195095355560346, 0.9161230671800843, -0.42902749408480056, -1.7127757149177076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0031740991404532, -0.07677936209308113, 0.2944169474636089]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.885468244651263e-06, 0.0, 0.0, 0.0, 0.09962668400609478, -0.12075815060583436, 0.347695869556778, -0.09362475286191596, -0.031811875716140796, -0.38599818712606765, 0.22510750788622713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06301237247999109, -0.020078950316597163, 0.012041022009987336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26835219762418383, 0.0, 0.0, 0.0, -0.07342244958175721, -0.06874220468909563, 0.5172966108047267, -0.19620215976923075, 0.9130861700234868, -0.44784677079635893, -1.7059775751908284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.004920035211489, -0.07704500971892342, 0.2943742837478135]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.8208431916129355e-06, 0.0, 0.0, 0.0, 0.09121475251386016, 0.05385962719284523, 0.37924890808306944, -0.022136084177695317, -0.06073794313194882, -0.3763855342311671, 0.13596279453758597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03491872142071854, -0.005312952516845786, -0.0008532743159080022]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2683522149761813, 0.0, 0.0, 0.0, -0.06927504739117361, -0.059644229920488394, 0.5340867314829538, -0.19560505869825534, 0.9104742692394945, -0.46680203836995143, -1.7038372534545905, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0054870179969935, -0.07695692859782101, 0.29403911059192184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4703994927180757e-07, 0.0, 0.0, 0.0, 0.08294804381167192, 0.18195949537214473, 0.3358024135645431, 0.01194202141950823, -0.05223801567984529, -0.37910535147185037, 0.042806434724757175, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011339655710088499, 0.0017616224220480588, -0.006703463117832598]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2684049174206975, 0.0, 0.0, 0.0, -0.06549434127835235, -0.04789122970945867, 0.5476124662114051, -0.19449860872557168, 0.9102145370237033, -0.48700635667175723, -1.7040447848416123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0055584098581891, -0.07661408474259626, 0.2936752605694536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010540488903241644, 0.0, 0.0, 0.0, 0.07561412225642525, 0.23506000422059445, 0.2705146945690257, 0.022128999453673026, -0.005194644315824205, -0.4040863660361163, -0.004150627740436008, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014278372239113011, 0.00685687710449496, -0.007277000449365399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2684118114524429, 0.0, 0.0, 0.0, -0.06021009578935407, -0.03723320405531662, 0.5541238160646349, -0.19663280984971285, 0.9160569733612092, -0.507696068120875, -1.7028501693540123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0059132983951695, -0.07643351082617751, 0.2939077336052483]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013788063490849638, 0.0, 0.0, 0.0, 0.10568490977996552, 0.213160513082841, 0.13022699706459526, -0.04268402248282359, 0.11684872675011776, -0.4137942289823539, 0.023892309751998898, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007097770739605909, 0.0036114783283749665, 0.004649460715893895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26776185952469633, 0.0, 0.0, 0.0, -0.053759912902062466, -0.03142015284891521, 0.5544512006750153, -0.20575766188808028, 0.9317515750642483, -0.5251284006131761, -1.696503407190766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0073315201413389, -0.07683058615066723, 0.29516078900401815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999038554932046, 0.0, 0.0, 0.0, 0.12900365774583214, 0.11626102412802829, 0.0065476922076079525, -0.18249704076734896, 0.3138920340607835, -0.34864664984602195, 0.12693524326492484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.028364434923387746, -0.007941506489794383, 0.02506110797539717]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267111907310854, 0.0, 0.0, 0.0, -0.046000620850737486, -0.03374415142750001, 0.5519833367973961, -0.22461170517793413, 0.9557766953575156, -0.5383878186564345, -1.6812544983796953, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0104334309774916, -0.07768573461232883, 0.29703319022393915]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044276846597, 0.0, 0.0, 0.0, 0.15518584102649952, -0.04647997157169599, -0.04935727755238529, -0.3770808657970768, 0.4805024058653454, -0.2651883608651676, 0.30497817622141576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062038216723052944, -0.017102969233232006, 0.03744802439842002]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2664619551355365, 0.0, 0.0, 0.0, -0.0352536462415785, -0.040476657760763216, 0.5504702244252089, -0.2515734075001164, 0.9869967915660244, -0.5512243211770045, -1.657297074392315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0151809472494062, -0.07956984160817317, 0.29932554190243454]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043506350238, 0.0, 0.0, 0.0, 0.2149394921831797, -0.1346501266652641, -0.030262247443743454, -0.5392340464436455, 0.6244019241701746, -0.2567300504114007, 0.479148479747608, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0949503254382905, -0.037682139916886556, 0.04584703356990742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26639167295800076, 0.0, 0.0, 0.0, -0.021291603050552332, -0.04786767185088748, 0.5536618635312297, -0.28289276885583514, 1.0239728684676541, -0.5673878919426599, -1.628381135225704, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0209294667219884, -0.08249524913830973, 0.30141285302927623]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001405643550714309, 0.0, 0.0, 0.0, 0.2792408638205234, -0.14782028180248521, 0.0638327821204166, -0.626387227114375, 0.7395215380325935, -0.3232714153131089, 0.5783187833322203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11497038945164323, -0.05850815060273121, 0.04174622253683391]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26639722231388907, 0.0, 0.0, 0.0, -0.005686839251930935, -0.05216719369794628, 0.5626180916248719, -0.3148197892451369, 1.0629549260628668, -0.5873914787585406, -1.5982566808798093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0269509282722395, -0.08622522233789769, 0.3026701239037015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011098711776618363, 0.0, 0.0, 0.0, 0.312095275972428, -0.085990436941176, 0.17912456187284254, -0.6385404077860357, 0.7796411519042554, -0.40007173631761317, 0.6024890869178955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12042923100502412, -0.07459946399175912, 0.025145417488505833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26639954255246895, 0.0, 0.0, 0.0, 0.008691861514725818, -0.04962522330201289, 0.5735889087062288, -0.3436044686680505, 1.10019296435171, -0.6074850840838151, -1.570673711354606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0324579574727435, -0.09035778390808502, 0.30247235684232177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6404771597524926e-05, 0.0, 0.0, 0.0, 0.28757401533313504, 0.05083940791866773, 0.21941634162713863, -0.5756935884582719, 0.7447607657768647, -0.40187210650548905, 0.5516593905040659, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11014058401007938, -0.08265123140374656, -0.003955341227595201]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26704949479163353, 0.0, 0.0, 0.0, 0.020153094822954867, -0.03728323840558011, 0.5828243147755015, -0.36549680712985905, 1.1319369833343633, -0.6250353292203136, -1.549382226649861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0366611298820434, -0.09448879355597326, 0.3006891840361485]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044783292144, 0.0, 0.0, 0.0, 0.229224666164581, 0.24683969792865565, 0.18470812138545187, -0.4378467692361704, 0.6348803796530667, -0.3510049027299706, 0.42582969409490184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08406344818599779, -0.08262019295776457, -0.03566345612346435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26769944318618416, 0.0, 0.0, 0.0, 0.030072038233296187, -0.018891239001709373, 0.5867423440762979, -0.37974517005966635, 1.154436990334572, -0.6385649961519703, -1.5381322266121062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0388175281868934, -0.09833895826264186, 0.2979456054791525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998967891012932, 0.0, 0.0, 0.0, 0.19837886820682638, 0.3678399880774147, 0.07836058601592845, -0.284967258596146, 0.45000014000417354, -0.2705933386331343, 0.2250000007550928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.043127966096999884, -0.07700329413337216, -0.05487157113992009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26787923669365915, 0.0, 0.0, 0.0, 0.03793755401175139, 0.001800774976912032, 0.5856782034604381, -0.38868142179888104, 1.169281136514286, -0.6443240854017388, -1.5360035883738143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0391839341756397, -0.10198292311618605, 0.2948666211139144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003595870149499929, 0.0, 0.0, 0.0, 0.15731031556910402, 0.4138402795724281, -0.021282812317196823, -0.17872503478429363, 0.29688292359427926, -0.11518178499537035, 0.04257276476583702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007328119774925068, -0.07287929707088382, -0.06157968730476235]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678880134088109, 0.0, 0.0, 0.0, 0.04299643078460586, 0.02104281882378083, 0.5758862511295437, -0.3960098281066915, 1.174845654100042, -0.6427651217073023, -1.5392463139535622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.038392590253071, -0.10533462658552947, 0.29207722732095587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001755343030350738, 0.0, 0.0, 0.0, 0.10117753545708943, 0.3848408769373759, -0.1958390466178866, -0.14656812615620957, 0.11129035171512094, 0.03117927388873165, -0.06485451159495724, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015826878451372095, -0.06703406938686848, -0.05578787585917042]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678850831196126, 0.0, 0.0, 0.0, 0.04570931829439437, 0.035181482034803625, 0.5608912017976336, -0.40175774145510923, 1.1738780172908025, -0.6375952698356051, -1.544110405950442, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.037055429385431, -0.10824005166407545, 0.2901345658864022]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.860578396576032e-05, 0.0, 0.0, 0.0, 0.05425775019577019, 0.2827732642204559, -0.29990098663820175, -0.11495826696835415, -0.01935273618479222, 0.1033970374339426, -0.09728183993759557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026743217352798238, -0.05810850157091953, -0.03885322869107408]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26788450069637937, 0.0, 0.0, 0.0, 0.04670005651865394, 0.04484961842443636, 0.5440532303978588, -0.40596495287544265, 1.1690546868216118, -0.6306852242622094, -1.54854038059483, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0357986861224984, -0.11060017126285825, 0.28887555431455264]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1648464664827375e-05, 0.0, 0.0, 0.0, 0.019814764485191434, 0.19336272779265473, -0.3367594279954977, -0.08414422840666817, -0.09646660938381495, 0.13820091146791458, -0.08859949288775873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02513486525865578, -0.04720239197565592, -0.02518023143699065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678844910361218, 0.0, 0.0, 0.0, 0.04641403581955245, 0.051428580935713133, 0.5270505996193192, -0.40881045543496985, 1.1619168143388638, -0.6227716632188728, -1.5530169047520128, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0349511387552124, -0.11242576465375408, 0.28805851074598804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9320515213740755e-07, 0.0, 0.0, 0.0, -0.005720413982029732, 0.13157925022553546, -0.34005261557079125, -0.056910051190543876, -0.14275744965495887, 0.15827122086673276, -0.08953048314366016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016950947345717934, -0.036511867817916537, -0.01634087137129247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678845060355355, 0.0, 0.0, 0.0, 0.04517143946783047, 0.05607798243563867, 0.5104009230801457, -0.41056984719639483, 1.1531611660316217, -0.6142268712778277, -1.558247211099493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0343993821364026, -0.11384519660416094, 0.28750236510643806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.999882742460349e-07, 0.0, 0.0, 0.0, -0.024851927034439704, 0.09298802999851072, -0.3329935307834691, -0.03518783522850004, -0.17511296614484168, 0.17089583882090162, -0.10460612694960053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011035132376195491, -0.028388639008137363, -0.011122912790999025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678845108780542, 0.0, 0.0, 0.0, 0.04319054871543771, 0.05964536404842619, 0.4940361167643921, -0.41148572129540184, 1.1430046555639763, -0.6053279248701041, -1.5647344691777052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0340001747938279, -0.11497488275021778, 0.2870938422084732]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.68503747436812e-08, 0.0, 0.0, 0.0, -0.03961781504785512, 0.07134763225575042, -0.32729612631507354, -0.018317481980140285, -0.20313020935290543, 0.1779789281544714, -0.12974516156424612, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007984146851495436, -0.022593722921136893, -0.008170457959297137]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678845147273684, 0.0, 0.0, 0.0, 0.040600084947939416, 0.06278918089149538, 0.4776283739215182, -0.41169738473102385, 1.131385177479085, -0.5963297966566199, -1.572866366229264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0336534616533604, -0.11589925152952285, 0.28676533441927865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.698628396713673e-08, 0.0, 0.0, 0.0, -0.05180927534996594, 0.06287633686138369, -0.32815485685747753, -0.0042332687124397965, -0.23238956169782563, 0.17996256426968338, -0.16263794103117557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006934262809352433, -0.018487375586101355, -0.006570155783891655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26788452305016486, 0.0, 0.0, 0.0, 0.03744618275052417, 0.06613763662244682, 0.460701888045675, -0.41120685781121247, 1.1179987400446374, -0.58752101519294, -1.5831227610302945, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.033288796062019, -0.11667604404837935, 0.2864739415319033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6645592946057356e-07, 0.0, 0.0, 0.0, -0.06307804394830493, 0.06696911461902871, -0.33852971751686384, 0.009810538396227537, -0.26772874868895274, 0.1761756292735985, -0.20512789602061043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007293311826829159, -0.015535850377129875, -0.0058278577475065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267884524469445, 0.0, 0.0, 0.0, 0.03368209092220058, 0.07051016465781684, 0.44256981452210153, -0.4098180720856493, 1.1021585341139906, -0.5793462282347126, -1.5963977152001754, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.032834756174601, -0.11734251396874035, 0.28618572021553523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8385602844268588e-08, 0.0, 0.0, 0.0, -0.07528183656647193, 0.08745056070740048, -0.36264147047147033, 0.02777571451126344, -0.3168041186129354, 0.16349573916454793, -0.26549908339761963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00908079774836176, -0.013329398407219997, -0.005764426327361348]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267884528763144, 0.0, 0.0, 0.0, 0.029089508348207435, 0.07746905618259536, 0.42195962221292016, -0.4068942244603292, 1.0822252235217915, -0.572732094839798, -1.614832722324306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.03216291535436, -0.11791734450607745, 0.2858575963365481]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.58739804694152e-08, 0.0, 0.0, 0.0, -0.09185165147986288, 0.13917783049557028, -0.41220384618362804, 0.05847695250640192, -0.39866621184398304, 0.13228266789829207, -0.36870014248261385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013436816404819045, -0.011496610746742002, -0.006562477579742597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685344810027367, 0.0, 0.0, 0.0, 0.021613017257404197, 0.08557957641797231, 0.39685434161545646, -0.39868531493843834, 1.05444880903488, -0.5703744190640847, -1.6414452282529808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305896432412824, -0.1179493312582453, 0.2852848435263928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044791853955, 0.0, 0.0, 0.0, -0.14952982181606475, 0.1622104047075391, -0.5021056119492735, 0.16417819043781728, -0.5555282897382301, 0.04715351551426765, -0.5322501185734968, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146544226155234, -0.0006397350433571154, -0.011455056203106589]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2691844332414858, 0.0, 0.0, 0.0, 0.014253633762876729, 0.09109444448719291, 0.37100397272884394, -0.38144134352582393, 1.0225792906528823, -0.572632846295547, -1.6724852329912394, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0282179602939003, -0.11805848446789798, 0.2846265749896631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044774981313, 0.0, 0.0, 0.0, -0.14718766989054935, 0.1102973613844119, -0.5170073777322504, 0.3448794282522883, -0.6373903676399553, -0.0451685446292462, -0.6208000947651722, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04743365894764118, -0.0021830641930532992, -0.013165370734593037]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26925471516477245, 0.0, 0.0, 0.0, 0.009796314764779525, 0.09026366062663242, 0.348158515552932, -0.35582136899596556, 0.9903666683757127, -0.5816881497325312, -1.7042027365391854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0258231665439757, -0.11866991046736258, 0.2845077905791742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056384657339886, 0.0, 0.0, 0.0, -0.08914637996194409, -0.016615677211209795, -0.45690914351823875, 0.5123994905971669, -0.6442524455433916, -0.18110606873968543, -0.6343500709589192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047895874998495146, -0.01222851998929224, -0.0023756882097782112]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.269249165728663, 0.0, 0.0, 0.0, 0.008994361191690167, 0.07933722484350195, 0.33206797008665095, -0.3255753907754556, 0.961560942202706, -0.5957034741126928, -1.732847738897428, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.024182186373852, -0.12021005495711566, 0.2855534893339755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098872218996063, 0.0, 0.0, 0.0, -0.016039071461787194, -0.21852871566260962, -0.32181090932562095, 0.6049195529421507, -0.5761145234601329, -0.2803064876032311, -0.5729000471648507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.032819603402473085, -0.030802889795061465, 0.020913975096025855]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2686299453068434, 0.0, 0.0, 0.0, 0.010890949495971206, 0.05898186169259201, 0.3264823321310573, -0.29445341001096725, 0.9399121121317414, -0.6120152339715125, -1.7546702400663932, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.02407110123095, -0.12308100569532991, 0.2878680046096351]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012384408436390723, 0.0, 0.0, 0.0, 0.03793176608562079, -0.4071072630181988, -0.1117127591118732, 0.6224396152897669, -0.4329766014192924, -0.32623519717639443, -0.43645002337930267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002221702858041113, -0.05741901476428488, 0.04629030551319131]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2679799930667457, 0.0, 0.0, 0.0, 0.014245418054936551, 0.03263922777013159, 0.32765160168911084, -0.26620542612788334, 0.9291701780203717, -0.6319272895635404, -1.7659202400495617, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0260141530386926, -0.1268164225265875, 0.2908703247604604]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044801954596, 0.0, 0.0, 0.0, 0.0670893711793069, -0.5268526784492082, 0.023385391161070135, 0.5649596776616778, -0.21483868222739355, -0.3982411118405581, -0.22499999966337098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03886103615485048, -0.07470833662515211, 0.060046403016505615]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2673300408246939, 0.0, 0.0, 0.0, 0.018578757198493927, 0.004059323075045029, 0.331825778769018, -0.24458143912549185, 0.9255851419565458, -0.6548273871054273, -1.7640452400387698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0297704764135536, -0.13082496670453278, 0.2940646759983455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044841035097, 0.0, 0.0, 0.0, 0.08666678287114753, -0.5715980939017313, 0.08348354159814267, 0.43247974004782974, -0.07170072127651819, -0.4580019508377384, 0.037500000215839435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07512646749721894, -0.08017088355890531, 0.06388702475770235]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26725975890762743, 0.0, 0.0, 0.0, 0.02300589291177914, -0.023007852392911827, 0.34251490480253177, -0.22583144900523122, 0.9254070039417829, -0.6780046584625603, -1.75279524003389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.034559495763242, -0.1346826364423622, 0.2968260583281673]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056383413293266, 0.0, 0.0, 0.0, 0.08854271426570424, -0.5413435093591371, 0.213782520670276, 0.37499980240521236, -0.0035627602952602727, -0.4635454271426597, 0.22500000009759907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09578038699376834, -0.07715339475658853, 0.055227646596435545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672653082964447, 0.0, 0.0, 0.0, 0.02748395397159615, -0.044812298633939485, 0.35939869842199257, -0.2062054557682501, 0.924885763977933, -0.6999418721802724, -1.7359202400348155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0395953016012618, -0.1379763819420428, 0.2985294717530343]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011098777634474164, 0.0, 0.0, 0.0, 0.08956122119634018, -0.43608892482055317, 0.3376758723892157, 0.3925198647396224, -0.010424799276997791, -0.43874427435424057, 0.3374999999814902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10071611676039582, -0.06587490999361185, 0.03406826849733996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672676285340556, 0.0, 0.0, 0.0, 0.03219238678344218, -0.05760401565276381, 0.38102691995733606, -0.18889246297898166, 0.9202714221158639, -0.7209210492562389, -1.7171702400399795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0440906988811793, -0.14029977334240967, 0.2987650095494673]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6404752218913485e-05, 0.0, 0.0, 0.0, 0.09416865623692068, -0.25583434037648656, 0.43256443070687, 0.3462598557853689, -0.0922868372413827, -0.4195835415193303, 0.37499999989671906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08990794559835226, -0.04646782800733787, 0.004710755928659174]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672678061902681, 0.0, 0.0, 0.0, 0.03716875801516868, -0.058160612280034794, 0.40364956942242664, -0.17534984302157475, 0.9119399779433843, -0.7426507725665725, -1.7002952400094844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0474149830746284, -0.14173690921505055, 0.298157669785667]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5531242497408177e-06, 0.0, 0.0, 0.0, 0.09952742463453004, -0.011131932545419748, 0.45245298930181127, 0.2708523991481382, -0.16662888344959192, -0.43459446620667314, 0.33750000060990415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06648568386898279, -0.028742717452817538, -0.01214679527600538]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672677886598416, 0.0, 0.0, 0.0, 0.04221012062455142, -0.05023208802967201, 0.42352916140218994, -0.16735099118226843, 0.9031930820042944, -0.765637271686527, -1.6888550611191866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0495075221522128, -0.14257310348236066, 0.2972958166540949]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.50608529645171e-07, 0.0, 0.0, 0.0, 0.10082725218765476, 0.1585704850072557, 0.3975918395952661, 0.1599770367861263, -0.1749379187817994, -0.4597299823990891, 0.22880357780595745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04185078155168732, -0.016723885346202106, -0.017237062631442188]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26734020057211694, 0.0, 0.0, 0.0, 0.0471748921184952, -0.03756844127608076, 0.44043144948505003, -0.16409683483252555, 0.8961284398598326, -0.7906041440932654, -1.6812453867648127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.051029118984033, -0.14282640345577632, 0.2965839015199754]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014482382455073414, 0.0, 0.0, 0.0, 0.09929542987887564, 0.2532729350718249, 0.3380457616572023, 0.06508312699485769, -0.14129284288923646, -0.49933744813476827, 0.15219348708747682, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03043193663640763, -0.005065999468313593, -0.014238302682390173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2673496737492822, 0.0, 0.0, 0.0, 0.053407950211120804, -0.023919672019226637, 0.45060643367187764, -0.1693373739722041, 0.8944960515033644, -0.8143480563721461, -1.6737162169464406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0527607468155522, -0.14291026392618691, 0.29664692438066637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018946354330487089, 0.0, 0.0, 0.0, 0.124661161852512, 0.2729753851370824, 0.20349968373655186, -0.10481078279357098, -0.032647767129363583, -0.4748782455776147, 0.15058339636744347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03463255663038461, -0.001677209408211578, 0.0012604572138201781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267349270413409, 0.0, 0.0, 0.0, 0.060716823599136396, -0.013035780258000208, 0.45030415164943766, -0.1849544899156498, 0.9020459169196785, -0.8347188376894084, -1.6625175516666062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.055483176438664, -0.14323655997044038, 0.29783163255613987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.066717463969515e-06, 0.0, 0.0, 0.0, 0.14617746776031176, 0.21767783522452855, -0.006045640448799572, -0.3123423188689141, 0.15099730832628083, -0.40741562634524386, 0.22397330559668746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05444859246223539, -0.006525920885069489, 0.02369416350946983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666993182001273, 0.0, 0.0, 0.0, 0.06918975246137374, -0.008666765870488511, 0.44310173887093596, -0.2092187531418781, 0.9191281504958037, -0.850763021019942, -1.64389939093797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0598751515753833, -0.14424490287914335, 0.2997541717312688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044265633891, 0.0, 0.0, 0.0, 0.16945857724474692, 0.0873802877502339, -0.14404825557003353, -0.4852852645245656, 0.34164467152250333, -0.3208836666106708, 0.37236321457272503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08783950273438278, -0.020166858174059544, 0.038450783502578655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2660493680745376, 0.0, 0.0, 0.0, 0.07931083777804265, -0.0112032508467941, 0.4327466477073343, -0.24063015713242164, 0.9443814658989877, -0.8648835069993985, -1.61713425994735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.065768848811053, -0.14622362562767066, 0.3022065175804674]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299900251179483, 0.0, 0.0, 0.0, 0.20242170633337822, -0.05072969952611178, -0.2071018232720332, -0.6282280798108708, 0.5050663080636824, -0.282409719589131, 0.5353026198124031, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11787394471339796, -0.039574454970546236, 0.04904691698397297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2659790864415243, 0.0, 0.0, 0.0, 0.08988154005043986, -0.016895235187067877, 0.42282640181923664, -0.2754387018875065, 0.9740558631297752, -0.8804292683674004, -1.585972158694668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0723851056086113, -0.1487572542545514, 0.3045636701971443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056326602661963, 0.0, 0.0, 0.0, 0.2114140454479441, -0.11383968680547557, -0.19840491776195296, -0.6961708951016982, 0.5934879446157484, -0.310915227360038, 0.6232420250536403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13232513595116682, -0.05067257253761478, 0.04714305233353856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26598463582006526, 0.0, 0.0, 0.0, 0.1005426792323239, -0.021992718891490095, 0.4170910012049413, -0.3098943874073358, 1.0044013422306168, -0.8985706734331053, -1.5541630871797827, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0789400156206352, -0.1514401466710619, 0.3062006766701767]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011098757081907593, 0.0, 0.0, 0.0, 0.21322278363768093, -0.10194967408844437, -0.11470801228590674, -0.6891137103965859, 0.6069095820168339, -0.36282810131409715, 0.6361814302977065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13109820024047678, -0.053657848330209514, 0.03274012946064741]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.265986956050085, 0.0, 0.0, 0.0, 0.11004553941453311, -0.022745701960128418, 0.4192904456323106, -0.34024721369199673, 1.0316679032017129, -0.91606350647762, -1.525457045402653, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0846461697311, -0.15387312982907067, 0.3066349167344261]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6404600394674066e-05, 0.0, 0.0, 0.0, 0.19005720364418419, -0.015059661372766445, 0.0439888885473855, -0.6070565256932183, 0.5453312194219213, -0.3498566608902943, 0.574120835542591, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11412308220929764, -0.04865966316017532, 0.008684801284988285]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26645170931755635, 0.0, 0.0, 0.0, 0.11808485654125497, -0.015404189538562669, 0.42567473664782446, -0.36274718256441396, 1.052105551183496, -0.9327901824731928, -1.5036040326774196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0887662154040214, -0.15580955020504425, 0.3061375173192031]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009295065349427537, 0.0, 0.0, 0.0, 0.16078634253443716, 0.14683024843131492, 0.12768582031027698, -0.44999937744834423, 0.40875295963566144, -0.33453351991145475, 0.43706025450467034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0824009134584273, -0.03872840751947182, -0.009947988304460337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26651245478170627, 0.0, 0.0, 0.0, 0.12485400997473534, -0.002240363480865159, 0.43249388984173126, -0.37641158910368455, 1.0655646990812049, -0.9468752319172226, -1.49235404701758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0908605211992874, -0.1575791746567504, 0.3052237478342747]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0012149092829978215, 0.0, 0.0, 0.0, 0.13538306866960723, 0.26327652115395017, 0.1363830638781357, -0.2732881307854116, 0.26918295795417496, -0.28170098888059564, 0.22499971319679335, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04188611590531978, -0.03539248903412296, -0.01827538969856722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650987715918983, 0.0, 0.0, 0.0, 0.13045128949025236, 0.012998209742899685, 0.4390684470008469, -0.38395654840750587, 1.07473673649581, -0.9583882860898785, -1.4890689643040282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915149373302167, -0.15917698368703545, 0.30421689359418935]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.155245032836169e-05, 0.0, 0.0, 0.0, 0.11194559031034036, 0.30477146447529685, 0.1314911431823128, -0.1508991860764266, 0.18344074829210388, -0.23026108345311927, 0.06570165427103683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013088322618584253, -0.03195618060570103, -0.0201370848017068]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650817774269087, 0.0, 0.0, 0.0, 0.13465775701949295, 0.02758872767393902, 0.44386480315165316, -0.38765268695102595, 1.0801743857550692, -0.9669865528785562, -1.4906704246464735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091374534237445, -0.16056735725836377, 0.3032821783469575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.398832997986964e-05, 0.0, 0.0, 0.0, 0.0841293505848115, 0.2918103586207867, 0.09592712301612491, -0.07392277087040194, 0.1087529851851813, -0.17196533577355455, -0.032029206848906214, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002808061855433811, -0.027807471426566453, -0.018694304944637297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650801389506806, 0.0, 0.0, 0.0, 0.13652320198273493, 0.03984645679054772, 0.4431329716366639, -0.38952518044809853, 1.0781276674822544, -0.9702801150218332, -1.4965825306653382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0910792508765204, -0.1617111529092108, 0.302494627699685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.276952455996106e-06, 0.0, 0.0, 0.0, 0.037308899264839324, 0.245154582332174, -0.014636630299785597, -0.03744986994145168, -0.040934365456297125, -0.06587124286554033, -0.1182421203772961, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005905667218492524, -0.02287591301694061, -0.015751012945449602]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650803118988836, 0.0, 0.0, 0.0, 0.13666704482363795, 0.05008067345029109, 0.4368678244660211, -0.3901706510562476, 1.0701030944865366, -0.9701011564872696, -1.5051706319344276, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0907575862402097, -0.16263451250884597, 0.3018495883197592]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.458964064437773e-07, 0.0, 0.0, 0.0, 0.002876856818060443, 0.20468433319486734, -0.125302943412855, -0.012909412162981061, -0.1604914599143541, 0.003579170691273517, -0.17176202538178553, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0064332927262117055, -0.01846719199270374, -0.012900787598515191]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665080978805647, 0.0, 0.0, 0.0, 0.13568531702724146, 0.05914434915414227, 0.42725388003563197, -0.38971459154112875, 1.0586131074142202, -0.9684068699763376, -1.5155581877737405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0903957821890682, -0.16338066031397486, 0.3013166444802918]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3338135262684832e-06, 0.0, 0.0, 0.0, -0.019634555927929745, 0.18127351407702347, -0.19227888860778286, 0.00912119030237735, -0.22979974144633025, 0.03388573021863844, -0.20775111678625907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007236081022829653, -0.014922956102577895, -0.01065887678934925]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665081863534346, 0.0, 0.0, 0.0, 0.13391103084956862, 0.06795480547931773, 0.4157879777469817, -0.38811134525111096, 1.0450879208182193, -0.9665444965990493, -1.5276315614571991, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899599595868004, -0.16398814343855117, 0.30086138408588115]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7694573978541509e-06, 0.0, 0.0, 0.0, -0.03548572355345654, 0.1762091265035094, -0.22931804577300557, 0.032064925800355436, -0.2705037319200173, 0.037247467545766466, -0.24146747366917187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00871645204535687, -0.012149662491526091, -0.00910520788821287]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665461799089997, 0.0, 0.0, 0.0, 0.13146126483273446, 0.07652825355701467, 0.4033085088511127, -0.38493420886485125, 1.030109522441329, -0.9653533812905258, -1.5426434886649438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0894425177304805, -0.16447574832831285, 0.3004563918844879]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007598711113021792, 0.0, 0.0, 0.0, -0.04899532033668302, 0.17146896155393884, -0.24958937791737912, 0.06354272772519484, -0.29956796753780474, 0.023822306170469723, -0.3002385441548945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010348837126396788, -0.009752097795233455, -0.008099844027864473]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26666554148599386, 0.0, 0.0, 0.0, 0.12830129192905287, 0.08399149483096947, 0.39032995285917793, -0.37922906302824866, 1.0137527008210865, -0.9653894799001311, -1.563471781331054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.08883459839963, -0.1648471955320758, 0.30007671002592917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023872315398834527, 0.0, 0.0, 0.0, -0.06319945807363181, 0.1492648254790959, -0.259571119838695, 0.11410291673205217, -0.3271364324048506, -0.0007219721921052878, -0.41656585332220303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012158386617011855, -0.007428944075259162, -0.007593637171174897]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26728141662187876, 0.0, 0.0, 0.0, 0.12362690604217573, 0.08790674566505206, 0.377660390136164, -0.36724591972114223, 0.9935813288175968, -0.968288932200734, -1.5919881189700735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0877719270490034, -0.1650705714123232, 0.2996123806173295]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01231750271769835, 0.0, 0.0, 0.0, -0.09348771773754293, 0.0783050166816517, -0.2533912544602793, 0.2396628661421287, -0.4034274400697956, -0.05798904601205637, -0.5703267527803932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021253427012531825, -0.00446751760494782, -0.00928658817199441]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2679313688641265, 0.0, 0.0, 0.0, 0.11672231334943953, 0.08895280918422309, 0.3690498205105754, -0.34600996860866495, 0.9658454065507099, -0.9720786424499401, -1.626801189077347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0857484200495358, -0.16464695637973825, 0.29884700218737964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044844954996, 0.0, 0.0, 0.0, -0.138091853854724, 0.020921270383420384, -0.17221139251177167, 0.4247190222495453, -0.5547184453377353, -0.07579420498412379, -0.6962614021454696, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04047013998935348, 0.008472300651699011, -0.015307568598996395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685813209868043, 0.0, 0.0, 0.0, 0.10954378873053226, 0.08632890300778437, 0.36824824319515637, -0.31927120912332546, 0.9342949205563862, -0.9746179452513145, -1.666651645003287, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.083023045803578, -0.16301433752773437, 0.29795106993247233]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042453556677, 0.0, 0.0, 0.0, -0.1435704923781454, -0.05247812352877451, -0.016031546308380135, 0.5347751783570656, -0.6310097198864753, -0.05078605602748728, -0.7970091185188022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.054507484919151944, 0.032652377040077986, -0.017918645098145985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2686516005904908, 0.0, 0.0, 0.0, 0.10428669769076393, 0.07628502935485647, 0.3778661248090947, -0.2907796419992226, 0.9026798680829154, -0.9749350605070586, -1.7077894870913664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0803772640896978, -0.16058746384860462, 0.29754491614625755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014055920737299395, 0.0, 0.0, 0.0, -0.10514182079536669, -0.2008774730585581, 0.19235763227876723, 0.569831342482057, -0.6323010494694157, -0.0063423051148813955, -0.8227568417615871, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05291563427760489, 0.0485374735825949, -0.008123075724295943]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2680016483551084, 0.0, 0.0, 0.0, 0.10120005714688729, 0.05666513464448504, 0.3941534653575288, -0.26428526666878654, 0.8747502491298513, -0.9738854034217097, -1.7464647153416544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0785893570405622, -0.15778290809208018, 0.2981955306441437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904470764783, 0.0, 0.0, 0.0, -0.061732810877532934, -0.39239789420742854, 0.32574681096868274, 0.5298875066087217, -0.5585923790612817, 0.02099314170697731, -0.7735045650057581, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03575814098271052, 0.05609111513048871, 0.013012289957723605]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26735169611146326, 0.0, 0.0, 0.0, 0.0998178908111847, 0.0295421638946813, 0.4133602648408667, -0.2435380831318183, 0.8542560636761456, -0.9716952597636777, -1.7789273297542452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0784322110847508, -0.1550145897605769, 0.2998406061759964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044872903367, 0.0, 0.0, 0.0, -0.027643326714051994, -0.5424594149960748, 0.384135989666757, 0.4149436707393648, -0.40988370907411387, 0.043802873160641013, -0.6492522882518164, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0031429191162277333, 0.05536636663006559, 0.03290151063705326]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2667017438697361, 0.0, 0.0, 0.0, 0.1001433583102512, -0.0013338828950555381, 0.4317365232665286, -0.23228809137699552, 0.8446761278672981, -0.9718978569206328, -1.801427330329476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.080208217203486, -0.1528358414127333, 0.30222599318340193]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044834542712, 0.0, 0.0, 0.0, 0.00650934998133007, -0.6175209357947367, 0.36752516851323896, 0.22499983509645563, -0.19159871617695112, -0.004051943139103384, -0.4500000115046202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03552012237470164, 0.04357496695687174, 0.04770774014811027]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663145878135147, 0.0, 0.0, 0.0, 0.1003896990353625, -0.03221302221213588, 0.4495087733319046, -0.22678535658697724, 0.8422605188034552, -0.9782431100087028, -1.8177145525521616, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0832051460660506, -0.15080666112179647, 0.3047267424477459]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014057017676928265, 0.0, 0.0, 0.0, 0.004926814502226014, -0.6175827863416068, 0.3554450013075192, 0.1100546958003655, -0.048312181276856714, -0.12690506176140057, -0.32574444445370865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05993857725129234, 0.04058360581873642, 0.05001498528687954]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663701285766606, 0.0, 0.0, 0.0, 0.10066821527059135, -0.059345319480718445, 0.46795462079216266, -0.2232800766204568, 0.8447696823538957, -0.9893224560443802, -1.8315389503451034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.086715213005737, -0.1487528885116559, 0.30671856726873703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011108152629218829, 0.0, 0.0, 0.0, 0.005570324704576973, -0.5426459453716512, 0.3689169492051616, 0.07010559933040919, 0.05018327100881037, -0.2215869207135483, -0.2764879558588347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0702013387937271, 0.04107545220281098, 0.03983649641982247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666393348969601, 0.0, 0.0, 0.0, 0.10106625856097351, -0.0789811700823969, 0.4859279750664324, -0.21949268893248491, 0.8504107768447529, -1.0018168073624552, -1.8466503729488057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0901412217082123, -0.14685547234691923, 0.30804024879157227]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.644078588155616e-05, 0.0, 0.0, 0.0, 0.007960865807643372, -0.3927170120335691, 0.35946708548539574, 0.07574775375943775, 0.11282188981714397, -0.24988702636149876, -0.30222845207404747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06852017404950696, 0.037948323294733535, 0.026433630456705208]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666395126421156, 0.0, 0.0, 0.0, 0.10151917057584567, -0.09096536996056655, 0.5021154127540256, -0.21625335040936575, 0.8586376931413159, -1.0138747924524636, -1.8628949719753696, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.092892375155402, -0.14531665009654368, 0.30884473506810733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.554903110104712e-06, 0.0, 0.0, 0.0, 0.009058240297443152, -0.2396839975633929, 0.32374875375186407, 0.06478677046238328, 0.16453832593125972, -0.24115970180016766, -0.32489198053127477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05502306894379624, 0.030776445007510755, 0.016089725530701524]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663948310447894, 0.0, 0.0, 0.0, 0.10199896648580115, -0.09745289120196635, 0.5160305093123795, -0.21387645984880052, 0.8683736623579553, -1.0254458895115903, -1.8781802723931698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0948532708576688, -0.1441345547822357, 0.30932463884584244]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907527334535394e-07, 0.0, 0.0, 0.0, 0.009595918199109509, -0.12975042482799598, 0.2783019311670768, 0.04753781121130425, 0.19471938433278854, -0.23142194118253395, -0.3057060083560046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.039217914045336366, 0.02364190628615989, 0.00959807555470248]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394749221178, 0.0, 0.0, 0.0, 0.10250291276434123, -0.10029625955514684, 0.5278037406056814, -0.21230141392716348, 0.878831873912644, -1.0369847058741137, -1.8911470338992138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.096251360829597, -0.1431893674730238, 0.3096244347067119]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6364722233934188e-07, 0.0, 0.0, 0.0, 0.01007892557080161, -0.05686736706361008, 0.23546462586603673, 0.031500918432740985, 0.20916423109377233, -0.23077632725047026, -0.25933523012087856, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027961799438562425, 0.018903746184238047, 0.005995917217389561]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947445039915, 0.0, 0.0, 0.0, 0.10303521376321989, -0.10073400735190223, 0.5378115622510466, -0.21135050183611298, 0.8895404049215837, -1.048897898220159, -1.9013420621546255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0973195155287607, -0.14237014097222597, 0.3098349992986931]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.434373712878155e-09, 0.0, 0.0, 0.0, 0.010646019977573178, -0.008754955935107625, 0.20015643290730634, 0.019018241821010154, 0.21417062017879587, -0.2382638469209087, -0.2039005651082354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021363093983276005, 0.016384530015956262, 0.004211291839624496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394744803509, 0.0, 0.0, 0.0, 0.1035744501797725, -0.09940582361540297, 0.5460806789377122, -0.21086393963492173, 0.9007521518355773, -1.0615263475782342, -1.908811016539398, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.098222297250128, -0.14160265492798974, 0.3100074373788788]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.990351826313005e-10, 0.0, 0.0, 0.0, 0.010784728331052153, 0.02656367472998524, 0.16538233373331096, 0.009731244023825199, 0.22423493827987162, -0.25256898716149906, -0.149379087695453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01805563442734626, 0.015349720884724733, 0.003448761603714218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394744980217, 0.0, 0.0, 0.0, 0.1041376044930153, -0.09678128062280042, 0.552898682656787, -0.21078042593764734, 0.912221670666274, -1.075108040923779, -1.913878862912966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0990878398188548, -0.14082473494293618, 0.31017517162864056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5341606329656277e-10, 0.0, 0.0, 0.0, 0.011263086264856028, 0.05249085985205092, 0.13636007438149636, 0.0016702739454878077, 0.22939037661393472, -0.2716338669108946, -0.10135692747135597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01731085137453581, 0.01555839970107092, 0.00335468499523483]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947469190663, 0.0, 0.0, 0.0, 0.10475113924275939, -0.09313250334395277, 0.5585958113039441, -0.21111173608415368, 0.9236329839616089, -1.0899769087187847, -1.9168992577640986, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1000283664753507, -0.13997562096400307, 0.31036370424577114]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.877698386723558e-09, 0.0, 0.0, 0.0, 0.012270694994881804, 0.07297554557695296, 0.11394257294314156, -0.006626202930126687, 0.22822626590669687, -0.2973773559001125, -0.06040789702265616, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018810533129916214, 0.016982279578662333, 0.0037706523426117985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394747384194, 0.0, 0.0, 0.0, 0.10544734103966462, -0.0885293516690003, 0.5634293707154018, -0.2119510158948703, 0.9346379340855314, -1.1067951180099072, -1.918131772821261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1011742403059177, -0.13897479027663898, 0.3106003258346873]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.302561045884131e-10, 0.0, 0.0, 0.0, 0.013924035938104477, 0.09206303349904948, 0.09667118822915322, -0.01678559621433242, 0.22009900247845024, -0.33636418582244876, -0.024650301143245325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022917476611338188, 0.020016613747281843, 0.004732431778322373]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947482430383, 0.0, 0.0, 0.0, 0.10628750632194282, -0.08270416728780662, 0.5675233070829718, -0.21356522344892667, 0.9446931563219226, -1.127143991421212, -1.9176399243147473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1027535693918114, -0.13766703995064183, 0.3109321384918999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7176884297616065e-09, 0.0, 0.0, 0.0, 0.016803305645564075, 0.11650368762387371, 0.08187872735140111, -0.03228415108112746, 0.2011044447278249, -0.40697746822609626, 0.009836970130274764, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.031586581717873985, 0.026155006519942833, 0.0066362531442522585]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394750031692, 0.0, 0.0, 0.0, 0.10723259841335893, -0.07586443302824697, 0.5711059670323481, -0.21588617458598264, 0.953861132867947, -1.1507169923517677, -1.9155953144259321, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.10477859921867, -0.13605752488766693, 0.3113597282582764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.577307397365356e-09, 0.0, 0.0, 0.0, 0.018901841828322066, 0.13679468519119306, 0.07165319898752551, -0.04641902274111955, 0.18335953092048912, -0.47146001861111553, 0.04089219777630271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040500596537176116, 0.03219030125949828, 0.008551795327530504]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947391426773, 0.0, 0.0, 0.0, 0.10865942933995708, -0.07176014875249087, 0.5704273509193154, -0.2226638675960555, 0.9583918639217596, -1.1737641209217982, -1.9082479434287793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1079607645274099, -0.13431765715345406, 0.31225820748069516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1778028852162315e-08, 0.0, 0.0, 0.0, 0.028536618531963057, 0.08208568551512205, -0.013572322260652997, -0.1355538602014572, 0.0906146210762515, -0.46094257140061023, 0.14694741994305338, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06364330617479678, 0.034797354684257265, 0.01796958444837487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663112093558483, 0.0, 0.0, 0.0, 0.11027409814355077, -0.07414131241423617, 0.5647859895171783, -0.2330747114197279, 0.9586646977241573, -1.1925353772853342, -1.8923501355117325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.111927299926172, -0.13262485006143357, 0.31336316022259253]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0001670595736584105, 0.0, 0.0, 0.0, 0.03229337607187374, -0.047623273234906116, -0.11282722804274309, -0.20821687647344822, 0.005456676047955619, -0.37542512727072297, 0.31795615834093655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07933070797524053, 0.033856141840409915, 0.02209905483794688]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665729533781325, 0.0, 0.0, 0.0, 0.11209662238980313, -0.08064335120819682, 0.5572353646644999, -0.24596585946947658, 0.9574012102468038, -1.2050367284324257, -1.869260795220862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1161728880092183, -0.13102792739809824, 0.3145060657513225]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011633511490462473, 0.0, 0.0, 0.0, 0.03645048492504721, -0.13004077587921303, -0.15101249705356914, -0.2578229609949733, -0.025269749547069398, -0.25002702294183066, 0.4617868058174091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08491176166092719, 0.03193845326670661, 0.022858110574599782]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665655334932147, 0.0, 0.0, 0.0, 0.11430989209163614, -0.08751626513610261, 0.551525476301931, -0.2575873117492882, 0.9583514011242869, -1.2143878047284404, -1.8427299225554783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.120137761290782, -0.1298249453901871, 0.3150619241168444]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00014839769835631135, 0.0, 0.0, 0.0, 0.04426539403666038, -0.13745827855811565, -0.11419776725137558, -0.23242904559623215, 0.01900381754966158, -0.18702152592029314, 0.5306174533076717, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07929746563127339, 0.0240596401582226, 0.01111716731043802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26656588231141, 0.0, 0.0, 0.0, 0.11665870778568183, -0.09306539416236148, 0.5512407506352881, -0.2656888694296548, 0.9652652550290952, -1.2207129665355423, -1.8165075169741374, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1232140844241048, -0.12916738707117403, 0.3151512416882477]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.9763639052446245e-06, 0.0, 0.0, 0.0, 0.04697631388091366, -0.11098258052517734, -0.0056945133328581005, -0.16203115360733247, 0.1382770780961669, -0.1265032361420368, 0.5244481116268199, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06152646266645549, 0.013151166380261205, 0.0017863514280658868]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26656609628160016, 0.0, 0.0, 0.0, 0.11873341763145234, -0.09354074957168348, 0.5541901095692269, -0.26773828995836224, 0.9751935851927864, -1.2263234009311401, -1.7943435761581585, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1247651852460623, -0.12911934008385495, 0.31475238201008143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.27940380375049e-06, 0.0, 0.0, 0.0, 0.04149419691541047, -0.00950710818644003, 0.058987178678774635, -0.04098841057414922, 0.19856660327382422, -0.1122086879119565, 0.44327881631957866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.031022016439150257, 0.0009609397463816553, -0.007977193563325016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665661163703244, 0.0, 0.0, 0.0, 0.12029367255144623, -0.08897512639969976, 0.5583093217689795, -0.2661175847189831, 0.9860490494462002, -1.2326694659354682, -1.7799880898911347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.124993528837271, -0.12946907370462055, 0.3141244588885657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.0177448482741343e-07, 0.0, 0.0, 0.0, 0.031205098399877576, 0.09131246343967446, 0.08238424399505269, 0.03241410478758261, 0.21710928506827631, -0.12692130008656408, 0.2871097253404775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004566871824174354, -0.006994672415312128, -0.012558462430313902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26656611426012494, 0.0, 0.0, 0.0, 0.12140860503693514, -0.08093946354724181, 0.5625433647990794, -0.263380120082581, 0.9967065781364572, -1.2408256349942755, -1.7722594960880946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1244587143820655, -0.1299159472178867, 0.31351420090667553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.220398944589155e-08, 0.0, 0.0, 0.0, 0.022298649709778257, 0.16071325704915906, 0.08468086060199743, 0.05474929272804286, 0.21315057380514052, -0.16312338117614517, 0.15457187606080014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010696289104109857, -0.008937470265323284, -0.012205159637803139]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26659687367740176, 0.0, 0.0, 0.0, 0.12203534824559277, -0.07067589824227796, 0.5664280901444293, -0.26061309543780914, 1.0063229247224652, -1.252901838734886, -1.7681370241177639, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1237138679863203, -0.13013871840631835, 0.31313111853589076]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006151883455367837, 0.0, 0.0, 0.0, 0.012534864173152627, 0.20527130609927693, 0.07769450690699686, 0.05534049289543743, 0.1923269317201573, -0.2415240748122098, 0.08244943940661416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014896927914903466, -0.0044554237686326836, -0.007661647415695828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666008979926753, 0.0, 0.0, 0.0, 0.12177275055561299, -0.05807443302727744, 0.5662135594415285, -0.25636078146715124, 1.0111481260218944, -1.2651480931702654, -1.771088187183669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1229549194196509, -0.130543171332653, 0.3128518990146296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.04863054709588e-05, 0.0, 0.0, 0.0, -0.005251953799595598, 0.25202930430001047, -0.004290614058015119, 0.08504627941315808, 0.096504025988582, -0.2449250887075872, -0.05902326131810244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015178971333388695, -0.008089058526692911, -0.005584390425223259]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666007510666907, 0.0, 0.0, 0.0, 0.12100280862888602, -0.04526934340964283, 0.5603666017652729, -0.251526664499642, 1.009913251422739, -1.2738152461760386, -1.7788392941006013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1221218740693075, -0.13121248376351222, 0.31260484406327055]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9385196917752006e-06, 0.0, 0.0, 0.0, -0.01539883853453951, 0.25610179235269215, -0.11693915352511344, 0.09668233935018507, -0.024697491983109054, -0.17334306011546274, -0.15502213833864364, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01666090700686577, -0.01338624861718422, -0.004941099027181387]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666848100756695, 0.0, 0.0, 0.0, 0.1199574079682994, -0.03371951263850336, 0.551531415170722, -0.2462664246414506, 1.0047330815632545, -1.2774814331579278, -1.7928485007855726, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1212609276320598, -0.13201021098312754, 0.31237340901825184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016811801795773593, 0.0, 0.0, 0.0, -0.02090801321173233, 0.2309966154227894, -0.17670373189101793, 0.10520479716382841, -0.10360339718969075, -0.07332373963778388, -0.2801841336994271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01721892874495362, -0.015954544392306473, -0.0046287009003737195]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2673347622718793, 0.0, 0.0, 0.0, 0.11865122438732395, -0.024030130294738897, 0.5434579992235014, -0.23683006194940895, 0.9971435604710508, -1.2790764761625824, -1.8157728396034851, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1203187623303152, -0.13284064164857118, 0.31213266422047764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904392419585, 0.0, 0.0, 0.0, -0.02612367161950905, 0.19378764687528932, -0.16146831894441435, 0.18872725384083294, -0.15179042184407257, -0.031900860093091066, -0.4584867763582513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018843306034891618, -0.016608613308873012, -0.004814895955483367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267417901791194, 0.0, 0.0, 0.0, 0.11902230517772423, -0.01995119632189494, 0.5358855538820204, -0.22696757638535278, 0.9908946879467333, -1.2808863187324109, -1.8438623105702705, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1200824984091418, -0.1341069017486618, 0.3123133084187358]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016627903862944174, 0.0, 0.0, 0.0, 0.0074216158080056965, 0.08157867945687913, -0.1514489068296178, 0.19724971128112317, -0.12497745048634938, -0.03619685139657097, -0.5617894193357071, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004725278423468242, -0.025325202001812486, 0.0036128839651624056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26676794954895106, 0.0, 0.0, 0.0, 0.12166656484254655, -0.025232710719865332, 0.5250640792485602, -0.22042896794922842, 0.9897364639899123, -1.2834635398719514, -1.8733669136859443, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1213403956761445, -0.136210589434846, 0.3130765427891761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044844858806, 0.0, 0.0, 0.0, 0.05288519329644632, -0.1056302879594079, -0.21642949266920317, 0.13077216872248743, -0.02316447913642021, -0.05154442279080832, -0.5900920623134763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025157945340053757, -0.04207375372368444, 0.01526468740880673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26611799742068276, 0.0, 0.0, 0.0, 0.12578515940349042, -0.03869112004879706, 0.5072435960886068, -0.2209642364473661, 0.9974188880018383, -1.2858962439721608, -1.9005366489680777, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1243700683666964, -0.1388888171362498, 0.31423990260231954]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999042565365907, 0.0, 0.0, 0.0, 0.08237189121887734, -0.2691681865786345, -0.35640966319906897, -0.01070536996275362, 0.15364848023852062, -0.04865408200418961, -0.5433947056426673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06059345381103688, -0.05356455402807532, 0.023267196262868835]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26546804518680944, 0.0, 0.0, 0.0, 0.13075018130111515, -0.05657642431246232, 0.48297273742143093, -0.23232338181811893, 1.0119183324996015, -1.2879729767645547, -1.9216215164222221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1287291581252799, -0.14162405911959472, 0.3156199152378934]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044677466806, 0.0, 0.0, 0.0, 0.09930043795249452, -0.3577060852733051, -0.48541717334351786, -0.22718290741505645, 0.28998888995526245, -0.04153465584787596, -0.4216973490828876, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08718179517167013, -0.05470483966689882, 0.02760025271147748]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26481809299343073, 0.0, 0.0, 0.0, 0.135818968472395, -0.0751386235201285, 0.45559596792010215, -0.2523273539266939, 1.029484797501975, -1.2918491914925134, -1.932871516063369, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1341689123566445, -0.1438356262809585, 0.31719308234527926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904386757372, 0.0, 0.0, 0.0, 0.10137574342559665, -0.37124398415332344, -0.5475353900265761, -0.40007944217149927, 0.35132930004747, -0.07752429455917591, -0.22499999282293798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10879508462729372, -0.044231343227275566, 0.03146334214771683]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26474781076378506, 0.0, 0.0, 0.0, 0.14060011729301136, -0.0906277177018237, 0.42886328745564545, -0.277226152783736, 1.0527379302855, -1.30000824604525, -1.9380366478782074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1398978798105304, -0.14512438020162943, 0.31843549499344914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056445929130704, 0.0, 0.0, 0.0, 0.09562297641232702, -0.3097818836339041, -0.5346536092891339, -0.4979759771408415, 0.46506265567050176, -0.163181091054731, -0.10330263629676915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11457934907771532, -0.025775078413418917, 0.024848252963397918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475336198326654, 0.0, 0.0, 0.0, 0.14593744984608215, -0.09929382794533224, 0.4065246674569948, -0.3032697816340956, 1.0788418743028663, -1.3087001795186268, -1.9408669086119057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1454728142690553, -0.14615455240260572, 0.318729443041711]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011102438962940072, 0.0, 0.0, 0.0, 0.10674665106141537, -0.17332220487017067, -0.4467723999730137, -0.5208725770071918, 0.5220788803473267, -0.1738386694675371, -0.056605214673967945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11149868917049918, -0.020603444019525664, 0.005878960965238145]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475568247334863, 0.0, 0.0, 0.0, 0.15113248240327118, -0.10300930815599448, 0.391918430165455, -0.3267082437849521, 1.1045703119431944, -1.3148458242623713, -1.9451122961155005, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.150289226977121, -0.14709371681787667, 0.3184515016600449]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6409801641558184e-05, 0.0, 0.0, 0.0, 0.10390065114378041, -0.07430960421324469, -0.2921247458307956, -0.4687692430171295, 0.5145687528065628, -0.12291289487488968, -0.08490775007189472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09632825416131231, -0.01878328830541886, -0.005558827633323268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475585939415497, 0.0, 0.0, 0.0, 0.1557595325640012, -0.10427926184610248, 0.3839272248065305, -0.34513218754787406, 1.1280210112986042, -1.3190541266713047, -1.9513351349853454, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1538211978124717, -0.14803428605984023, 0.3179542479553117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.538416126590643e-06, 0.0, 0.0, 0.0, 0.09254100321460045, -0.025399073802160055, -0.1598241071784906, -0.36847887525843925, 0.46901398710819336, -0.08416604817866853, -0.12445677739689606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07063941670701401, -0.018811384839271427, -0.009945074094664006]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558295821085, 0.0, 0.0, 0.0, 0.15958299641283583, -0.1039096139271208, 0.38073863529279217, -0.35835464332263395, 1.1482155265850664, -1.3226050966802707, -1.9596537804434433, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1561227720412133, -0.14895503079596983, 0.3173980767623391]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.962409291951285e-07, 0.0, 0.0, 0.0, 0.07646927697669201, 0.007392958379633649, -0.0637717902747666, -0.2644491154951975, 0.4038903057292426, -0.07101940017931986, -0.16637290916195768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04603148457483186, -0.01841489472259184, -0.011123423859451843]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475581554977595, 0.0, 0.0, 0.0, 0.16265616411282718, -0.10269688849069691, 0.3809062433273441, -0.367478584409937, 1.1652728078396457, -1.326112684408923, -1.9687258566556634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1575137478171047, -0.14979371930473845, 0.3168727558922333]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.806466512971204e-07, 0.0, 0.0, 0.0, 0.06146335399982743, 0.024254508728477515, 0.00335216069103815, -0.18247882174606134, 0.34114562509158686, -0.07015175457304522, -0.18144152424440052, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027819515517827964, -0.016773770175372207, -0.010506417402115886]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264755813025721, 0.0, 0.0, 0.0, 0.16514459481174038, -0.10135686416622813, 0.3834151663969018, -0.37383777163558324, 1.1797935015316907, -1.3297155596236636, -1.976997251546014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158334486209964, -0.15049953255602447, 0.3164258923415723]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.048109882255089e-08, 0.0, 0.0, 0.0, 0.04976861397826402, 0.026800486489375747, 0.050178461391155144, -0.12718374451292472, 0.29041387384090206, -0.07205750429480978, -0.1654278978070107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016414767857187818, -0.01411626502572041, -0.008937271013219575]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558103342911, 0.0, 0.0, 0.0, 0.16720366730878633, -0.10023468418418392, 0.387581004949629, -0.3783838932854358, 1.1924034154309011, -1.3334027330575022, -1.983780112118894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1588127363106104, -0.15106330532837506, 0.31606874728641027]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.382859816940282e-08, 0.0, 0.0, 0.0, 0.041181449940919164, 0.02244359964088426, 0.0833167710545432, -0.09092243299705197, 0.2521982779842101, -0.07374346867677095, -0.1356572114576017, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009565002012928484, -0.011275455447012025, -0.007142901103241041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475581003790605, 0.0, 0.0, 0.0, 0.1689560534499147, -0.09946748047982665, 0.3929354016428149, -0.38176000404298466, 1.203631860081062, -1.337124530814242, -1.9889109910060323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1590906123981022, -0.15149739828487205, 0.3157953616895498]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.927700740377247e-09, 0.0, 0.0, 0.0, 0.03504772282256774, 0.015344074087145602, 0.10708793386371737, -0.06752221515097692, 0.2245688930032171, -0.07443595513479569, -0.10261757774276611, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00555752174983281, -0.008681859129940064, -0.005467711937209329]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558100359005, 0.0, 0.0, 0.0, 0.1704995671065108, -0.09915159157186919, 0.39914801918122544, -0.3844682955935468, 1.213907261524332, -1.340824481944231, -1.9922957843781004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1592723526652995, -0.1518137834527632, 0.3155972009139256]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.011177440788874e-11, 0.0, 0.0, 0.0, 0.030870273131921606, 0.0063177781591493044, 0.1242523507682113, -0.054165831011242185, 0.20550802886540154, -0.07399902259977635, -0.06769586744136027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003634805343945794, -0.006327703357823181, -0.003963215512484091]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558085662291, 0.0, 0.0, 0.0, 0.17187651630342948, -0.09910888493655559, 0.40599657218995844, -0.38661304314915096, 1.2234811349818342, -1.3445168438227446, -1.9945790920520396, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1593678890644947, -0.15205208981785018, 0.31545194982204594]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9393427582632583e-08, 0.0, 0.0, 0.0, 0.027538983938373562, 0.0008541327062720509, 0.13697106017466001, -0.04289495111208375, 0.19147746915004307, -0.07384723757027259, -0.04566615347878475, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0019107279839029878, -0.004766127301739837, -0.002905021837593614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475580785935104, 0.0, 0.0, 0.0, 0.1730934420791447, -0.0990235219309919, 0.4133330266427755, -0.3880618826063071, 1.2324878441260727, -1.348245002933955, -1.996783590690115, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1593319341255943, -0.1522665946227727, 0.31533119435951523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4137561068418236e-08, 0.0, 0.0, 0.0, 0.02433851551430429, 0.0017072601112737692, 0.14672908905634102, -0.0289767891431228, 0.18013418288477226, -0.07456318222420621, -0.0440899727615052, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0007190987780078869, -0.004290096098450377, -0.002415109250613951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558077968646, 0.0, 0.0, 0.0, 0.17409877817007832, -0.09825174536053224, 0.42107658077326215, -0.38823293621845884, 1.2409137450418013, -1.352089004642658, -2.0008772461536632, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1590155722611426, -0.15255415325309543, 0.31518905518415047]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2497287464934408e-09, 0.0, 0.0, 0.0, 0.020106721818672502, 0.01543553140919305, 0.1548710826097334, -0.0034210722430344717, 0.16851801831457158, -0.07688003417406002, -0.08187310927096186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006327237289034513, -0.005751172606454401, -0.002842783507295123]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558079949703, 0.0, 0.0, 0.0, 0.1748339895669449, -0.09620155172155666, 0.4291823538818404, -0.38653914581903037, 1.2487351388307413, -1.3560677409044783, -2.008690443186472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1582706405482894, -0.15300899871025844, 0.3149833490622006]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.962113489348294e-09, 0.0, 0.0, 0.0, 0.014704227937331824, 0.0410038727795118, 0.16211546217156517, 0.03387580798856945, 0.15642787577880118, -0.07957472523640675, -0.15626394065617882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014898634257065224, -0.009096909143260206, -0.004114122438997861]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558080231777, 0.0, 0.0, 0.0, 0.17516484739264052, -0.09180184680902725, 0.4376559402450063, -0.38178444469816747, 1.2558001968204227, -1.3601565229409203, -2.0233859408392267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1568147441090033, -0.15379350374650566, 0.3146458029882803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.641483867872276e-10, 0.0, 0.0, 0.0, 0.006617156513912412, 0.08799409825058811, 0.16947172726331852, 0.0950940224172579, 0.1413011597936278, -0.08177564072883751, -0.2939099530550925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029117928785723154, -0.015690100724944367, -0.006750921478405622]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26540576026701346, 0.0, 0.0, 0.0, 0.1754279068716065, -0.08334579121692463, 0.44832620853288535, -0.37021883285598434, 1.2583589190130209, -1.3640906853814472, -2.0468821888828677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1542454763484162, -0.15569340651474145, 0.3137680676992551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876714992, 0.0, 0.0, 0.0, 0.005261189579319909, 0.16912111184205253, 0.21340536575758065, 0.23131223684366256, 0.05117444385196604, -0.07868324881053776, -0.46992496087282276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05138535521174349, -0.03799805536471586, -0.017554705780504908]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654907859183264, 0.0, 0.0, 0.0, 0.1731709251874777, -0.07458338494419613, 0.45744315876276215, -0.3555923102917338, 1.2601613018153504, -1.3641202364107963, -2.0754291873177264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1509633414978186, -0.15791999451793395, 0.3129751423110955]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017005130262588899, 0.0, 0.0, 0.0, -0.0451396336825758, 0.17524812545457014, 0.18233900459753638, 0.2925304512850105, 0.03604765604658902, -0.0005910205869804203, -0.5709399686971779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06564269701195061, -0.04453176006385011, -0.01585850776319133]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548716522068505, 0.0, 0.0, 0.0, 0.16856883971401374, -0.06926462798863547, 0.4612567909493772, -0.34165487700385033, 1.2609730931345458, -1.3578559968187738, -2.1052769361442403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1473719052439906, -0.1596879368646509, 0.3128920267594651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.241395282739653e-05, 0.0, 0.0, 0.0, -0.09204170946927914, 0.10637513911121295, 0.07627264373230136, 0.27874866575767004, 0.016235826383906346, 0.12528479184045083, -0.5969549765302816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07182872507656154, -0.035358846934339196, -0.001662311032608249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548475405059074, 0.0, 0.0, 0.0, 0.1631413419816036, -0.07113944345195383, 0.4583551862894037, -0.33215650330077373, 1.2609642874566485, -1.3489459464432183, -2.132675438210116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.143874290743903, -0.16021487611798102, 0.3141437184010465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.822340188646102e-05, 0.0, 0.0, 0.0, -0.10854995464820284, -0.03749630926636703, -0.05803209319947028, 0.18996747406153158, -0.00017611355794367942, 0.17820100751111112, -0.5479700413175117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06995229000175233, -0.010538785066602385, 0.025033832831627675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654845205228911, 0.0, 0.0, 0.0, 0.1583296919722795, -0.07837526292245249, 0.4518060035575307, -0.32908284116992875, 1.260096844384238, -1.3386520392613326, -2.1538747281159676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.141255101454644, -0.15990244748928684, 0.3161052210830155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.67055399237876e-06, 0.0, 0.0, 0.0, -0.09623300018648182, -0.14471638940997328, -0.13098365463746003, 0.06147324261689949, -0.017348861448211395, 0.2058781436377146, -0.42398579811703146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.052383785785181984, 0.006248572573883645, 0.03923005363937987]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548453780614667, 0.0, 0.0, 0.0, 0.15446749555267678, -0.08889892552038234, 0.4442355712850151, -0.3297943525881716, 1.2595494542619827, -1.324626565985125, -2.1674459669903485, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1394476634199182, -0.15941609228721562, 0.31815173156266324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4566511142357926e-07, 0.0, 0.0, 0.0, -0.07724392839205443, -0.21047325195859684, -0.15140864545031196, -0.014230228364857003, -0.010947802445103506, 0.28050946552414846, -0.2714247774876201, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0361487606945131, 0.009727104041424363, 0.040930209592955534]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548142273267195, 0.0, 0.0, 0.0, 0.15182016214011365, -0.10175673598711157, 0.43939379155620334, -0.3323149796161467, 1.263071911592247, -1.306785838672453, -2.17622992441997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1379686260378619, -0.15928187046328035, 0.3198697033409628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.23014694947478e-05, 0.0, 0.0, 0.0, -0.05294666825126235, -0.2571562093345846, -0.09683559457623514, -0.05041254055950254, 0.07044914660528818, 0.35681454625344333, -0.1756791485924284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02958074764112502, 0.0026844364787054122, 0.034359435565991754]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.265481014694849, 0.0, 0.0, 0.0, 0.15027430449716725, -0.11374025049856382, 0.4410259780839107, -0.3365164917066845, 1.273422641355929, -1.2888798076265053, -2.1804901952978764, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.13674121135096, -0.1591684852935765, 0.3212235456848956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.160756457979803e-06, 0.0, 0.0, 0.0, -0.030917152858928196, -0.23967029022904482, 0.03264373055414685, -0.08403024181075607, 0.20701459527364163, 0.35812062091894925, -0.08520541755812483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024548293738037193, 0.002267703394076924, 0.027076846878655855]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654810319127324, 0.0, 0.0, 0.0, 0.14946966470417497, -0.12305942182075875, 0.4468948388792953, -0.3420547850041193, 1.2868537471179413, -1.2746582102168769, -2.180193797963985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.135978842483269, -0.15877309799065983, 0.3223042061381608]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4435766767572e-07, 0.0, 0.0, 0.0, -0.01609279585984567, -0.1863834264438988, 0.11737721590769293, -0.11076586594869536, 0.26862211524024665, 0.28443194819256845, 0.005927946677824161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015247377353821322, 0.007907746058333266, 0.021613209065304007]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654810433659598, 0.0, 0.0, 0.0, 0.14920359010584522, -0.13003658338046162, 0.45463507301977807, -0.3484331869417402, 1.3007274535607514, -1.2671711890763535, -2.1756836716815187, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.135739025176766, -0.1581050236647337, 0.32319198773658214]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2906454708137905e-07, 0.0, 0.0, 0.0, -0.00532149196659488, -0.13954323119405723, 0.15480468280965515, -0.1275680387524183, 0.277474128856203, 0.14974042281046887, 0.09020252564932817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004796346130062132, 0.013361486518522632, 0.017755631968426874]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654810395106448, 0.0, 0.0, 0.0, 0.1493877706102916, -0.13573758333410182, 0.4630217862685106, -0.3555927139896415, 1.314259369566811, -1.2649276677337158, -2.166980426591682, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1360143612179239, -0.15723503459111224, 0.3239529142816831]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.710630005964129e-08, 0.0, 0.0, 0.0, 0.0036836100889274977, -0.11401999907280394, 0.16773426497465, -0.14319054095802625, 0.2706383201211919, 0.044870426852752526, 0.1740649017967285, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005506720823154435, 0.01739978147242914, 0.015218530902019162]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548099530005076, 0.0, 0.0, 0.0, 0.1500319455931379, -0.14141674075188548, 0.4716180402900231, -0.3641612357824809, 1.3275794471504883, -1.2660362715287812, -2.1528945867527365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1368770320705006, -0.15615768394320664, 0.3246606296460654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.842118807659552e-07, 0.0, 0.0, 0.0, 0.012883499656926279, -0.11358314835567314, 0.17192508043024968, -0.17137043585678793, 0.2664015516735447, -0.022172075901306335, 0.28171679677891104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017253417051536955, 0.021547012958112136, 0.014154307287645603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264831048379349, 0.0, 0.0, 0.0, 0.1516181473741707, -0.14517144554717934, 0.4796196796977191, -0.37788875162287755, 1.3425974287436169, -1.2676756784447298, -2.1299063882774556, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1385116100787882, -0.15434066434005447, 0.32541820208253686]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012998938414034647, 0.0, 0.0, 0.0, 0.031724035620655906, -0.0750940959058772, 0.1600327881539215, -0.2745503168079332, 0.300359631862571, -0.03278813831897105, 0.4597639695056208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03269156016575021, 0.036340392063043486, 0.015151448729429232]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26418109615602237, 0.0, 0.0, 0.0, 0.1526557561660527, -0.14548000674951175, 0.4832767061474716, -0.4005252614607949, 1.3590989519071794, -1.2663331649362104, -2.099515829540973, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.140461132091098, -0.15127741481319085, 0.3261074017863471]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044466533136, 0.0, 0.0, 0.0, 0.020752175837639823, -0.006171224046648341, 0.07314052899504955, -0.45273019675834775, 0.33003046327125096, 0.026850270170387512, 0.6078111747296513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.038990440246195045, 0.06126499053727262, 0.013783994076205414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2641108141286731, 0.0, 0.0, 0.0, 0.15546218414131874, -0.13859242435891436, 0.4844254862590161, -0.42832076529623553, 1.3733340166412595, -1.2619406591225981, -2.0654729105432854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1423333750779767, -0.14776047250200158, 0.32657352661894634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056405469850333, 0.0, 0.0, 0.0, 0.05612855950532085, 0.1377516478119476, 0.022975602230890436, -0.5559100767088119, 0.2847012946816036, 0.08785011627224446, 0.6808583799537539, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03744485973757457, 0.07033884622378545, 0.00932249665198423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26411636770054797, 0.0, 0.0, 0.0, 0.16034436920430686, -0.12160277244366503, 0.486815267220721, -0.4575252631342237, 1.381552623096373, -1.257373844915654, -2.031527631279506, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1437372053560726, -0.14458272820809948, 0.3269181714282179]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001110714374969084, 0.0, 0.0, 0.0, 0.09764370125976249, 0.3397930383049865, 0.047795619234098065, -0.5840899567597636, 0.16437212910227184, 0.09133628413888288, 0.6789055852755898, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02807660556191557, 0.06355488587804224, 0.006892896185431182]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476631991929017, 0.0, 0.0, 0.0, 0.16674118532728036, -0.09619472922739854, 0.49419604891529, -0.48438875497796163, 1.3800062601149365, -1.2553993896826732, -2.0014299917471208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1442829653396736, -0.14253751496243677, 0.32675965379894406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044374844379, 0.0, 0.0, 0.0, 0.12793632245946995, 0.5081608643253299, 0.14761563389138044, -0.537269836874759, -0.030927259628728276, 0.03948910465961735, 0.6019527906477051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010915199672019359, 0.040904264913253774, -0.0031703525854760058]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654162721625312, 0.0, 0.0, 0.0, 0.17279449348232198, -0.06611829470994807, 0.5041827975703563, -0.5051612408281536, 1.37244492767157, -1.2596745127855593, -1.9789299919458065, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1436032911273977, -0.14240867057116127, 0.32646158567424055]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044864820652, 0.0, 0.0, 0.0, 0.12106616310083249, 0.6015286903490094, 0.19973497310132757, -0.415449717003839, -0.15122664886733303, -0.0855024620577235, 0.4499999960262835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013593484245517389, 0.0025768878255102807, -0.00596136249407027]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2660662243606415, 0.0, 0.0, 0.0, 0.17569644771705706, -0.03512346888574713, 0.5130255139688394, -0.5163404613564648, 1.362618622526514, -1.2707897565801738, -1.9673248641359316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1420893155385865, -0.14340389317892915, 0.3266489670032395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043962204684, 0.0, 0.0, 0.0, 0.058039084694701634, 0.6198965164840186, 0.17685432796966144, -0.22358441056622322, -0.1965261029011192, -0.22230487589228998, 0.23210255619750159, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030279511776224496, -0.01990445215535755, 0.0037476265799785465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26613650661828936, 0.0, 0.0, 0.0, 0.17776141533720877, -0.006960251651377317, 0.5169741982885128, -0.5216763981620784, 1.352922070579278, -1.2849951210806747, -1.9628646084558345, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.14053681844059, -0.14591647981481998, 0.32794679629544626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056451529575586, 0.0, 0.0, 0.0, 0.04129935240303398, 0.5632643446873963, 0.07897368639346583, -0.10671873611227346, -0.19393103894471997, -0.2841072900100189, 0.08920511360193958, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031049941959931306, -0.05025173271781655, 0.025956585844135648]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661309572553657, 0.0, 0.0, 0.0, 0.17884278056155437, 0.014621358408666508, 0.5122788541046444, -0.5235133158879759, 1.3466973636417685, -1.298540606422307, -1.961799225602026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1394207491009507, -0.1493876386880295, 0.32973007375906405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098725847383424, 0.0, 0.0, 0.0, 0.02162730448691199, 0.4316322012008765, -0.09390688367736919, -0.0367383545179487, -0.1244941387501864, -0.2709097068326459, 0.021307657076168995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02232138679278577, -0.0694231774641908, 0.03566554927235541]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286370482004, 0.0, 0.0, 0.0, 0.17935620579551292, 0.028100798869859958, 0.5022739707061691, -0.5238647945431902, 1.342680268703112, -1.307676220509117, -1.960835999606829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1389165275696802, -0.1530955388865337, 0.3314670906401684]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6404143305599766e-05, 0.0, 0.0, 0.0, 0.010268504679171286, 0.269588809223869, -0.20009766796950462, -0.007029573104286382, -0.08034189877312857, -0.18271228173619752, 0.0192645199039402, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010084430625411069, -0.07415800397008415, 0.03474033762208626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661284633970455, 0.0, 0.0, 0.0, 0.17949218208518541, 0.035837503476792425, 0.49024536469148206, -0.5235923840831797, 1.339670092518184, -1.309937203688509, -1.960204681647976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1387051011851566, -0.15650412358793706, 0.3329354725451849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.473023097933565e-06, 0.0, 0.0, 0.0, 0.0027195257934496822, 0.15473409213864933, -0.2405721202937403, 0.0054482092002119745, -0.06020352369856509, -0.04521966358783985, 0.012626359177061307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004228527690471898, -0.06817169402806678, 0.029367638100330547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661284981773362, 0.0, 0.0, 0.0, 0.17934123962185536, 0.04012180024453085, 0.4780556923221349, -0.5230889841477239, 1.336858828188047, -1.3072920228379028, -1.9603764893145326, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1385546426827868, -0.15943026891055614, 0.3340813313490461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.956058138763873e-07, 0.0, 0.0, 0.0, -0.003018849266600887, 0.08568593535476852, -0.2437934473869432, 0.01006799870911539, -0.056225286602738504, 0.052903617012127646, -0.0034361533311316333, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0030091700473960405, -0.05852290645238179, 0.02291717607722427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661285740779218, 0.0, 0.0, 0.0, 0.17896097501599745, 0.04245760128382929, 0.466481105812764, -0.5225285944796508, 1.3338271375482034, -1.3017317808966946, -1.9615150794926115, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1383555406066181, -0.16186781606425044, 0.3349278257576445]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.518011712435235e-06, 0.0, 0.0, 0.0, -0.007605292117158024, 0.0467160207859688, -0.23149173018741878, 0.011207793361459979, -0.06063381279686962, 0.11120483882416278, -0.02277180356158058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003982041523374193, -0.0487509430738856, 0.01692988817196832]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612859677635453, 0.0, 0.0, 0.0, 0.1783963394408925, 0.043709687042905426, 0.45571602384181986, -0.5219809142040578, 1.3304231847415962, -1.2945127618034795, -1.9635608096250026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1380716520722918, -0.16388160383193717, 0.33552462708938496]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.5396865505473667e-07, 0.0, 0.0, 0.0, -0.011292711502098991, 0.025041715181522775, -0.21530163941888222, 0.010953605511861971, -0.06807905613214547, 0.14438038186430266, -0.040914602647820694, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005677770686525882, -0.04027575535373461, 0.011936026634809346]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286021093255, 0.0, 0.0, 0.0, 0.17768358330020043, 0.044349384172770866, 0.4457059759345147, -0.5214658830805912, 1.3266424561195191, -1.286306606469063, -1.9663733686309133, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.137699831340902, -0.16555630614746336, 0.33592396463254615]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0665941919858273e-07, 0.0, 0.0, 0.0, -0.014255122813841377, 0.01279394259730876, -0.20020095814610314, 0.010300622469333153, -0.07561457244154077, 0.164123106688332, -0.05625118011821406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007436414627796874, -0.033494046310523794, 0.007986750863223264]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.266128604002413, 0.0, 0.0, 0.0, 0.1768508032296661, 0.04463468611825146, 0.4363179970572665, -0.5209800964646494, 1.3225446050569358, -1.2774429898173811, -1.9698152212577897, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1372473132051102, -0.16697384534161874, 0.3361711617002469]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.786175061728433e-08, 0.0, 0.0, 0.0, -0.016655601410686907, 0.005706038909611823, -0.1877595775449645, 0.009715732318836346, -0.08195702125166435, 0.17727233303363488, -0.06883705253752985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00905036271583243, -0.028350783883107807, 0.00494394135401542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286053185456, 0.0, 0.0, 0.0, 0.17591842394550922, 0.04471604395853678, 0.4274135675017475, -0.5205081719906879, 1.3182061822800817, -1.2680744728827371, -1.973787008982511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1367214752784514, -0.16820517706446855, 0.33630214608133097]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6322651529538716e-08, 0.0, 0.0, 0.0, -0.018647585683137277, 0.0016271568057064324, -0.17808859111037864, 0.009438489479230776, -0.08676845553708162, 0.18737033869288172, -0.07943575449442451, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0105167585331765, -0.02462663445699628, 0.002619687621680676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612860718853354, 0.0, 0.0, 0.0, 0.1749140854866592, 0.044518445524972916, 0.41887621293119015, -0.5201561751700677, 1.3137429876349935, -1.2582710322900612, -1.9779267781241203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1361555565014407, -0.16929291248663794, 0.3363502301535836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.739975863345121e-08, 0.0, 0.0, 0.0, -0.020086769176999978, -0.003951968671277293, -0.17074709141114747, 0.007039936412403962, -0.08926389290176222, 0.196068811853518, -0.08279538283218885, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011318375540214407, -0.021754708443387616, 0.0009616814450528837]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286077881597, 0.0, 0.0, 0.0, 0.17387796836455283, 0.04372115440864493, 0.41062272117872356, -0.5201836646418213, 1.3093275449228, -1.248041564367296, -1.9815293325154038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1356156377746671, -0.17024985268907683, 0.33634921107113763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1992523293527261e-08, 0.0, 0.0, 0.0, -0.020722342442127686, -0.015945822326559795, -0.16506983504933223, -0.0005497894350710826, -0.08830885424387074, 0.2045893584553037, -0.07205108782566824, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010798374535474012, -0.019138804048777897, -2.038164891970235e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612860780298714, 0.0, 0.0, 0.0, 0.17282589241290908, 0.04225619217773744, 0.4025972909436918, -0.5206411111114311, 1.3050755226590165, -1.237304222555455, -1.9844255602830192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1351144721930122, -0.17110868144739091, 0.3363163793279702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.965487644663138e-10, 0.0, 0.0, 0.0, -0.021041519032874847, -0.02929924461814969, -0.16050860470063547, -0.00914892939219471, -0.08504044527566909, 0.2147468362368229, -0.057924555352310246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010023311633097765, -0.017176575166281856, -0.0006566348633484282]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.266128607790855, 0.0, 0.0, 0.0, 0.17175049861533023, 0.04032392821659583, 0.3947669753271486, -0.5213655568196836, 1.3010477415752089, -1.2258739437644794, -1.987027912757261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1346020975306035, -0.171929322021282, 0.33625187890946434]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.426427501607317e-10, 0.0, 0.0, 0.0, -0.021507875951576966, -0.03864527922283224, -0.1566063123308639, -0.01448891416504988, -0.08055562167615082, 0.22860557581950927, -0.05204704948483499, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010247493248173905, -0.016412811477821507, -0.001290008370117655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286077952793, 0.0, 0.0, 0.0, 0.17061837293643486, 0.038447805010262646, 0.3871119337049026, -0.5219443403648791, 1.297232568552834, -1.213453041492427, -1.9904584627217712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.13394874518036, -0.1728093116149613, 0.3361361561525302]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.848638916235128e-11, 0.0, 0.0, 0.0, -0.022642513577907114, -0.037522464126663546, -0.15310083244492018, -0.01157567090391079, -0.07630346044749525, 0.24841804544104823, -0.06861099929020445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013067047004866834, -0.017599791873585933, -0.002314455138682981]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286078520693, 0.0, 0.0, 0.0, 0.16939237802655835, 0.03720233704577738, 0.37962643724791795, -0.5219177113987072, 1.2936216353990153, -1.1996250171017186, -1.99607636000695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1329870857396735, -0.17386327534029775, 0.33593985776928476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1358007199441248e-09, 0.0, 0.0, 0.0, -0.024519898197530234, -0.02490935928970535, -0.14970992913969314, 0.0005325793234389267, -0.07221866307637526, 0.2765604878141655, -0.11235794570357513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019233188813730803, -0.021079274506729088, -0.003925967664908161]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286081079845, 0.0, 0.0, 0.0, 0.1680186980670547, 0.03733385639633423, 0.37229647792738235, -0.5206981247985758, 1.2901486185877802, -1.1838958395047665, -2.005655615942108, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1314959989311235, -0.17523005569775693, 0.33562079509601467]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.118304105185253e-09, 0.0, 0.0, 0.0, -0.027473599190073028, 0.0026303870111370406, -0.14659918641071232, 0.024391732002629663, -0.06946033622470259, 0.3145835519390442, -0.19158511870315675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02982173617100067, -0.027335607149183525, -0.006381253465401308]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286081464471, 0.0, 0.0, 0.0, 0.16628230192854246, 0.04129536067804891, 0.36492397029282325, -0.5165084411754213, 1.2859841396915148, -1.1661804119108894, -2.0229462223109658, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1289789581347347, -0.1771620896137992, 0.33507599924716064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.692524832600097e-10, 0.0, 0.0, 0.0, -0.03472792277024456, 0.07923008563429368, -0.14745015269118245, 0.08379367246309062, -0.0832895779253093, 0.3543085518775436, -0.3458121273771545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0503408159277777, -0.038640678320845265, -0.010895916977080559]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612860768593327, 0.0, 0.0, 0.0, 0.16365280500896318, 0.04533685135836222, 0.3595579026970348, -0.5130986575639089, 1.2848781879911668, -1.1481307430884045, -2.044198179279633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.125821176163139, -0.17886396640165067, 0.3349304695454913]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.21027691532921e-09, 0.0, 0.0, 0.0, -0.05258993839158542, 0.08082981360626615, -0.10732135191576848, 0.06819567223024758, -0.022119034006960615, 0.3609933764496965, -0.42503913937334514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06315563943191577, -0.03403753575702956, -0.002910594033386397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26547865544341726, 0.0, 0.0, 0.0, 0.15861729965043544, 0.04570832843746334, 0.35259719883503804, -0.5142187739638918, 1.2905807634851816, -1.1298557980605355, -2.0656614868481715, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1224083608714128, -0.17954334119525345, 0.3358092059897029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044850320635, 0.0, 0.0, 0.0, -0.10071010717055476, 0.007429541582022456, -0.1392140772399357, -0.022402327999658717, 0.11405150988029539, 0.365498900557378, -0.42926615137076707, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0682563058345209, -0.013587495872055553, 0.017574728884230457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2648287032767418, 0.0, 0.0, 0.0, 0.1513590882692843, 0.03938610560316109, 0.3415854420284019, -0.5236187903431017, 1.306582907850095, -1.1089006097417342, -2.0835861450406337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1191521733268013, -0.17849736723232482, 0.33785551515914375]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043333508736, 0.0, 0.0, 0.0, -0.14516422762302303, -0.1264444566860451, -0.22023513613272222, -0.188000327584196, 0.3200428872982689, 0.4191037663760234, -0.3584931638492422, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06512375089223192, 0.020919479258572685, 0.04092618338881697]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647584208969125, 0.0, 0.0, 0.0, 0.14372857928124702, 0.030120160017861664, 0.3302726277614276, -0.5375487148245781, 1.3306442744066598, -1.0863884010708869, -2.098092551201705, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1159982748752775, -0.17640636396652165, 0.34044439969064455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056475965857351, 0.0, 0.0, 0.0, -0.15261017976074553, -0.18531891170598852, -0.22625628533948658, -0.2785984896295293, 0.48122733113129545, 0.45024417341694645, -0.2901281232214308, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06307796903047444, 0.041820065316063235, 0.05177769063001621]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647639705114251, 0.0, 0.0, 0.0, 0.13679217187810522, 0.02166045816364011, 0.3224087529871493, -0.5522585553625589, 1.3590149059256786, -1.0660691565381444, -2.1129293022972093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1129573181571875, -0.173927544331552, 0.34295086765248955]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011099229025160386, 0.0, 0.0, 0.0, -0.13872814806283626, -0.16919403708443104, -0.15727749548556508, -0.2941968107596152, 0.5674126303803757, 0.4063848906548504, -0.29673502191008966, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06081913436180128, 0.049576392699392874, 0.050129359236900393]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476629078783115, 0.0, 0.0, 0.0, 0.13088688378496335, 0.017089205881265043, 0.3192179508409571, -0.5639983153139854, 1.3879448027884924, -1.0516927199415205, -2.1273183575200676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.110349980893241, -0.17160775318006863, 0.3450604273843706]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.640552812165432e-05, 0.0, 0.0, 0.0, -0.11810576186283715, -0.09142504564750134, -0.0638160429238442, -0.23479519902853005, 0.5785979372562755, 0.2875287319324791, -0.28778110445716376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05214674527892915, 0.04639582302966746, 0.04219119463762132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664683698033, 0.0, 0.0, 0.0, 0.12618364116341532, 0.01548477344034789, 0.3197168631826913, -0.5721343516816407, 1.414002076597127, -1.0424173552289444, -2.1402732799799202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1081752496622137, -0.169715780069158, 0.34671234185629807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5516394427910082e-06, 0.0, 0.0, 0.0, -0.09406485243096056, -0.03208864881834307, 0.009978246834684762, -0.16272072735310697, 0.521145476172694, 0.18550729425152085, -0.2590984491970518, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043494624620549746, 0.037839462218212896, 0.03303828943854946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643894308044, 0.0, 0.0, 0.0, 0.12268279512419489, 0.015488266670990337, 0.3228637195581985, -0.5774126331129201, 1.4366172759536346, -1.0363980085168762, -2.1514487671705305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.106319843092135, -0.16833337535259965, 0.34794307740963537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.88534457104509e-07, 0.0, 0.0, 0.0, -0.07001692078440862, 6.98646128489272e-05, 0.06293712751014367, -0.10556562862558684, 0.4523039871301521, 0.12038693424136139, -0.22350974381220107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03710813140157346, 0.027648094331166773, 0.02461471106674642]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643101333963, 0.0, 0.0, 0.0, 0.12025853422020397, 0.016241720084833915, 0.32788644649123194, -0.5805905067965282, 1.4562272034059378, -1.032153503687627, -2.1611514446943945, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.104648512368432, -0.16745348880586808, 0.348816358455733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5859481650144143e-07, 0.0, 0.0, 0.0, -0.04848521807981843, 0.015069068276871548, 0.1004545386606694, -0.06355747367216305, 0.39219854904606116, 0.08489009658498584, -0.1940535504772783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0334266144740623, 0.01759773093463136, 0.017465620921952918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664306617872, 0.0, 0.0, 0.0, 0.11843143505295134, 0.02043383575239546, 0.3331696769770664, -0.5797033841049434, 1.4717637952572689, -1.0285313337447441, -2.17313131025325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1025834062396578, -0.1673118844682218, 0.3491999883529489]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.03104925380982e-09, 0.0, 0.0, 0.0, -0.03654198334505256, 0.08384231335123088, 0.10566460971668894, 0.017742453831696814, 0.3107318370266204, 0.07244339885765697, -0.23959731117711208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04130212257548332, 0.002832086752925997, 0.0076725979443180835]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643180934617, 0.0, 0.0, 0.0, 0.11714304912862554, 0.02671197423583858, 0.33892061010513, -0.5760210819726153, 1.4848589641414316, -1.0245957784566169, -2.189189843862316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0999542849324677, -0.1678682034662479, 0.3492129685258999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.295117951156564e-08, 0.0, 0.0, 0.0, -0.02576771848651587, 0.12556276966886243, 0.1150186625612721, 0.073646042646562, 0.26190337768325467, 0.07871110576254355, -0.3211706721813176, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05258242614380167, -0.011126379960522226, 0.0002596034590194706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643199085426, 0.0, 0.0, 0.0, 0.116577213936638, 0.03156965912597852, 0.3463836163530932, -0.5723083940038088, 1.4989070368358248, -1.0180386407133397, -2.2055773209814737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0971585103480541, -0.16891545944690242, 0.3490322686819484]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.6301615963257087e-09, 0.0, 0.0, 0.0, -0.011316703839750756, 0.09715369780279869, 0.14926012495926358, 0.07425375937612802, 0.2809614538878657, 0.1311427548655441, -0.3277495423831592, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05591549168827386, -0.02094511961309063, -0.0036139968790289668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643178367376, 0.0, 0.0, 0.0, 0.1162742758385884, 0.03334246211453408, 0.35367857866147, -0.5700026507674979, 1.5133848724612957, -1.0068698998265686, -2.219296539998739, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0945471565788314, -0.17025346765464594, 0.34877300953169954]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.143609581813442e-09, 0.0, 0.0, 0.0, -0.006058761960991877, 0.03545605977111122, 0.14589924616753522, 0.046114864726218396, 0.2895567125094163, 0.22337481773542373, -0.27438438034530266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05222707538445559, -0.026760164154870324, -0.005185183004978082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664317347447, 0.0, 0.0, 0.0, 0.11527769354390283, 0.0314629381793694, 0.3570555241855653, -0.5702525929686189, 1.524542498087137, -0.991220411590491, -2.227902718851112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0926232060732566, -0.17143679046359547, 0.3486075279595993]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.785813747885674e-10, 0.0, 0.0, 0.0, -0.01993164589371154, -0.03759047870329362, 0.06753891048190544, -0.004998844022419971, 0.2231525125168239, 0.31298976472155127, -0.17212357704745274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03847901011149427, -0.023666456178990602, -0.003309631442004097]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316084939, 0.0, 0.0, 0.0, 0.11378679943433333, 0.027597220186734325, 0.356256455532495, -0.5720686936318743, 1.531278333759708, -0.9742282071442913, -2.232513891847721, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0914710831855785, -0.1723175627042114, 0.3485383525202129]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.5250156241231264e-09, 0.0, 0.0, 0.0, -0.02981788219138992, -0.07731435985270142, -0.015981373061405152, -0.03632201326510961, 0.13471671345142006, 0.3398440889239949, -0.09222345993218652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02304245775356016, -0.0176154448123184, -0.0013835087877277063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264766431594108, 0.0, 0.0, 0.0, 0.11299112355251571, 0.0254941426036934, 0.3550313721956987, -0.5727816188771538, 1.5373423783235054, -0.9596432852641452, -2.23544868442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0904756681098446, -0.17303305400669133, 0.3483969850357224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8771777683904587e-10, 0.0, 0.0, 0.0, -0.015913517636352216, -0.04206155166081847, -0.024501666735926908, -0.014258504905591919, 0.12128089127594698, 0.29169843760292, -0.05869585147798742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01990830151467944, -0.014309826049598719, -0.0028273496898103085]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664315983433, 0.0, 0.0, 0.0, 0.11291865359027885, 0.026167173886651535, 0.35713020919360755, -0.5722681122102595, 1.5441031183848033, -0.951215640475407, -2.2373747216453372, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0894594438368936, -0.17349439125857263, 0.3482204851176128]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.470578986111211e-11, 0.0, 0.0, 0.0, -0.0014493992447372414, 0.013460625659162659, 0.041976739958177633, 0.010270133337886771, 0.13521480122595625, 0.16855289577476507, -0.038520744474341354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02032448545902065, -0.009226745037626138, -0.0035299983621923836]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664317389788, 0.0, 0.0, 0.0, 0.11324448775844541, 0.029368723826725732, 0.36132295522004887, -0.570794754547609, 1.5493744380535333, -0.9514922017230499, -2.2384344472073847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.088654410780289, -0.1735718219474068, 0.34807898566217643]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.812709705718739e-09, 0.0, 0.0, 0.0, 0.006516683363331197, 0.06403099880148391, 0.08385492052882589, 0.029467153253010036, 0.10542639337459983, -0.00553122495285982, -0.021194511240953052, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01610066113209596, -0.0015486137766833287, -0.002829989108727092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643172315384, 0.0, 0.0, 0.0, 0.1131380005788106, 0.03141015375478614, 0.3638596999125084, -0.5706569731349215, 1.549407444413861, -0.9567229910988146, -2.2355636355137825, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0886781869779254, -0.17313521085545588, 0.3481453620075015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1649906240734936e-10, 0.0, 0.0, 0.0, -0.0021297435926962913, 0.04082859856120814, 0.05073489384919036, 0.002755628253749653, 0.000660127206555769, -0.10461578751529363, 0.0574162338720494, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004755239527300171, 0.008732221839018263, 0.0013275269065020417]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316844906, 0.0, 0.0, 0.0, 0.11233490444658752, 0.030908924454804153, 0.3610029716914766, -0.5716463007756346, 1.5451614274280667, -0.9631580421880943, -2.230626308135342, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0895154754916776, -0.17251786429133562, 0.3483622577391764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.732646543988025e-10, 0.0, 0.0, 0.0, -0.01606192264446163, -0.010024585999639735, -0.05713456442063604, -0.01978655281426186, -0.0849203397158846, -0.12870102178559306, 0.09874654756880347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016745770275043915, 0.012346931282405396, 0.004337914633497819]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316718823, 0.0, 0.0, 0.0, 0.11116961238076889, 0.027814293955794173, 0.3548633579739013, -0.5731844010115555, 1.5403854714987177, -0.9670473668165558, -2.225698641901949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0906515710796603, -0.1721328493494456, 0.3486037054106216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.52166204574048e-10, 0.0, 0.0, 0.0, -0.023305841316372478, -0.0618926099801996, -0.12279227435150651, -0.03076200471841811, -0.09551911858698153, -0.07778649256922998, 0.0985533246678646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022721911759653123, 0.007700298837800282, 0.004828953428904187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316841142, 0.0, 0.0, 0.0, 0.11117165016237776, 0.025324918112385665, 0.34919085416673257, -0.5723635339346635, 1.5388295719441993, -0.968840333240735, -2.2245306316726055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915909367430834, -0.17244641191884746, 0.3484980501005215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4463783639043815e-10, 0.0, 0.0, 0.0, 4.075563217735209e-05, -0.04978751686817012, -0.11345007614337416, 0.016417341537839084, -0.03111799109036796, -0.03585932848358506, 0.023360204586867828, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018787313268462724, -0.006271251388037686, -0.0021131062020017036]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643168771546, 0.0, 0.0, 0.0, 0.11201724161563884, 0.02415343452395005, 0.34773544327052686, -0.5697582607626464, 1.5438717307767065, -0.969812063350708, -2.227247431013922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091645544246025, -0.17339510328982402, 0.3481462012440518]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.202568411930899e-11, 0.0, 0.0, 0.0, 0.01691182906522159, -0.023429671768712246, -0.02910821792411418, 0.052105463440344904, 0.10084317665014204, -0.01943460219945926, -0.054335986826331076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001092150058831014, -0.01897382741953133, -0.007036977129393326]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643250153836, 0.0, 0.0, 0.0, 0.1132721992116631, 0.024058121153961744, 0.3501844609216766, -0.5665672772502849, 1.5522560841924036, -0.9718234442422322, -2.2311342746699547, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0911969580321144, -0.17450191787748523, 0.34772830155218526]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6276457965752105e-08, 0.0, 0.0, 0.0, 0.025099151920485063, -0.0019062673997661123, 0.04898035302299533, 0.06381967024722891, 0.16768706831394253, -0.04022761783048395, -0.07773687312064889, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008971724278209251, -0.02213629175322423, -0.008357993837330758]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664326095421, 0.0, 0.0, 0.0, 0.11445451903214579, 0.024507249900566488, 0.35370485870085017, -0.5636993872708438, 1.5603106262097637, -0.9750135662098344, -2.2343102480805372, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0907285157633746, -0.17541667469736083, 0.3473655591636725]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.1600742432189773e-09, 0.0, 0.0, 0.0, 0.023646396409653873, 0.008982574932094894, 0.07040795558347131, 0.057357799588821895, 0.16109084034720442, -0.06380243935204247, -0.06351946821164736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009368845374796899, -0.018295136397511774, -0.00725484777025548]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643100308517, 0.0, 0.0, 0.0, 0.11458036925662182, 0.023568559564922643, 0.3545477886589088, -0.5629429394625612, 1.5642864534576193, -0.975654170043454, -2.2359529447873876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090803251414037, -0.17587178312508353, 0.3471734912259824]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.212913869202863e-08, 0.0, 0.0, 0.0, 0.002517004489520639, -0.018773806712876907, 0.016858599161172258, 0.015128956165651818, 0.07951654495711415, -0.012812076672392848, -0.03285393413700806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014947130132468016, -0.00910216855445421, -0.0038413587538018044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664305158545, 0.0, 0.0, 0.0, 0.1139299561430751, 0.021708015350115187, 0.35099867355436914, -0.5635788327219675, 1.5634141876817278, -0.9734786486704348, -2.236819993174125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912796643580107, -0.17600537504634886, 0.3471020437186431]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.74461261590733e-09, 0.0, 0.0, 0.0, -0.01300826227093424, -0.037210884296149105, -0.07098230209079326, -0.012717865188124598, -0.01744531551783067, 0.043510427460384436, -0.01734096773474526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009528258879476517, -0.0026718384253064235, -0.0014289501467858482]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643049415943, 0.0, 0.0, 0.0, 0.11351121426930624, 0.02030305170591325, 0.346807480914311, -0.5639466852879884, 1.561443802071491, -0.9721315611981735, -2.236829857706255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0916525853239254, -0.17610880826157563, 0.3470585035099417]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3390187051915983e-10, 0.0, 0.0, 0.0, -0.008374837475377353, -0.028099272884038733, -0.0838238528011629, -0.007357051320417162, -0.039407712204739764, 0.026941749445225534, -0.00019729064260128396, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007458419318294714, -0.0020686643045355613, -0.0008708041740279629]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643099283725, 0.0, 0.0, 0.0, 0.11384138157389646, 0.020350251236577986, 0.3457236255359675, -0.5629476134615214, 1.5621244857101886, -0.9738760046518786, -2.236542246252096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915795029734605, -0.17637459813567227, 0.34697574126655617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.973556358390658e-09, 0.0, 0.0, 0.0, 0.00660334609180431, 0.0009439906132947054, -0.021677107566870114, 0.019981436529340316, 0.013613672773953825, -0.034888869074103185, 0.00575222908318224, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014616470092957553, -0.005315797481932686, -0.0016552448677107934]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664311102472, 0.0, 0.0, 0.0, 0.11467646501230651, 0.02139696714924933, 0.3486361645455943, -0.5610807810741122, 1.566051700203503, -0.9777340575348878, -2.2361940335188546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0911938479043735, -0.17674195518873392, 0.34686556480455893]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.348199823777098e-09, 0.0, 0.0, 0.0, 0.01670166876820084, 0.020934318253426877, 0.058250780192535566, 0.03733664774818482, 0.07854428986628981, -0.07716105766018339, 0.006964254664826009, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007713101381740762, -0.007347141061232829, -0.002203529239944765]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264766431107414, 0.0, 0.0, 0.0, 0.11506492907744939, 0.021530381442416792, 0.3517951149061298, -0.5601400818383483, 1.5694754664230979, -0.9799558284021133, -2.2358034551629618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0910461259403064, -0.1769845012960689, 0.3468060587781453]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.66649237253457e-11, 0.0, 0.0, 0.0, 0.007769281302857646, 0.0026682858633492006, 0.06317900721070913, 0.01881398471527897, 0.06847532439189696, -0.04443541734450738, 0.007811567117857081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0029544392813405217, -0.004850922146699959, -0.001190120528273116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664309854784, 0.0, 0.0, 0.0, 0.1147442272670446, 0.020163529216010792, 0.35145201789756975, -0.5605863382470238, 1.568834999834427, -0.9779139570558685, -2.235455632636704, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912582431379232, -0.17707551535297095, 0.3468094533529982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.438711943511148e-09, 0.0, 0.0, 0.0, -0.006414036208095768, -0.027337044528119976, -0.006861940171200953, -0.00892512817350979, -0.01280933177341713, 0.04083742692489569, 0.006956450525153016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004242343952335669, -0.0018202811380409682, 6.789149705782203e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643095956204, 0.0, 0.0, 0.0, 0.11427413393156692, 0.018173723836868272, 0.3497546179721089, -0.5615948958528232, 1.5669854437529516, -0.9739417135822606, -2.235173547805247, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915522614461362, -0.17713099857723627, 0.34683257617917307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.183273236773194e-10, 0.0, 0.0, 0.0, -0.009401866709553598, -0.03979610758285038, -0.03394799850921682, -0.020171152115987852, -0.03699112162950849, 0.07944486947215787, 0.005641696629135675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00588036616425801, -0.001109664485306548, 0.00046245652349833304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664309762652, 0.0, 0.0, 0.0, 0.1145566185984655, 0.017509666579236593, 0.3504528905361901, -0.5615166227001228, 1.567676762933102, -0.9717890422235987, -2.2349554898279456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0914172599690992, -0.1773312504451124, 0.3467967054784157]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.340625236588448e-10, 0.0, 0.0, 0.0, 0.00564969333797144, -0.013281145152633605, 0.013965451281624706, 0.001565463054006417, 0.013826383603012304, 0.04305342717323527, 0.004361159546027461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002700029540739488, -0.0040050373575222405, -0.0007174140151477491]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664310346551, 0.0, 0.0, 0.0, 0.11541078709966017, 0.018160556628257805, 0.3547706508880259, -0.5604984059487357, 1.5713200407791421, -0.9729573057215175, -2.234762542889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0909833556679853, -0.17759366418276812, 0.34672200560776456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.167798485713038e-09, 0.0, 0.0, 0.0, 0.0170833700238934, 0.013017800980424227, 0.08635520703671531, 0.02036433502774195, 0.07286555692080171, -0.023365269958375366, 0.0038589387736306918, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00867808602227708, -0.005248274753114821, -0.0014939974130222802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664310381693, 0.0, 0.0, 0.0, 0.11599846791051192, 0.0187843454282189, 0.3589579205539048, -0.5598435905774848, 1.5741653219430067, -0.974188485413714, -2.2345140334742064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090709312241996, -0.1777219212204129, 0.34667602895435884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.028473286281447e-11, 0.0, 0.0, 0.0, 0.011753616217034994, 0.012475775999221846, 0.08374539331757799, 0.01309630742501846, 0.05690562327729225, -0.02462359384392793, 0.004970188301154795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0054808685197868575, -0.0025651407528952683, -0.0009195330681145696]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664309467918, 0.0, 0.0, 0.0, 0.11576679578965395, 0.018721201460101967, 0.35926513129604076, -0.5600647179329961, 1.5724649129236763, -0.972494082672975, -2.2351225623556337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0907803111973564, -0.177676031638525, 0.34667884358644474]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8275503812316527e-09, 0.0, 0.0, 0.0, -0.004633442417159501, -0.0012628793623386536, 0.006144214842719625, -0.00442254711022487, -0.034008180386607426, 0.033888054814779564, -0.01217057762854782, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014199791072080897, 0.0009177916377579306, 5.629264171799471e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664308872581, 0.0, 0.0, 0.0, 0.11506866228233743, 0.018053558114696742, 0.356232527925416, -0.5609244622609034, 1.5677816623117127, -0.9689480506687775, -2.235940683224265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091083981761194, -0.17752209248416453, 0.34671678048290006]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1906745023300447e-09, 0.0, 0.0, 0.0, -0.013962670146330198, -0.01335286690810448, -0.06065206741249586, -0.01719488655814779, -0.09366501223927319, 0.07092064008394876, -0.016362417372625334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006073411276752258, 0.003078783087209056, 0.0007587379291066578]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 199999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664308917629, 0.0, 0.0, 0.0, 0.11485511729238716, 0.017931706509770322, 0.353610084199067, -0.5612026685594074, 1.5638655451152779, -0.967299732012413, -2.2357590380109866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912231957930703, -0.17743325405106408, 0.34673634256929214]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.009600635212578e-11, 0.0, 0.0, 0.0, -0.004270899799005339, -0.002437032098528422, -0.05244887452697968, -0.005564125970079589, -0.07832234392869553, 0.03296637312728962, 0.0036329042655682577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0027842806375245792, 0.0017767686620091404, 0.0003912417278418097]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643089431073, 0.0, 0.0, 0.0, 0.11535827976153545, 0.018999049877875603, 0.3551477308113616, -0.560382911718757, 1.5641707192651413, -0.9693825822611004, -2.235258209301683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0910316214632758, -0.1774680817597735, 0.34671070268202514]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.0957516246021646e-11, 0.0, 0.0, 0.0, 0.010063249382965881, 0.021346867362105608, 0.030752932245892213, 0.016395136813007544, 0.006103482997267873, -0.041657004973748246, 0.010016574186070774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003831486595889918, -0.0006965541741881628, -0.0005127977453404362]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664308927253, 0.0, 0.0, 0.0, 0.11590722482611304, 0.020120441676030287, 0.35755532971776466, -0.559512339986934, 1.5655646892786426, -0.9723358176950191, -2.2342308562155666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090844821515898, -0.1774948844662164, 0.3466880986955456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.17095045301625e-11, 0.0, 0.0, 0.0, 0.010978901291551707, 0.02242783596309367, 0.048151978128061546, 0.01741143463646015, 0.027879400270027433, -0.05906470867837435, 0.020547061722332317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0037359989475602576, -0.0005360541288577792, -0.0004520797295898358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664307226811, 0.0, 0.0, 0.0, 0.11577413019321742, 0.020221694597589067, 0.35708497993453703, -0.559559295831013, 1.5643043881218945, -0.9725795765366342, -2.23317217155742, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0909676680126992, -0.17740693715444716, 0.34670868420814804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.4008839616760352e-09, 0.0, 0.0, 0.0, -0.0026618926579125325, 0.0020250584311756192, -0.009406995664553067, -0.0009391168815819188, -0.025206023134960048, -0.004875176832301015, 0.021173693162934493, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024569299360261533, 0.0017589462353845434, 0.0004117102520489837]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643030597097, 0.0, 0.0, 0.0, 0.11518304029054811, 0.019599761370579498, 0.3540036170771198, -0.560225239245386, 1.56093423401713, -0.9707353792638763, -2.2322573536799926, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912902782809368, -0.17725329032808565, 0.34675639542599523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.334201746103628e-09, 0.0, 0.0, 0.0, -0.011821798053386129, -0.012438664540191408, -0.061627257148344446, -0.01331886828746065, -0.06740308209529246, 0.036883945455158273, 0.018296357548550815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00645220536475301, 0.00307293652723054, 0.0009542243569432922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 449999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643025727264, 0.0, 0.0, 0.0, 0.11491334003232198, 0.019418422949829935, 0.3520612054242456, -0.5604450725012409, 1.5592040742383544, -0.9702816985637978, -2.231404250576391, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0914616547683167, -0.17716597262138345, 0.3467828372094147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.73966741974502e-10, 0.0, 0.0, 0.0, -0.005394005164522714, -0.003626768414991292, -0.03884823305748317, -0.00439666511709696, -0.03460319557551171, 0.009073614001571154, 0.017062062072031474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0034275297475966616, 0.0017463541340441092, 0.0005288356683900361]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664302830495, 0.0, 0.0, 0.0, 0.11523098476711803, 0.02005383722768126, 0.35364925518427875, -0.5599316163048906, 1.5605976936933394, -0.9723401943607346, -2.2306974601120473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0913749815412719, -0.17717255644147348, 0.34677439067363364]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.1553741489976e-10, 0.0, 0.0, 0.0, 0.006352894695920986, 0.012708285557026513, 0.03176099520066221, 0.010269123927004532, 0.027872389099700162, -0.0411699159387365, 0.014135809286875516, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0017334645408973858, -0.00013167640180042947, -0.00016893071562217423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643028057684, 0.0, 0.0, 0.0, 0.11551675927557364, 0.02061162496318783, 0.3552602385282862, -0.5594709280454054, 1.5620812612479051, -0.9742804084550046, -2.2300050352697567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912927545016766, -0.17718254135595407, 0.3467660468594465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.945354146376601e-11, 0.0, 0.0, 0.0, 0.005715490169112327, 0.011155754710131418, 0.03221966688014856, 0.00921376518970403, 0.029671351091312036, -0.03880428188540073, 0.013848496845809181, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001644540791906005, -0.0001996982896116515, -0.0001668762837422621]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643013503304, 0.0, 0.0, 0.0, 0.11529102842767731, 0.020483383729382607, 0.35400999178978443, -0.5595782696520546, 1.5612570586669148, -0.9740195086475434, -2.229418883587127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0913974896669885, -0.17713997337586745, 0.3467805173526685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9108757849844204e-09, 0.0, 0.0, 0.0, -0.0045146169579267145, -0.002564824676104492, -0.0250049347700357, -0.0021468321329834276, -0.016484051619805703, 0.005217996149224476, 0.011723033652596955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020947033062384927, 0.000851359601732346, 0.00028940986444063633]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664301155837, 0.0, 0.0, 0.0, 0.11485851486649702, 0.020067670516678727, 0.3516324465586707, -0.5599199235732419, 1.5594998543821916, -0.9727952747290967, -2.2289307583069338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915794143987825, -0.17707677889586718, 0.34680445938895255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.889865402505619e-10, 0.0, 0.0, 0.0, -0.008650271223605933, -0.008314264254077584, -0.04755090462227426, -0.00683307842374694, -0.03514408569446362, 0.024484678368933577, 0.009762505603865086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003638494635879916, 0.0012638896000056546, 0.00047884072568107487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 699999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664307268475, 0.0, 0.0, 0.0, 0.11475305183805688, 0.0200654512616469, 0.3511903589653456, -0.5599129043790838, 1.5592776919504603, -0.9728423362259102, -2.2285406738398224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091635622223444, -0.17705293358484722, 0.3468125652375084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 750000000" + }, + "execution_count": 25, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "reset_giskard()\n", + "\n", + "# variables\n", + "gripper_link = 'r_gripper_tool_frame'\n", + "\n", + "# adding the object\n", + "cyl_pose = PoseStamped()\n", + "cyl_pose.header.frame_id = 'map'\n", + "cyl_pose.pose.orientation.w = 1\n", + "cyl_pose.pose.position = Point(2, -0.2, 1.2)\n", + "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", + "\n", + "# define the robot features\n", + "robot_pointing_feature = Vector3Stamped()\n", + "robot_pointing_feature.header.frame_id = gripper_link\n", + "robot_pointing_feature.vector = Vector3(1, 0, 0)\n", + "\n", + "robot_point_feature = PointStamped()\n", + "robot_point_feature.header.frame_id = gripper_link\n", + "robot_point_feature.point = Point(0, 0, 0)\n", + "\n", + "# define the world features\n", + "world_cylinder_center_feature = PointStamped()\n", + "world_cylinder_center_feature.header.frame_id = 'mycyl'\n", + "world_cylinder_center_feature.point = Point(0, 0, 0)\n", + "\n", + "# define the constraints\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cylinder_center_feature,\n", + " robot_feature=robot_point_feature,\n", + " lower_limit=0.03,\n", + " upper_limit=0.03)\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='HeightFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cylinder_center_feature,\n", + " robot_feature=robot_point_feature,\n", + " lower_limit=-0.05,\n", + " upper_limit=0.05)\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='PointingFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cylinder_center_feature,\n", + " robot_feature=robot_pointing_feature)\n", + "# EXCERCISE SOLUTION:\n", + "robot_gripper_z_axis_feature = Vector3Stamped()\n", + "robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", + "robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "\n", + "world_cyl_z_axis_feature = Vector3Stamped()\n", + "world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", + "world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='AlignFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cyl_z_axis_feature,\n", + " robot_feature=robot_gripper_z_axis_feature)\n", + "\n", + "gs.add_default_end_motion_conditions()\n", + "gs.execute()\n", + "\n", + "# EXERCISE:\n", + "# 1. Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.\n", + "# 2. You might notice that not all poses are feasible. This is due to a missing that constraint that allows the gripper_frame to freely rotate around its x-axis. Try to constrain this using the AlignFeatureFunction" + ], "metadata": { "collapsed": false, "pycharm": { @@ -402,22 +485,103 @@ } }, { - "cell_type": "code", - "execution_count": null, - "outputs": [], - "source": [], + "cell_type": "markdown", + "source": [ + "Another advantage of having unconstrained DOF in the motion specification can be seen if we put an obstacle in front of the object we want to grasp and configure the collision avoidance to avoid this obstacle with all parts of the robot." + ], "metadata": { "collapsed": false, "pycharm": { - "name": "#%%\n" + "name": "#%% md\n" } } }, { "cell_type": "code", - "execution_count": null, - "outputs": [], - "source": [], + "execution_count": 20, + "outputs": [ + { + "data": { + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2006499522418266, 0.0, 0.00013138406399284356, 0.0, -0.0018911454110190373, 0.003467997502063863, 0.002261559670703244, -0.15000000000558167, 9.394081548625307e-05, -0.1000100000032556, -0.002153130433649211, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.019017857734377e-12, 0.0, 0.0, -0.1500592024683071, 0.0, -0.1000692024683071, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246093841233858, 0.0006251787189194379, 0.0006249999938137112]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836531927, 0.0, 0.0026276812798569, 0.0, -0.037822908220380744, 0.06935995004127726, 0.045231193414064876, -1.1163372917477135e-10, 0.0018788163097250615, -6.511201788104837e-11, -0.04306260867298421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4038035715469994e-10, 0.0, 0.0, -0.0011840493661418627, 0.0, -0.0011840493661418627, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492187682467714, 0.012503574378388756, 0.012499999876274225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990446959206, 0.0, 0.0004934941405271855, 0.0, -0.005350422446676624, 0.009361262454469312, 0.006332831450702455, -0.1500000000508954, 0.00026247729174472435, -0.10001000003397474, -0.006102626025669795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3730638088655887e-11, 0.0, 0.0, -0.15020664513455953, 0.0, -0.10021664513455955, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.00249723430344827, 0.0015775437167409373, 0.00249999986996056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904455530908, 0.0, 0.007242201530686958, 0.0, -0.06918554071315174, 0.11786529904810897, 0.08142543559998422, -9.062747616995622e-10, 0.0033707295251694256, -6.143828286889566e-10, -0.07898991184041168, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.342324046184313e-10, 0.0, 0.0, -0.002948853325049055, 0.0, -0.002948853325049055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03745249838649769, 0.019047299956429987, 0.03749999752293697]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985671017934, 0.0, 0.0009829394491939064, 0.0, -0.009625451074185092, 0.0164101024713223, 0.011702223103185062, -0.15000000005946915, 0.0005080102959921151, -0.10001000003879015, -0.011484726567758976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9043136840312716e-11, 0.0, 0.0, -0.1503912226054937, 0.0, -0.10040122260549372, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005930246007499822, 0.002350992783948762, 0.0058796256049771685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044811745646, 0.0, 0.009788906173334395, 0.0, -0.08550057255016935, 0.14097680033705975, 0.10738783304965216, -1.7147478170045847e-10, 0.004910660084947813, -9.630832166644655e-11, -0.10764201084178363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.062499750331366e-10, 0.0, 0.0, -0.00369154941868348, 0.0, -0.00369154941868348, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06866023408103104, 0.015468981344156495, 0.06759251470033216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980895180787, 0.0, 0.0015247125917483844, 0.0, -0.013684989558475105, 0.02387080971806118, 0.018452663010715478, -0.1500000000655235, 0.000893751167781702, -0.10001000004222109, -0.018528238686148626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2916338007399637e-11, 0.0, 0.0, -0.15058189005965322, 0.0, -0.10059189005965323, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010648935037852013, 0.0025713986057469182, 0.010142249711465132]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044832570441, 0.0, 0.010835462851089545, 0.0, -0.08119076968580023, 0.14921414493477758, 0.13500879815060832, -1.210867776366769e-10, 0.007714817435791737, -6.861884688315247e-11, -0.140870242367793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.746402334173857e-11, 0.0, 0.0, -0.0038133490831902387, 0.0, -0.0038133490831902387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09437378060704382, 0.004408116435963127, 0.08525248212975926]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976119520266, 0.0, 0.00205072747891782, 0.0, -0.016672511341103168, 0.03139955025506507, 0.02736721087723845, -0.15000000006708336, 0.0015372123151348443, -0.10001000004308903, -0.028156866764058104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.569956530974065e-11, 0.0, 0.0, -0.15075750321751125, 0.0, -0.10076750321751125, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01635039505753499, 0.002021498070780422, 0.014662872278838005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044867895668, 0.0, 0.010520297743388668, 0.0, -0.059750435652561246, 0.15057481074007778, 0.1782909573304594, -3.1197317276118474e-11, 0.012869222947062844, -1.7358919222223152e-11, -0.19257256155818953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.566454604682024e-11, 0.0, 0.0, -0.003512263157160443, 0.0, -0.003512263157160443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11402920039365956, -0.010998010699329923, 0.09041245134745743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134385485, 0.0, 0.0025408648649906415, 0.0, -0.018033083156050445, 0.03885291651019851, 0.03988804443326672, -0.15000000006876096, 0.002610648532880667, -0.10001000004402233, -0.041975238951710944, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.7685239490123808e-11, 0.0, 0.0, -0.15091338521862452, 0.0, -0.10092338521862454, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022751113360734126, 0.0005604002153586066, 0.01895407434687648]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044866917026, 0.0, 0.00980274772145646, 0.0, -0.027211436298945547, 0.1490673251026688, 0.2504166711205653, -3.35520508135503e-11, 0.021468724354916452, -1.86658965237018e-11, -0.2763674437530568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9713483607663136e-11, 0.0, 0.0, -0.0031176400222656746, 0.0, -0.0031176400222656746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12801436606398273, -0.029221957108436305, 0.08582404136076949]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966568164473, 0.0, 0.0029965907777055943, 0.0, -0.01734099759877982, 0.04606126888023213, 0.058002789644010865, -0.15000000007105113, 0.0043519333470906614, -0.10001000004529743, -0.06219227263093911, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.9095133475902258e-11, 0.0, 0.0, -0.1510532271255623, 0.0, -0.10106322712556233, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029641037670814968, -0.001980554234652346, 0.022870813772015882]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861924228, 0.0, 0.009114518254299027, 0.0, 0.013841711145412446, 0.1441670474006725, 0.36229490421488286, -4.580346133623464e-11, 0.03482569628419989, -2.5502215580156844e-11, -0.40434067358456327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8197879715569004e-11, 0.0, 0.0, -0.002796838138755713, 0.0, -0.002796838138755713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1377984862016168, -0.05081908900021905, 0.07833478850278802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961792498273, 0.0, 0.0034118890253128226, 0.0, -0.014443457215812451, 0.05249343132179201, 0.0831310908475063, -0.15000000007274986, 0.006470848965680013, -0.10001000004624182, -0.08956318615097353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.0089871246348254e-11, 0.0, 0.0, -0.15117998940011299, 0.0, -0.101189989400113, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03687803504716805, -0.005659221270354244, 0.026427564241316516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044866760167, 0.0, 0.008305964952144602, 0.0, 0.05795080765934738, 0.1286432488311975, 0.502566024069909, -3.397455259264848e-11, 0.04237831237178703, -1.8887686270923795e-11, -0.5474182704006882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9894755408919886e-11, 0.0, 0.0, -0.0025352454910136054, 0.0, -0.0025352454910136054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14473994752706168, -0.07357334071403795, 0.07113500938601268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20584957016741257, 0.0, 0.003822800749548274, 0.0, -0.009589450287785935, 0.05778680297322593, 0.11466198197822292, -0.1500000000766933, 0.008336333026081978, -0.10001000004846573, -0.12317593973829957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.0749430646133444e-11, 0.0, 0.0, -0.15130782365807424, 0.0, -0.10131782365807426, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.044363773981805035, -0.010311789755080687, 0.029687281644921303]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044848596453, 0.0, 0.008218234484709059, 0.0, 0.0970801385605303, 0.1058674330286784, 0.630617822614332, -7.886896624705964e-11, 0.0373096812080393, -4.447844539583911e-11, -0.672255071746521, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3191187995703765e-11, 0.0, 0.0, -0.0025566851592250376, 0.0, -0.0025566851592250376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14971477869273975, -0.09305136969452885, 0.06519434807209575]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952240914754, 0.0, 0.004248608651217674, 0.0, -0.003205133026555734, 0.06178133828048554, 0.1516824378353661, -0.15000000008231962, 0.009773557694005897, -0.10001000005172546, -0.1620153776062251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.1081544416184297e-11, 0.0, 0.0, -0.15144544863438456, 0.0, -0.10145544863438456, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05204122702337631, -0.01574078511979557, 0.032715159305722996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044834699559, 0.0, 0.00851615803338803, 0.0, 0.127686345224604, 0.07989070614519228, 0.7404091171428636, -1.1252602139809881e-10, 0.028744493358478375, -6.519457231291811e-11, -0.7767887573585108, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.642275401017126e-12, 0.0, 0.0, -0.0027524995262060274, 0.0, -0.0027524995262060274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15354906083142542, -0.10857990729429765, 0.06055755321603393]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2071494744950351, 0.0, 0.004843462187939546, 0.0, 0.004299473485592131, 0.06444830753945968, 0.1932887590046653, -0.15000000046769238, 0.01067892439265633, -0.10001000029102042, -0.2050869119704552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2182600888122174e-11, 0.0, 0.0, -0.15166501076302943, 0.0, -0.10167501076302944, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.059876341665892084, -0.02176118622344076, 0.035566103819730896]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999041717751068, 0.0, 0.01189707073443735, 0.0, 0.1500921302429573, 0.0533393851794828, 0.8321264233859839, -7.707454969155888e-09, 0.01810733397300869, -4.78589920034722e-09, -0.8614306872846019, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.779788705612392e-10, 0.0, 0.0, -0.0043912425728975905, 0.0, -0.0043912425728975905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15670229285031548, -0.12040802207290378, 0.057018890280158045]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2077994267376033, 0.0, 0.00546154849475136, 0.0, 0.01257838148326606, 0.06583025778954048, 0.23857381568612884, -0.1500000004713173, 0.011198482601646638, -0.10001000029305597, -0.25154413930604774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.613306950154479e-11, 0.0, 0.0, -0.1518945605480015, 0.0, -0.10190456054800148, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06784712627442557, -0.028207944594465757, 0.03828273752242274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904485136395, 0.0, 0.012361726136236298, 0.0, 0.16557815995347858, 0.027639005001615945, 0.9057011336292708, -7.249881089523998e-11, 0.010391164179806137, -4.0710942533207546e-11, -0.9291445467118509, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2099062773154713e-10, 0.0, 0.0, -0.004590995699440854, 0.0, -0.004590995699440854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15941569217066984, -0.12893516742049993, 0.05433267405383695]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20844937897841428, 0.0, 0.006082240028599633, 0.0, 0.021383227025485313, 0.06599725415938462, 0.2868018606060743, -0.15000000047944895, 0.011483526673358195, -0.10001000029764828, -0.3007099209055795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1406865455404655e-11, 0.0, 0.0, -0.15211903790385034, 0.0, -0.10212903790385035, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07593665318757832, -0.03494186219459571, 0.04089959488696079]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044816219928, 0.0, 0.012413830676965443, 0.0, 0.17609691084438509, 0.003339927396882776, 0.9645608983989093, -1.6263268161968243e-10, 0.005700881434231118, -9.184611526689736e-11, -0.9833156319906354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0547591907719455e-10, 0.0, 0.0, -0.004489547116977286, 0.0, -0.004489547116977286, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16179053826305503, -0.13467835200259912, 0.05233714729076094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20909933122141655, 0.0, 0.006670650904320104, 0.0, 0.030495423615918643, 0.06503905902363567, 0.3368018856169309, -0.1500000004820552, 0.011440160361093608, -0.10001000029910548, -0.35070992075212937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.3006558612131775e-11, 0.0, 0.0, -0.15232853483166567, 0.0, -0.10233853483166569, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08413105242809399, -0.04182726535714707, 0.04344111496186072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904486004547, 0.0, 0.011768217514409401, 0.0, 0.18224393180866655, -0.01916390271497888, 1.0000005002171315, -5.212497952851372e-11, -0.0008673262452917312, -2.9144014055440184e-11, -0.9999999969309965, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199386313454186e-10, 0.0, 0.0, -0.004189938556306829, 0.0, -0.004189938556306829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16388798481031347, -0.13770806325102714, 0.050830401497998626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20974928346196006, 0.0, 0.007240970887316747, 0.0, 0.03969175839498482, 0.06306744187433781, 0.386801910593047, -0.1500000004912826, 0.011142185474431066, -0.10001000030430325, -0.40070992068634476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.497529703852458e-11, 0.0, 0.0, -0.15253044088306777, 0.0, -0.10254044088306781, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09241791159321974, -0.048724268576277645, 0.045921626606422544]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044810870226, 0.0, 0.011406399659932879, 0.0, 0.1839266955813236, -0.03943234298595728, 1.0000004995223222, -1.8454778775646793e-10, -0.0059594977332508145, -1.0395538012366769e-10, -0.999999998684308, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.393747685278628e-10, 0.0, 0.0, -0.004038121028042349, 0.0, -0.004038121028042349, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16573718330251522, -0.13794006438261144, 0.04961023289123645]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21039923570296526, 0.0, 0.007732221462388101, 0.0, 0.048794427725561924, 0.06019460660459044, 0.4368019355081021, -0.15000000049922965, 0.010679004063671713, -0.10001000030875064, -0.45070992063834375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4712850532846104e-10, 0.0, 0.0, -0.15270186426513366, 0.0, -0.10271186426513369, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10078576245733886, -0.05550666059922085, 0.048349643723326334]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044820104153, 0.0, 0.009825011501427085, 0.0, 0.18205338661154202, -0.05745670539494751, 1.0000004983011015, -1.5894120516751055e-10, -0.009263628215187083, -8.894762340874952e-11, -0.9999999990399798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.443064165798729e-09, 0.0, 0.0, -0.0034284676413176727, 0.0, -0.0034284676413176727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16735701728238245, -0.1356478404588642, 0.04856034233807585]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21104918794604352, 0.0, 0.008147786332540378, 0.0, 0.05705228481887245, 0.056800807764968736, 0.48555193873788377, -0.15000000050177123, 0.01380061600121068, -0.1000100003101726, -0.500709920623694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2717270090655328e-10, 0.0, 0.0, -0.15284560293508898, 0.0, -0.102855602935089, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10920690437274234, -0.06180199580844874, 0.05069924429470897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861565058, 0.0, 0.008311297403045492, 0.0, 0.16515714186621044, -0.0678759767924341, 0.9750000645956334, -5.08317863654895e-11, 0.06243223875077937, -2.8439096560152044e-11, -0.9999999997070046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6008839115618438e-09, 0.0, 0.0, -0.00287477339910612, 0.0, -0.00287477339910612, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684228383080697, -0.12590670418455774, 0.04699201142765273]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21169914018422958, 0.0, 0.008534478083287349, 0.0, 0.06403777050224106, 0.05321928999215028, 0.5293019426708888, -0.1500000005195259, 0.024257018781159476, -0.10001000031997744, -0.5507099205508378, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.419726178962552e-10, 0.0, 0.0, -0.15298591053575372, 0.0, -0.10299591053575374, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11765685702945115, -0.06743100837199263, 0.05295855908556127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044763721124, 0.0, 0.007733835014939449, 0.0, 0.13970971366737228, -0.0716303554563691, 0.8749996308904224, -3.550929400220887e-10, 0.2091280555989759, -1.96096875850802e-10, -0.9999999985428758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2959983397940833e-09, 0.0, 0.0, -0.002806152013295014, 0.0, -0.002806152013295014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1689990531341761, -0.11258025127087788, 0.04518629581704597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21234909242042924, 0.0, 0.008919434834985456, 0.0, 0.07016762022951395, 0.0494175940147947, 0.5697185914419661, -0.15000000054176404, 0.04087900161373344, -0.10001000033265742, -0.6007099204582315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.172261176257898e-10, 0.0, 0.0, -0.1531310030940534, 0.0, -0.1031410030940534, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12613808298481552, -0.07263779449082776, 0.05515874228157932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044723993144, 0.0, 0.007699135033962173, 0.0, 0.12259699454545765, -0.07603391954711151, 0.8083329754215461, -4.4476326808857897e-10, 0.3324396566514793, -2.535997719814049e-10, -0.9999999981478731, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5050699945906894e-09, 0.0, 0.0, -0.0029018511659931385, 0.0, -0.0029018511659931385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16962451910728726, -0.10413572237670247, 0.04400366392036104]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21299904465715247, 0.0, 0.009293039493004852, 0.0, 0.0754688364483216, 0.04559216505320407, 0.6030519081311608, -0.1500000005651568, 0.06416199520211285, -0.1000100003461419, -0.650709920371305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.445127250908072e-10, 0.0, 0.0, -0.15327506561997678, 0.0, -0.1032850656199768, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13464324815966475, -0.07752258837267564, 0.057309669372721216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044734464905, 0.0, 0.007472093160387933, 0.0, 0.10602432437615295, -0.07650857923181258, 0.6666663199529763, -4.678550080457724e-10, 0.4656598717675884, -2.696896087189137e-10, -0.9999999982614709, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.545732149300358e-09, 0.0, 0.0, -0.002881250518467983, 0.0, -0.002881250518467983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17010330349698466, -0.09769587763695757, 0.04301854182283792]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21364899688939626, 0.0, 0.009658391636922252, 0.0, 0.07997391461622062, 0.041898905040172345, 0.6255518916748604, -0.15000000060235424, 0.09375928730575571, -0.10001000036752647, -0.7007099202590399, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.052037151899731e-09, 0.0, 0.0, -0.15341385722836937, 0.0, -0.10342385722836939, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1431656619275683, -0.08214254742847302, 0.0594179492930798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044644875767, 0.0, 0.007307042878347957, 0.0, 0.09010156335798036, -0.07386520026063448, 0.44999967087399106, -7.439485877121285e-10, 0.591945842072857, -4.276915516720644e-10, -0.999999997754698, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.150488536178495e-09, 0.0, 0.0, -0.002775832167851572, 0.0, -0.002775832167851572, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17044827535807106, -0.09239918111594755, 0.04216559840717177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21429894912892766, 0.0, 0.009985706783816878, 0.0, 0.0837337290217971, 0.038396160311925796, 0.6368018822133517, -0.15000000061579705, 0.12886795528830985, -0.10001000037561404, -0.7507099202145302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3798853267769924e-09, 0.0, 0.0, -0.15353458444110352, 0.0, -0.10354458444110352, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15169634264779158, -0.0864779427160285, 0.06148597299316276]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044790628024, 0.0, 0.006546302937892518, 0.0, 0.07519628811152951, -0.07005489456493094, 0.22499981076982642, -2.6885595931816126e-10, 0.7021733596510829, -1.6175154970901431e-10, -0.9999999991098066, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.556963497545229e-09, 0.0, 0.0, -0.002414544254682828, 0.0, -0.002414544254682828, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17061361440446554, -0.08670790575110973, 0.04136047400165921]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21494890137143005, 0.0, 0.010264454243218679, 0.0, 0.08678608163424363, 0.03505861876145826, 0.6405518772939177, -0.15000000062038576, 0.1686260343332976, -0.1000100003784644, -0.8007099201998603, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6795870208000474e-09, 0.0, 0.0, -0.15363358895884927, 0.0, -0.10364358895884926, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1602220150777761, -0.09043350824202971, 0.06351113278956284]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044850047567, 0.0, 0.005574949188036019, 0.0, 0.06104705224893067, -0.06675083100935077, 0.0749999016113218, -9.177432472503254e-11, 0.7951615808997544, -5.70071178666004e-11, -0.9999999997066031, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.9940338804610954e-09, 0.0, 0.0, -0.001980090354914737, 0.0, -0.001980090354914737, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17051344859969034, -0.07911131052002421, 0.040503195928001605]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2155988536133159, 0.0, 0.010512477538606261, 0.0, 0.08917333761613773, 0.031819375692793896, 0.6405518767334001, -0.1500000006268655, 0.21212016801686073, -0.10001000038266154, -0.8507099201793282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9436985414550135e-09, 0.0, 0.0, -0.1537173747429903, 0.0, -0.10372737474299028, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16872947233638164, -0.09391383418919608, 0.06549035882132435]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044837717048, 0.0, 0.004960465907751631, 0.0, 0.04774511963788189, -0.06478486137328723, -1.121035296536288e-08, -1.2959442582619387e-10, 0.8698826736712626, -8.394290868376176e-11, -0.9999999995893574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.282230413099323e-09, 0.0, 0.0, -0.0016757156828205056, 0.0, -0.0016757156828205056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17014914517211085, -0.06960651894332726, 0.03958452063523034]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624880583370626, 0.0, 0.010852328592641411, 0.0, 0.09096265279970184, 0.028608789864863603, 0.6405518797729715, -0.15000000069903854, 0.2584714183539546, -0.10001000043263603, -0.9007099200054107, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3562451393582777e-09, 0.0, 0.0, -0.15384859696269915, 0.0, -0.10385859696269913, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17721036787849695, -0.09688157501635633, 0.06742405875677049]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044407807097, 0.0, 0.006797021080703107, 0.0, 0.03578630367128222, -0.06421171655860582, 6.079142685293374e-08, -1.44346094321848e-09, 0.9270250067418772, -9.994897449842253e-10, -0.9999999965216487, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.250931958065287e-09, 0.0, 0.0, -0.0026244443941768753, 0.0, -0.0026244443941768753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1696179108423063, -0.05935481654320514, 0.03867399870892276]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21689875806718503, 0.0, 0.011300877429596479, 0.0, 0.09227873789315236, 0.02536685475345451, 0.6424268805905101, -0.15000000073163844, 0.30666902346985675, -0.10001000045630226, -0.9507099199307493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.8537136835463267e-09, 0.0, 0.0, -0.1540190682967799, 0.0, -0.10402906829677987, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1856660076880292, -0.09939784436400441, 0.06931951751056728]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904466957562, 0.0, 0.008970976739101277, 0.0, 0.026321701869010262, -0.06483870222818186, 0.037500016350772804, -6.51997879852614e-10, 0.9639521023180428, -4.733246865006198e-10, -0.9999999985067713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.949370883761092e-09, 0.0, 0.0, -0.0034094266816149916, 0.0, -0.0034094266816149916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1691127961906452, -0.050325386952961446, 0.03790917507593572]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2175487103087854, 0.0, 0.011770218513646671, 0.0, 0.0932714632554926, 0.022061943787337147, 0.64523938086188, -0.15000000073901393, 0.35573319838288087, -0.10001000046195532, -1.0007099199127507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.328029080500186e-09, 0.0, 0.0, -0.15419080038758087, 0.0, -0.10420080038758084, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19410546128967338, -0.10159406944352833, 0.07118853758681834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044832007294, 0.0, 0.009386821681003785, 0.0, 0.019854507246804855, -0.06609821932234719, 0.056250005427398664, -1.4750986883952772e-10, 0.9812834982604819, -1.1306130665252855e-10, -0.9999999996400307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.486307939077179e-09, 0.0, 0.0, -0.003434641816019505, 0.0, -0.003434641816019505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16878907203288349, -0.043924501590478456, 0.03738040152502133]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21819866255086648, 0.0, 0.012231417093476374, 0.0, 0.09406346139523418, 0.018684489860862883, 0.6485206308761887, -0.15000000074492958, 0.40480642523638716, -0.10001000046683238, -1.0507099198988972, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.7416997887180695e-09, 0.0, 0.0, -0.1543552077024912, 0.0, -0.10436520770249118, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20253867134741851, -0.10359818670415696, 0.07304196131361186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044841621763, 0.0, 0.009223971596594023, 0.0, 0.01583996279483155, -0.0675490785294853, 0.06562500028617337, -1.1831312535746496e-10, 0.981464537070126, -9.754100343302632e-11, -0.999999999722928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.273414164357678e-09, 0.0, 0.0, -0.00328814629820667, 0.0, -0.00328814629820667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1686642011549027, -0.040082345212572625, 0.037068474535870324]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21884861479282602, 0.0, 0.012681963178276325, 0.0, 0.0946896242576126, 0.015264962496134796, 0.648520630748284, -0.1500000007511614, 0.45381268570763494, -0.10001000047244901, -1.100709919885822, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.089003996019543e-09, 0.0, 0.0, -0.15451122196480946, 0.0, -0.10452122196480944, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.210969653422239, -0.10547787095288377, 0.07488452190797693]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904483919091, 0.0, 0.00901092169599902, 0.0, 0.01252325724756844, -0.06839054729456173, -2.558093556426222e-09, -1.246361466178929e-10, 0.9801252094249557, -1.1233270757581111e-10, -0.999999999738495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.9460841460294794e-09, 0.0, 0.0, -0.0031202852463652567, 0.0, -0.0031202852463652567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1686196414964095, -0.03759368497453624, 0.03685121188730116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21949856703278942, 0.0, 0.013147782374812735, 0.0, 0.09511874132783578, 0.011815420237923174, 0.6485206306468849, -0.15000000076362424, 0.5028362713185435, -0.1000100004846988, -1.1507099198571205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.399854768709976e-09, 0.0, 0.0, -0.15467290784359775, 0.0, -0.10468290784359774, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21939327077655743, -0.10720528731950858, 0.07671364924150878]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044799267624, 0.0, 0.009316383930728199, 0.0, 0.008582341404463636, -0.06899084516423246, -2.027981472628404e-09, -2.4925664219977295e-10, 0.9804717122181699, -2.449956832591036e-10, -0.9999999994259727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.217015453808661e-09, 0.0, 0.0, -0.0032337175757659285, 0.0, -0.0032337175757659285, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684723470863685, -0.03454832733249622, 0.036582546670637206]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2201485192742323, 0.0, 0.013623788941061686, 0.0, 0.09531906162784433, 0.008342026567448452, 0.6485206305832516, -0.1500000007715805, 0.551943502408045, -0.10001000049336234, -1.2007099198405284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.6742107292516785e-09, 0.0, 0.0, -0.15483629274046184, 0.0, -0.10484629274046184, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22780423022706894, -0.10874430297840229, 0.07852637152999838]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044828857465, 0.0, 0.009520131324979031, 0.0, 0.004006406000171084, -0.06946787340949447, -1.272666291182583e-09, -1.5912499862137065e-10, 0.982144621790032, -1.7327077473054033e-10, -0.9999999996681582, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.487119210834061e-09, 0.0, 0.0, -0.0032676979372821273, 0.0, -0.0032676979372821273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16821918901023017, -0.030780313177874098, 0.03625444576979181]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22079847151555543, 0.0, 0.014110573710590914, 0.0, 0.09527248824826526, 0.004849772608454271, 0.6485206305171828, -0.1500000007799317, 0.6011589517180577, -0.10001000050357446, -1.2507099198236151, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.917908082290279e-09, 0.0, 0.0, -0.15500069749687434, 0.0, -0.10501069749687432, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23619897491002814, -0.11007252304077374, 0.08032091153843443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044826462983, 0.0, 0.00973569539058459, 0.0, -0.0009314675915815165, -0.06984507917988361, -1.3213773837591944e-09, -1.6702433388508912e-10, 0.9843089862002536, -2.042423831144059e-10, -0.999999999661733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.873947060772019e-09, 0.0, 0.0, -0.0032880951282497186, 0.0, -0.0032880951282497186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16789489365918395, -0.026564401247428877, 0.03589080016872123]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2214484237568297, 0.0, 0.014607555872701287, 0.0, 0.09497283766926826, 0.0013440461490668407, 0.6485206304499114, -0.15000000078844067, 0.6504789457596579, -0.10001000051549594, -1.3007099198066143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.137772956576989e-09, 0.0, 0.0, -0.15516612963298104, 0.0, -0.10517612963298102, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24457550109843162, -0.1111813882913863, 0.08209660339454215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825485388, 0.0, 0.009939643242207502, 0.0, -0.0059930115799399514, -0.07011452918774859, -1.3454284400697918e-09, -1.7017965170917594e-10, 0.9863998808320041, -2.384294710003577e-10, -0.9999999996599848, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.397297485734195e-09, 0.0, 0.0, -0.003308642722134026, 0.0, -0.003308642722134026, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16753052376806973, -0.022177305012251246, 0.03551383712215434]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2220983759980697, 0.0, 0.015113155745422463, 0.0, 0.094420946483, -0.00216903209190683, 0.6485206303817854, -0.15000000079706255, 0.6998873937161252, -0.10001000052969553, -1.3507099197898365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.339860708042743e-09, 0.0, 0.0, -0.1553326177339662, 0.0, -0.10534261773396618, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2529327762420183, -0.11207104885059285, 0.08385345624777664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044824800344, 0.0, 0.01011199745442348, 0.0, -0.011037823725364899, -0.0702615648194734, -1.36251809128989e-09, -1.7243747943025986e-10, 0.9881689591293462, -2.8399178713010005e-10, -0.9999999996644424, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.041755029315071e-09, 0.0, 0.0, -0.0033297620197030595, 0.0, -0.0033297620197030595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16714550287173405, -0.017793211184131, 0.03513705706468985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2227483282393383, 0.0, 0.015625098975479503, 0.0, 0.093620623594063, -0.0056826996005171024, 0.6485206303142311, -0.15000000080560133, 0.7493661217053265, -0.10001000054682253, -1.4007099197734676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.528605922436317e-09, 0.0, 0.0, -0.15549994685252458, 0.0, -0.10550994685252457, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2612702553209708, -0.11274564918306716, 0.08559178033665367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825372041, 0.0, 0.01023886460114081, 0.0, -0.016006457778740255, -0.07027335017220546, -1.35108650252395e-09, -1.707753936836974e-10, 0.9895745597840248, -3.425400640587867e-10, -0.9999999996726217, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.77490428787147e-09, 0.0, 0.0, -0.0033465823711677648, 0.0, -0.0033465823711677648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16674958157904987, -0.013492006649486316, 0.03476648177754073]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2233982804809964, 0.0, 0.016151811965851602, 0.0, 0.09257620564835774, -0.009156325087475159, 0.6485206302546236, -0.15000000081299195, 0.7989015240881927, -0.10001000056552993, -1.450709919756761, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.705159646365449e-09, 0.0, 0.0, -0.15567149501929897, 0.0, -0.10568149501929895, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2695849884202265, -0.11321018105902551, 0.08731132032083022]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904483316163, 0.0, 0.01053425980744193, 0.0, -0.020888358914105103, -0.06947250973916112, -1.1921506773564672e-09, -1.4781249721503265e-10, 0.9907080476573255, -3.7414794840339533e-10, -0.9999999996658693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5310744785826864e-09, 0.0, 0.0, -0.0034309633354876598, 0.0, -0.0034309633354876598, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16629466198511336, -0.009290637519167127, 0.03439079968353114]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22404823272191543, 0.0, 0.01670179410018435, 0.0, 0.09129151724487952, -0.012500479729901572, 0.6485206301743803, -0.1500000008226585, 0.8484863196745451, -0.1000100005999739, -1.5007099197355778, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.878929188958743e-09, 0.0, 0.0, -0.1558516341873733, 0.0, -0.1058616341873733, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2778700636982681, -0.11346900053323304, 0.08901076988191917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044818381131, 0.0, 0.010999642686654917, 0.0, -0.02569376806956442, -0.06688309284852827, -1.604864356320739e-09, -1.9333113324994764e-10, 0.9916959117270491, -6.888796015496336e-10, -0.999999999576335, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4753908518658475e-09, 0.0, 0.0, -0.0036027833614867763, 0.0, -0.0036027833614867763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1657015055608328, -0.005176389484150449, 0.033988991221778946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22469818496266336, 0.0, 0.01727302224630608, 0.0, 0.08976962415618728, -0.01566518389626617, 0.6485206300896822, -0.15000000083282966, 0.8981147179182369, -0.10001000066253873, -1.550709919713898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.05375263058638e-09, 0.0, 0.0, -0.15603979627678075, 0.0, -0.10604979627678074, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28612148421272143, -0.11352576888950498, 0.09068942059720404]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044814958595, 0.0, 0.011424562922434602, 0.0, -0.03043786177384493, -0.06329408332729203, -1.6939617687373992e-09, -2.034231728748778e-10, 0.9925679648738353, -1.2512964352458322e-09, -0.9999999995664056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.496468832552792e-09, 0.0, 0.0, -0.0037632417881488765, 0.0, -0.0037632417881488765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1650284102890669, -0.0011353671254387982, 0.03357301430569766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2253481372038179, 0.0, 0.017857883151037084, 0.0, 0.08801295913639282, -0.01864200845186594, 0.6485206300166523, -0.15000000084171888, 0.9477818768895375, -0.10001000093137014, -1.600709919695662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.225456061526945e-09, 0.0, 0.0, -0.15623264261135686, 0.0, -0.10624264261135687, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2943383888579311, -0.1133835405829943, 0.09234727904522456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044823091095, 0.0, 0.011697218094620036, 0.0, -0.03513330039588935, -0.05953649111199532, -1.4605977778677033e-09, -1.7778429305701197e-10, 0.9933431794260119, -5.3766280833859315e-09, -0.9999999996352784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4340686188112653e-09, 0.0, 0.0, -0.003856926691522533, 0.0, -0.003856926691522533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16433809290419346, 0.002844566130213586, 0.033157168960410356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22599808944707864, 0.0, 0.01838578605757855, 0.0, 0.08726962042814145, -0.02148436347881346, 0.6485206299975904, -0.15000000084399806, 0.9972376593253539, -0.10149295659461942, -1.6507099196910697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.376292362635531e-09, 0.0, 0.0, -0.15640416717991285, 0.0, -0.10641416717991285, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3026367246767601, -0.11365840896765043, 0.09410203878694091]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044865214745, 0.0, 0.010558058130829375, 0.0, -0.014866774165027269, -0.05684710053895043, -3.812375620497551e-10, -4.558357211708274e-11, 0.9891156487163273, -0.029659113264985618, -0.9999999999081556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.0167260221717253e-09, 0.0, 0.0, -0.003430491371119661, 0.0, -0.003430491371119661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16596671637658011, -0.005497367693122679, 0.0350951948343271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22664804169059963, 0.0, 0.018840006748963932, 0.0, 0.08840492069765327, -0.024392733765289724, 0.6485206299842403, -0.15000000084544074, 1.0462943997134098, -0.10567192467666546, -1.7007099196880862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.501261782367847e-09, 0.0, 0.0, -0.1565485004968659, 0.0, -0.10655850049686588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3111261249822649, -0.11496549237911022, 0.09610529751097581]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044870419725, 0.0, 0.009084413827707609, 0.0, 0.02270600539023654, -0.05816740572952526, -2.6700106270383326e-10, -2.8853439740065987e-11, 0.9811348077611188, -0.08357936164092075, -0.9999999999403305, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.499388394646316e-09, 0.0, 0.0, -0.0028866663390606515, 0.0, -0.0028866663390606515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1697880061100957, -0.02614166822919553, 0.04006517448069801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2272979939338419, 0.0, 0.01922541003542927, 0.0, 0.09141088703754008, -0.027642250000865298, 0.6485206299622293, -0.15000000084759751, 1.0949260853578993, -0.11281341848140539, -1.7507099196836429, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.603990964623237e-09, 0.0, 0.0, -0.15666792998448356, 0.0, -0.10667792998448357, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31986597720360976, -0.11775797841320136, 0.09845562635552416]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044864845568, 0.0, 0.007708065729306733, 0.0, 0.060119326797736364, -0.06499032471151148, -4.4022066378222286e-10, -4.3135235934749456e-11, 0.9726337128897881, -0.14282987609479839, -0.9999999999111359, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0545836451077934e-09, 0.0, 0.0, -0.0023885897523536976, 0.0, -0.0023885897523536976, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17479704442689714, -0.05584972068182295, 0.0470065768909669]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22794794616049477, 0.0, 0.019663216868114303, 0.0, 0.09595724604108705, -0.031513928604466175, 0.6485206294161658, -0.1500000008953732, 1.1431581731527016, -0.122715114970351, -1.8007099195632277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.800086744031778e-09, 0.0, 0.0, -0.15681312023204916, 0.0, -0.10682312023204915, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32883625727994553, -0.12177903300371423, 0.1011975108086962]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044533057192, 0.0, 0.008756136653700739, 0.0, 0.09092718007093946, -0.07743357207201752, -1.0921269262070155e-08, -9.555133829885226e-10, 0.964641755896047, -0.19803392977891207, -0.9999999975916941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.921915588170908e-09, 0.0, 0.0, -0.0029038049513116803, 0.0, -0.0029038049513116803, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17940560152671553, -0.08042109181025732, 0.05483768906344095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2285978983789231, 0.0, 0.02019778242038303, 0.0, 0.1015934010784249, -0.03623301233749256, 0.6485206285389342, -0.1500000009630398, 1.191034592837942, -0.1349449256109987, -1.8507099194363694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.150230432186841e-09, 0.0, 0.0, -0.15700312472854858, 0.0, -0.10701312472854857, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33802112830129416, -0.12677509839018047, 0.10432340356810274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904436856656, 0.0, 0.010691311045374498, 0.0, 0.11272310074675733, -0.09438167466052755, -1.754463174687428e-08, -1.353332621585259e-09, 0.957528393704806, -0.24459621281295374, -0.9999999974628351, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.002873763101444e-09, 0.0, 0.0, -0.0038000899299882977, 0.0, -0.0038000899299882977, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1836974204269731, -0.09992130772932467, 0.06251785518813079]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22924785061936293, 0.0, 0.020737691803928926, 0.0, 0.1079149889944046, -0.04194605310748499, 0.648520628420636, -0.15000000097183167, 1.2385907035183767, -0.1490380006997704, -1.900709919420488, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.54569605950863e-09, -1.0426903683738898e-12, -2.5514401118195656e-13, -0.15719728381705064, 0.0, -0.10720728381705065, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34741095355339363, -0.13253875137666998, 0.10778053041429005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044808796163, 0.0, 0.010798187670917945, 0.0, 0.1264317583195939, -0.11426081539984874, -2.3659661644447584e-09, -1.758371953475359e-10, 0.9511222136086955, -0.28186150177543445, -0.9999999996823721, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.909312546435763e-09, -2.0853807367477396e-11, -5.102880223639271e-12, -0.0038831817700415243, 0.0, -0.0038831817700415243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1877965050419889, -0.11527305972979002, 0.06914253692374604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22989780285812036, 0.0, 0.02125959858857387, 0.0, 0.11459825854316781, -0.048710905661322045, 0.6485206282489472, -0.15000000098414312, 1.2858556284373268, -0.16454561561375944, -1.95070991939866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.94278953324394e-09, -3.0403320506258407e-12, -7.733889766789014e-13, -0.1573814351600216, 0.0, -0.1073914351600216, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35699897437664574, -0.1389038744794559, 0.11147550916898084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044775148969, 0.0, 0.010438135692898963, 0.0, 0.13366539097526417, -0.1352970510767411, -3.4337746962637712e-09, -2.462290677275148e-10, 0.9452984983790007, -0.3101522982797803, -0.9999999995634374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.941869474706234e-09, -3.9952833645039244e-11, -1.0364899309938878e-11, -0.003683026859419063, 0.0, -0.003683026859419063, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19176041646504177, -0.12730246205571835, 0.07389957509381602]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23054775485035695, 0.0, 0.02186462247148685, 0.0, 0.12138908799278897, -0.05649667516409468, 0.6485206158107779, -0.15000000156864474, 1.3328638233173495, -0.1810319198486464, -2.0007099189910917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 9.414842788505576e-09, -1.913049931177333e-11, -7.77090301008133e-12, -0.15759512833415784, 0.0, -0.10760512833415783, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.36677876288705563, -0.14573363422859614, 0.11527847017272014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999039844731473, 0.0, 0.012100477658259558, 0.0, 0.1358165889924233, -0.15571539005545265, -2.487633863473451e-07, -1.1690032168508873e-08, 0.9401638976004553, -0.3297260846977389, -0.9999999918486393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9441065105232425e-08, -3.2180334522297096e-10, -1.3995028066804872e-10, -0.004273863482724726, 0.0, -0.004273863482724726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19559577020819743, -0.13659519498280495, 0.0760592200747859]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23119770702939135, 0.0, 0.022479608442008768, 0.0, 0.1279280117911787, -0.065121020276135, 0.6485206148580289, -0.15000000167904998, 1.379268106179796, -0.19791953321164663, -2.050709918719779, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1115903595142684e-08, -3.7857343609259916e-11, -1.6258580684052826e-11, -0.15780800249453208, 0.0, -0.10781800249453208, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37671058105571864, -0.15275282186605943, 0.11903688852937533]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043580687947, 0.0, 0.012299719410438332, 0.0, 0.13077847596779463, -0.17248690224080668, -1.9054980297925722e-08, -2.2081048098157728e-09, 0.9280856572489296, -0.33775226726000473, -0.9999999945737411, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4021216132742206e-08, -3.7453688594973177e-10, -1.6975355347942991e-10, -0.004257483207484845, 0.0, -0.004257483207484845, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19863636337325982, -0.1403837527492658, 0.07516836713310386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23184765806519372, 0.0, 0.023097359065355757, 0.0, 0.13365869955507467, -0.0740114373450419, 0.648520609543342, -0.15000000225457907, 1.422965171830249, -0.2143799827745139, -2.098938326600579, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2753217741840951e-08, -5.477721509148242e-11, -2.479893808615554e-11, -0.15801118959641505, 0.0, -0.10802118959641506, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38667228016511457, -0.15934750061329966, 0.12262207163908631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999020716047414, 0.0, 0.012355012466939775, 0.0, 0.11461375527791967, -0.17780834137813792, -1.0629373828857953e-07, -1.1510581868469042e-08, 0.8739413130090581, -0.32920899125734515, -0.9645681576160031, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2746282933965545e-08, -3.3839742964445013e-10, -1.7080714804205447e-10, -0.004063742037659556, 0.0, -0.004063742037659556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19923398218791882, -0.1318935749448046, 0.07170366219421956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23245135821315047, 0.0, 0.023651585936944827, 0.0, 0.13815819787098435, -0.08241848935617074, 0.6485206092120694, -0.15000000230184185, 1.4618918239728365, -0.22965107487618347, -2.1424723141088395, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4136978914913975e-08, -6.858577382316248e-11, -3.2198187894587434e-11, -0.1581851245947468, 0.0, -0.1081951245947468, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.39652166044585796, -0.16493414836225212, 0.12594494847795754]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012074002959135122, 0.0, 0.011084537431781408, 0.0, 0.08998996631819364, -0.168141040222577, -6.625452348267423e-09, -9.45255599426992e-10, 0.7785330428517518, -0.30542184203339134, -0.8706797501652095, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7675223461460466e-08, -2.761711746336011e-10, -1.4798499616863783e-10, -0.0034786999666346586, 0.0, -0.0034786999666346586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1969876056148681, -0.1117329549790489, 0.0664575367774243]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23285989429464005, 0.0, 0.02419511714977966, 0.0, 0.14131225010848045, -0.0898134535250838, 0.6485205149756879, -0.1500000089914203, 1.495152825295853, -0.24331436077630994, -2.1798187931733968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5447162340067583e-08, -7.652653702333584e-11, -4.001337926033458e-11, -0.15834547722401884, 0.0, -0.10835547722401885, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4061537540659481, -0.1693192033094132, 0.12896743830993018]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00817072162979149, 0.0, 0.01087062425669661, 0.0, 0.06308104474992204, -0.1478992833782612, -1.884727631173058e-06, -1.3379156886403865e-07, 0.6652200264603333, -0.2732657180025293, -0.7469295812911407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6203668503072155e-08, -1.5881526400346788e-10, -1.5630382731494277e-10, -0.0032070525854411263, 0.0, -0.0032070525854411263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19264187240180328, -0.08770109894322164, 0.06044979663945314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23316043961107294, 0.0, 0.024683460882710104, 0.0, 0.1432128769062681, -0.09596026849169326, 0.6485205123525173, -0.15000000929612767, 1.5228839367369664, -0.2552221568668601, -2.2108423424890757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.655090754999538e-08, -8.102564817971736e-11, -4.69006156900477e-11, -0.1584821114118807, 0.0, -0.10849211141188071, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4155034423213876, -0.1725549049097725, 0.1316930425490508]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006010906328657944, 0.0, 0.009766874658608898, 0.0, 0.03801253595575331, -0.12293629933218929, -5.2463411205057644e-08, -6.0941472099821464e-09, 0.5546222288222695, -0.23815592181100403, -0.6204709863135772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.207490419855599e-08, -8.998222312763029e-11, -1.3774472859426245e-10, -0.0027326837572372873, 0.0, -0.0027326837572372873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18699376510878926, -0.06471403200718603, 0.054512084782412214]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2333369060458328, 0.0, 0.025114299395530355, 0.0, 0.1439269508242421, -0.10083243379924917, 0.6485204510966678, -0.15000001299672583, 1.54515403048778, -0.2651015799290508, -2.2355695879325537, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.743531022887847e-08, -8.324714988240809e-11, -5.2528139737987404e-11, -0.15859639542015294, 0.0, -0.10860639542015293, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42453664662085777, -0.17471857585836037, 0.13414260325659544]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003529328695197331, 0.0, 0.008616770256405035, 0.0, 0.014281478359479665, -0.09744330615111815, -1.2251169898690067e-06, -7.401196309132527e-08, 0.4454018750162714, -0.19758846124381368, -0.4945449088695583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7688053577661782e-08, -4.443003405381462e-11, -1.1255048095879397e-10, -0.0022856801654445, 0.0, -0.0022856801654445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18066408598940384, -0.04327341897175778, 0.0489912141508933]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23345017649183689, 0.0, 0.025562334333568262, 0.0, 0.14357636122608883, -0.10451823588294969, 0.6485101834368872, -0.15000054767467796, 1.5624187928456847, -0.2728285129098619, -2.2545327200363254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8157099414399842e-08, -8.274047766673912e-11, -5.706207400326252e-11, -0.15871208351056104, 0.0, -0.10872208351056104, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4332632851844255, -0.1759432136987451, 0.1363534142706526]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002265408920081733, 0.0, 0.008960698760758133, 0.0, -0.007011791963065454, -0.07371604167401051, -0.0002053531956116083, -1.0693559042482743e-05, 0.3452952471580932, -0.15453865961622157, -0.37926264207543503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4435783710427439e-08, 1.0133444313378143e-11, -9.067868530550222e-11, -0.0023137618081619004, 0.0, -0.0023137618081619004, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17453277127135441, -0.024492756807694447, 0.04421622028114328]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23354709943893084, 0.0, 0.026043600688978333, 0.0, 0.1423391612726244, -0.10717185771402409, 0.6484829928122745, -0.15000157811889386, 1.575495048324172, -0.27848788988709283, -2.268675988531895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.876306294518793e-08, -7.940160949018136e-11, -6.069441931571837e-11, -0.15883498246556102, 0.0, -0.10884498246556101, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4417199197563183, -0.1764044824743997, 0.1383686839588234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001938458941878926, 0.0, 0.009625327108201341, 0.0, -0.02474399906928895, -0.0530724366214879, -0.0005438124922535102, -2.060888431814506e-05, 0.2615251095697489, -0.11318753954461916, -0.2828653699113879, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2119270615761769e-08, 6.677736353115447e-11, -7.264690624911709e-11, -0.0024579790999995853, 0.0, -0.0024579790999995853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16913269143785647, -0.009225375513091567, 0.04030539376341641]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23364652157190524, 0.0, 0.026556752697781537, 0.0, 0.14040895031317793, -0.10897826494258968, 0.6484506764544448, -0.15000231245062512, 1.5853100379868694, -0.2822949838046462, -2.2790832430492185, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9283335534337668e-08, -7.365447402695554e-11, -6.360258672928566e-11, -0.1589653270094304, 0.0, -0.10897532700943038, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4499550693901091, -0.17628389829245467, 0.14023045577806884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0019884426594877743, 0.0, 0.010263040176064095, 0.0, -0.03860421918892897, -0.03612814457131189, -0.0006463271565940428, -1.4686634625192808e-05, 0.1962997932539462, -0.07614187835106714, -0.20814509034647016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.040545178299469e-08, 1.1494270926451437e-10, -5.8163348271345824e-11, -0.002606890877387421, 0.0, -0.002606890877387421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16470299267581576, 0.0024116836389002534, 0.037235436384908435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23375242036731944, 0.0, 0.02701269615353316, 0.0, 0.13796471176186845, -0.11012488014858206, 0.6484420122943285, -0.15000231409845804, 1.592714475557891, -0.2844994933582057, -2.2867618159945082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9700681088802365e-08, -6.778668525192253e-11, -6.58427538699814e-11, -0.1590799785840921, 0.0, -0.10908997858409208, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45801907665713304, -0.17574337830544842, 0.14197591694161615]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021179759082840667, 0.0, 0.009118869115032461, 0.0, -0.048884771026189856, -0.022932304119847646, -0.0001732832023256829, -3.2956658318118945e-08, 0.1480887514204333, -0.0440901910711896, -0.1535714589057927, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.346911089293952e-09, 1.1735577550066008e-10, -4.4803342813914826e-11, -0.0022930314932340158, 0.0, -0.0022930314932340158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1612801453404785, 0.01081039974012472, 0.0349092232709461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2338659231946939, 0.0, 0.02739183408059816, 0.0, 0.1351537360195266, -0.11077871517158902, 0.6484419114911212, -0.15000231495767824, 1.5984225593442756, -0.285403703581227, -2.2925319789193237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.0023603628948926e-08, -6.263298434069478e-11, -6.753049879912866e-11, -0.15917367500587645, 0.0, -0.10918367500587643, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4659573541300894, -0.17491238699337666, 0.14363572379574532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022700565474893446, 0.0, 0.007582758541299972, 0.0, -0.056219514846836766, -0.013076700460139264, -2.016064146821944e-06, -1.7184403942960408e-08, 0.11416167572768893, -0.018084204460426342, -0.11540325849630509, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.458450802931198e-09, 1.0307401822455513e-10, -3.375489858294525e-11, -0.0018739284356870326, 0.0, -0.0018739284356870326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1587655494591269, 0.016619826241435015, 0.03319613708258321]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23398556698750417, 0.0, 0.02772923012901613, 0.0, 0.1320890483878322, -0.11107868538223692, 0.6484412723115424, -0.1500023294154196, 1.6029762536193908, -0.2853156659470832, -2.2970090050427263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.029681071934546e-08, -5.708160534809578e-11, -6.886716390910505e-11, -0.15925503418648854, 0.0, -0.1092650341864885, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4738073947305494, -0.17388639393446054, 0.1452339426197058]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002392875856205386, 0.0, 0.00674792096835945, 0.0, -0.061293752633888074, -0.005999404212957951, -1.2783591576158763e-05, -2.891548274544786e-07, 0.09107388550230336, 0.001760752682876357, -0.08954052246805287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.464141807930622e-09, 1.1102757985198014e-10, -2.673330219952771e-11, -0.001627183612241516, 0.0, -0.001627183612241516, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15700081200920052, 0.020519861178322725, 0.031964376479209494]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23410933325183225, 0.0, 0.028041757235566504, 0.0, 0.12885354001162114, -0.11113396841962918, 0.6484407596160549, -0.15000233629890292, 1.606758771783485, -0.2845093177805187, -2.3006272165494317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.0544374693364325e-08, -5.072118956612593e-11, -6.997768868039825e-11, -0.1593288285119097, 0.0, -0.10933882851190965, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48159827706432196, -0.17273214936617354, 0.14678881974330207]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024753252865618923, 0.0, 0.006250542131007422, 0.0, -0.06471016752422128, -0.001105660747845156, -1.0253909750451642e-05, -1.3766966598552862e-07, 0.07565036328188371, 0.01612696333128955, -0.07236423013410599, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.9512794803773375e-09, 1.2720831563939715e-10, -2.2210495425864007e-11, -0.0014758865084229585, 0.0, -0.0014758865084229585, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15581764667545103, 0.02308489136573995, 0.031097542471925504]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23423554484492332, 0.0, 0.028339901647175095, 0.0, 0.1255060827783855, -0.11102612778323918, 0.6484402619865923, -0.15000234480641825, 1.6100286309160716, -0.28320582600245575, -2.303679494496613, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.0780496730469134e-08, -4.340206095585463e-11, -7.094423079902275e-11, -0.15939837859081107, 0.0, -0.10940837859081105, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4893514699409288, -0.17149484925818256, 0.1483138298766744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025242318618210954, 0.0, 0.005962888232171783, 0.0, -0.06694914466471238, 0.0021568127277997824, -9.952589251615955e-06, -1.7015030668549262e-07, 0.06539718265173003, 0.026069835561258504, -0.06104555894362565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.7224407420962155e-09, 1.46382572205426e-10, -1.9330842372489993e-11, -0.0013910015780279055, 0.0, -0.0013910015780279055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15506385753213695, 0.02474600215981932, 0.03050020266744668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2343629979787527, 0.0, 0.028629881713542624, 0.0, 0.12208749661852794, -0.11081339225980956, 0.6484397557360918, -0.1500023538862766, 1.6129545121371744, -0.2815713323764946, -2.3063569083418605, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1012427442448405e-08, -3.5163358655847117e-11, -7.181962946838004e-11, -0.15946573014865476, 0.0, -0.10947573014865475, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49708217220689543, -0.17020460292446507, 0.14981871818366843]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002549062676587914, 0.0, 0.0057996013273505466, 0.0, -0.06837172319715155, 0.004254710468592533, -1.0125010009834757e-05, -1.8159716706827383e-07, 0.05851762442205703, 0.032689872519222105, -0.053548276904955755, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.638614239585403e-09, 1.6477404600015038e-10, -1.7507973387145735e-11, -0.0013470311568738798, 0.0, -0.0013470311568738798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15461404531933265, 0.025804926674350016, 0.03009776613988055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2344908947129585, 0.0, 0.02891514143485623, 0.0, 0.11862556742783333, -0.11053560118320818, 0.6484392457343992, -0.15000236267571637, 1.6156441061162783, -0.2797237903429685, -2.308781248566564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.124305099563389e-08, -2.619252949260472e-11, -7.264496270161636e-11, -0.15953199500685766, 0.0, -0.10954199500685766, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5048007515332844, -0.16888140656508638, 0.15131041571608805]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002557934684115954, 0.0, 0.005705194426272128, 0.0, -0.06923858381389242, 0.0055558215320275954, -1.0200033852804097e-05, -1.757887952344529e-07, 0.05379187958207796, 0.036950840670521616, -0.04848680449407016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.612471063709708e-09, 1.7941658326484802e-10, -1.650666466472641e-11, -0.0013252971640581462, 0.0, -0.0013252971640581462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.154371586527779, 0.026463927187573878, 0.029833950648392425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23461872265981276, 0.0, 0.02919743985561392, 0.0, 0.11513892872436539, -0.11021890289895717, 0.6484387355717922, -0.15000237065113722, 1.618165247200876, -0.2777431204985583, -2.3110289223764098, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1472827714829075e-08, -1.6725966771297862e-11, -7.344981498682178e-11, -0.1595976962105436, 0.0, -0.10960769621054359, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5125140418872783, -0.16753861945170317, 0.15279378595491294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025565589370850476, 0.0, 0.005645968415153752, 0.0, -0.06973277406935874, 0.006333965685020402, -1.0203252138787573e-05, -1.5950841693143406e-07, 0.05042282169195538, 0.039613396888204463, -0.04495347619691749, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.59553438390374e-09, 1.8933125442613705e-10, -1.6097045704108537e-11, -0.0013140240737186954, 0.0, -0.0013140240737186954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15426580707987964, 0.02685574226766386, 0.029667404776497663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2347461471374862, 0.0, 0.029477599995726585, 0.0, 0.11163990556434744, -0.10987973971251085, 0.6484382233230851, -0.15000237756329504, 1.6205602544718025, -0.2756812906295641, -2.3131472731768437, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1701078306136764e-08, -6.993056465398058e-12, -7.425431396593362e-11, -0.15966303455978986, 0.0, -0.10967303455978986, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5202263989088121, -0.16618525114532579, 0.1542722034166537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002548489553469015, 0.0, 0.005603202802253336, 0.0, -0.06998046320035903, 0.006783263728926491, -1.0244974141707887e-05, -1.3824315639164396e-07, 0.04790014541852751, 0.04123659737988409, -0.042367016008675464, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.56501182615382e-09, 1.9465820611799593e-10, -1.6089979582236827e-11, -0.0013067669849253284, 0.0, -0.0013067669849253284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15424714043067508, 0.0270673661275478, 0.029568349234815418]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23487293390634528, 0.0, 0.029755978211713916, 0.0, 0.1081365208677483, -0.10952797063519008, 0.6484377017612931, -0.1500023833413627, 1.6228551870399055, -0.27357077867490387, -2.3151651896169314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1926716644642806e-08, 2.8090770400611453e-12, -7.507133980198243e-11, -0.1597280609129997, 0.0, -0.10973806091299969, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5279404990685906, -0.16482741443172033, 0.15574798584011823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025357353771814925, 0.0, 0.005567564319746647, 0.0, -0.07006769393198281, 0.00703538154641534, -1.0431235839951606e-05, -1.1556135324608088e-07, 0.0458986513620609, 0.04221023909320415, -0.040358328801756035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.5127667701208695e-09, 1.9604267010918394e-10, -1.6340516720975946e-11, -0.0013005270641966514, 0.0, -0.0013005270641966514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15428200319557223, 0.027156734272109136, 0.029515648469290202]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2349989021130141, 0.0, 0.0300333514128411, 0.0, 0.10463387576098314, -0.10916917013363675, 0.6484370973216877, -0.15000239042048158, 1.6250656753822348, -0.27143102121542395, -2.317099787078903, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2149321376928164e-08, 1.2553336564362067e-11, -7.591152658572583e-11, -0.15979297149496838, 0.0, -0.10980297149496836, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.535657913314235, -0.1634692395911408, 0.15722270859887044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00251936413337637, 0.0, 0.00554746402254369, 0.0, -0.07005290213530335, 0.00717601003106655, -1.2088792106869578e-05, -1.4158237737221335e-07, 0.04420976684658694, 0.04279514918959882, -0.038691949239432324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.452094645707175e-09, 1.948851904860186e-10, -1.6803735674868066e-11, -0.0012982116393735102, 0.0, -0.0012982116393735102, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15434828491288669, 0.02716349681159085, 0.02949445517504397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23512389711455098, 0.0, 0.030311467457312107, 0.0, 0.10113508399282219, -0.10880623805666632, 0.6484362838140256, -0.15000240293111636, 1.6272005468312238, -0.26927300752371003, -2.318960565199986, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2369780858839134e-08, 2.219962092500878e-11, -7.67876467415067e-11, -0.15985827654600593, 0.0, -0.10986827654600592, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5433795022060451, -0.16211345620762432, 0.1586974290101216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002499900030737275, 0.0, 0.005562320889420086, 0.0, -0.0699758353632191, 0.007258641539408401, -1.627015324160636e-05, -2.502126954737701e-07, 0.042697428979782154, 0.04316027383427814, -0.03721556242165659, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.409189638219435e-09, 1.9292568721293418e-10, -1.7522403115617473e-11, -0.0013061010207512567, 0.0, -0.0013061010207512567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15443177783620432, 0.02711566767032933, 0.029494408225023354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23524777415625286, 0.0, 0.03059189952242291, 0.0, 0.09764189813496264, -0.10844048376721195, 0.6484352335277774, -0.15000242074401485, 1.6292640292954501, -0.2671023824056519, -2.3207520248452713, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.258896989012391e-08, 3.1728884400891745e-11, -7.770987037437262e-11, -0.1599244143640249, 0.0, -0.1099344143640249, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5511056793095391, -0.16076177191939214, 0.1601728438952585]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024775408340380013, 0.0, 0.005608641302216077, 0.0, -0.06986371715719096, 0.007315085789087459, -2.1005724963301243e-05, -3.5625796992647297e-07, 0.04126964928452708, 0.04341250236116362, -0.035829192905704674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.383780625695489e-09, 1.9058526951765944e-10, -1.8444472657318492e-11, -0.001322756360379724, 0.0, -0.001322756360379724, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15452354206987995, 0.027033685764643694, 0.029508297702737815]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23537037467807018, 0.0, 0.030844804304131584, 0.0, 0.09415512059614983, -0.10807236438422016, 0.6484351923730954, -0.15000242148205567, 1.6312566575858614, -0.264921371051575, -2.3224754827187453, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.277676354631131e-08, 3.9821514704439934e-11, -7.851289453323425e-11, -0.1599832570734113, 0.0, -0.1099932570734113, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5588365789779075, -0.15941510406309659, 0.16164939731444897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002452010436346326, 0.0, 0.00505809563417353, 0.0, -0.06973555077625619, 0.0073623876598357466, -8.23093639646332e-07, -1.4760816422144336e-08, 0.03985256580822472, 0.04362022708153831, -0.03446915746947815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.755873123748003e-09, 1.6185260607096375e-10, -1.6060483177232553e-11, -0.0011768541877280017, 0.0, -0.0011768541877280017, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1546179933673668, 0.026933357125911103, 0.02953106838380959]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2354836315201696, 0.0, 0.031066841292699415, 0.0, 0.0906870719313321, -0.10770757186704713, 0.6484350279421831, -0.15000242320180887, 1.6331580314333565, -0.26256078061520977, -2.3241134405567734, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2928484863876526e-08, 4.623222790995583e-11, -7.91570905998172e-11, -0.16003388303076396, 0.0, -0.11004388303076396, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5665751226248817, -0.15808307098830915, 0.16312852739624395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002265136841988309, 0.0, 0.004440739771356601, 0.0, -0.06936097329635471, 0.007295850343460581, -3.2886182473096295e-06, -3.439506419699579e-08, 0.03802747694990197, 0.04721180872730438, -0.032759156760566545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.0344263513042983e-09, 1.2821426411031797e-10, -1.2883921331658946e-11, -0.0010125191470531324, 0.0, -0.0010125191470531324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15477087293948397, 0.026640661495748903, 0.02958260163589951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23559656211997387, 0.0, 0.03126175174443458, 0.0, 0.0872353188644252, -0.10734382767416505, 0.6484348713614603, -0.15000242499389568, 1.63495937295192, -0.2601321012863367, -2.325655742633186, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3047582135683344e-08, 5.1122738374509406e-11, -7.965204263503365e-11, -0.16007746291508265, 0.0, -0.11008746291508266, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5743205463471606, -0.15676160338141618, 0.16461014198475066]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022586119960855116, 0.0, 0.003898209034703265, 0.0, -0.06903506133813807, 0.007274883857641698, -3.131614457582905e-06, -3.584173605088328e-08, 0.03602683037127282, 0.04857358657746172, -0.030846041528253598, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3819454361363837e-09, 9.781020929107155e-11, -9.899040704328936e-12, -0.0008715976863739917, 0.0, -0.0008715976863739917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15490847444557623, 0.026429352137859234, 0.02963229177013412]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23570915057465264, 0.0, 0.031540970928845294, 0.0, 0.08379641732109279, -0.10697830924524152, 0.6484197552576919, -0.15000285972089877, 1.6366636889471027, -0.25773627360033774, -2.327090837444873, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3170772975423448e-08, 5.4771638370600525e-11, -8.002292789821144e-11, -0.16014943596475342, 0.0, -0.11015943596475344, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5820719956248928, -0.1554453376796855, 0.16609403874555245]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022517690935752598, 0.0, 0.005584383688214324, 0.0, -0.06877803086664841, 0.0073103685784705955, -0.00030232207536811984, -8.694540062029453e-06, 0.03408631990365086, 0.047916553719978355, -0.02870189623374077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.463816794802012e-09, 7.297799992182236e-11, -7.417705263555998e-12, -0.0014394609934156705, 0.0, -0.0014394609934156705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15502898555464278, 0.026325314034613773, 0.029677935216036025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2358194659869966, 0.0, 0.03181854915846394, 0.0, 0.0803671521382902, -0.10661112535396337, 0.6484161242735884, -0.1500028609574039, 1.6382533810006044, -0.2554066397583302, -2.32841650797076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3278802346883926e-08, 5.745706941078317e-11, -8.02966204087127e-11, -0.16022208724964926, 0.0, -0.11023208724964927, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5898286661390962, -0.154129578309216, 0.16757998178875053]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002206308246879396, 0.0, 0.005551564592372899, 0.0, -0.06858530365605174, 0.00734367782556294, -7.261968206977143e-05, -2.4730102184566027e-08, 0.03179384107003346, 0.04659267684015055, -0.026513410517737597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.160587429209571e-09, 5.37086208036528e-11, -5.473850210025159e-12, -0.0014530256979164928, 0.0, -0.0014530256979164928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1551334102840702, 0.02631518740938986, 0.029718860863961503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2359279954535198, 0.0, 0.03217028921619197, 0.0, 0.07694488220338354, -0.10624041162445719, 0.6483972110764464, -0.1500033694319681, 1.6397360439895363, -0.25314024043509153, -2.3296255061597675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3403253279245123e-08, 5.94162643069729e-11, -8.049664267194146e-11, -0.1603169870954875, 0.0, -0.11032698709548751, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5975899625219483, -0.15281293508775598, 0.1690678207444054]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021705893304641262, 0.0, 0.007034801154560681, 0.0, -0.06844539869813324, 0.007414274590123609, -0.00037826394283997866, -1.016949128399572e-05, 0.02965325977863748, 0.045327986464774116, -0.024179963780147987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.489018647223943e-09, 3.918389792379487e-11, -4.000445264575243e-12, -0.0018979969167648638, 0.0, -0.0018979969167648638, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1552259276570421, 0.026332864429200485, 0.029756779113097417]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23603405254605822, 0.0, 0.03259618232668198, 0.0, 0.07352686979763058, -0.10586538433915092, 0.6483659200144282, -0.15000386058177903, 1.641110178012199, -0.25091267331839673, -2.330715621332648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3531875170512757e-08, 6.083756754420044e-11, -8.064191314216345e-11, -0.16043288770673927, 0.0, -0.11044288770673928, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6053552688449194, -0.1514947659210473, 0.1705573698579185]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021211418507682865, 0.0, 0.008517862209800301, 0.0, -0.06836024811505906, 0.007500545706125172, -0.0006258212403663213, -9.822996218828881e-06, 0.027482680453252546, 0.04455134233389597, -0.021802303457615586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.572437825352757e-09, 2.8426064744550706e-11, -2.905409404439761e-12, -0.00231801222503555, 0.0, -0.00231801222503555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15530612645942193, 0.02636338333417354, 0.02979098227026193]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23613749610560622, 0.0, 0.03308120550237276, 0.0, 0.07011046049973069, -0.10548538707061689, 0.6483247101640359, -0.1500043808489106, 1.6423728979116206, -0.24869770796241325, -2.3316853207443002, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3658183034947667e-08, 6.18648421629815e-11, -8.074698818090143e-11, -0.16056407199672149, 0.0, -0.11057407199672148, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6131240172128315, -0.15017474753212554, 0.17204843860793395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020688711909601053, 0.0, 0.009700463513815516, 0.0, -0.06832818595799789, 0.007599945370680642, -0.0008241970078448187, -1.040534263119019e-05, 0.0252543979884313, 0.04429930711966955, -0.019393988233042676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5261572886982225e-09, 2.054549237562139e-11, -2.101500774759419e-12, -0.0026236857996440478, 0.0, -0.0026236857996440478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1553749673582423, 0.026400367778435477, 0.029821375000309066]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23623828589247167, 0.0, 0.03361081915501, 0.0, 0.06669324887728778, -0.10509973933716733, 0.6482729354688894, -0.15000500072272843, 1.6435218643866791, -0.24647506327902116, -2.3325323130044975, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3780143809386652e-08, 6.260550923664847e-11, -8.082278475744289e-11, -0.1607054735129628, 0.0, -0.11071547351296278, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6208957313787304, -0.14885252901324492, 0.1735408530825426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020157957373092943, 0.0, 0.010592273052744787, 0.0, -0.06834423244885818, 0.007712954668990981, -0.0010354939029294285, -1.2397476356777747e-05, 0.022979329501171496, 0.044452893667841706, -0.01693984520394583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4392154887796924e-09, 1.4813341473339263e-11, -1.5159315308292773e-12, -0.0028280303248260606, 0.0, -0.0028280303248260606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15543428331797998, 0.026444370377612537, 0.029848289492172976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2363363583766248, 0.0, 0.034173608578940855, 0.0, 0.06327312385326757, -0.10470779835859415, 0.6482080378614357, -0.15000575155892074, 1.6445553163821707, -0.24423156960560957, -2.3332532328515225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.389743788551014e-08, 6.313866403826305e-11, -8.087736330003845e-11, -0.16085347614389675, 0.0, -0.11086347614389674, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6286700407631273, -0.14752756669020284, 0.17503446393720964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001961449683062611, 0.0, 0.011255788478617176, 0.0, -0.06840250048040437, 0.007838819571463835, -0.0012979521490758517, -1.5016723846254982e-05, 0.020669039909832355, 0.04486987346823152, -0.014418396940501467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3458815224696854e-09, 1.0663096032291786e-11, -1.0915708519109832e-12, -0.002960052618679262, 0.0, -0.002960052618679262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15548618768793607, 0.026499246460841664, 0.02987221709334078]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23643099336676607, 0.0, 0.03469421185181706, 0.0, 0.05984790096871858, -0.1043104315541347, 0.6481438802900256, -0.15000576782732722, 1.6454561674367232, -0.24195538260858473, -2.333848554866085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4000622752712e-08, 6.352202952571782e-11, -8.091661661968918e-11, -0.16098690369785373, 0.0, -0.11099690369785373, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6364465384993025, -0.14619820487101615, 0.17652909179012896]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018926998028252911, 0.0, 0.010412065457524012, 0.0, -0.06850445769097972, 0.007947336089188916, -0.0012831514282027091, -3.253681296559442e-07, 0.018017021091052285, 0.045523739940496875, -0.011906440291243128, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.063697344037216e-09, 7.667309749095432e-12, -7.850663930146427e-13, -0.002668551079139711, 0.0, -0.002668551079139711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555299547235063, 0.02658723638373394, 0.029892557058386414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23652271196453423, 0.0, 0.03515773962880821, 0.0, 0.05641581825700634, -0.10390693159020216, 0.6480748055704058, -0.15000579359900207, 1.646223631204738, -0.23964349337978352, -2.3343118877718054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4088785496056662e-08, 6.379748942851932e-11, -8.094482545199182e-11, -0.16110189964081276, 0.0, -0.11111189964081275, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6442249777901686, -0.14486341586213425, 0.17802461808338896]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018343719553634555, 0.0, 0.00927055553982295, 0.0, -0.06864165423424481, 0.008069999278650892, -0.001381494392395647, -5.154334968332421e-07, 0.015349275360295204, 0.04623778457602429, -0.00926665811440934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7632548668932437e-09, 5.509198056030061e-12, -5.641766460527954e-13, -0.002299918859180376, 0.0, -0.002299918859180376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15556878581732111, 0.026695780177638188, 0.02991052586519994]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23661146933644733, 0.0, 0.03557029373058668, 0.0, 0.05297528220725666, -0.10349625119698591, 0.6479889638264205, -0.15000583452581348, 1.6468621027972825, -0.23729549742437023, -2.3346345695499386, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4163582698440382e-08, 6.399532005352956e-11, -8.096508653387568e-11, -0.16120095737905724, 0.0, -0.11121095737905723, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.652005197388668, -0.14352236727052198, 0.17952095359697182]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017751474382620097, 0.0, 0.008251082035569336, 0.0, -0.0688107209949935, 0.00821360786432508, -0.0017168348797065424, -8.185362281814537e-07, 0.012769431850891818, 0.046959919108266024, -0.006453635562662793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4959440476744143e-09, 3.956612500204865e-12, -4.0522163767717417e-13, -0.00198115476488968, 0.0, -0.00198115476488968, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1556043919699879, 0.026820971832245542, 0.029926710271657424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23669708826053368, 0.0, 0.035943342278203734, 0.0, 0.04952467547403197, -0.10307734121433192, 0.6478728897170454, -0.1500058983237358, 1.647376921751764, -0.2349111177422827, -2.3348069341938658, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.422705991441986e-08, 6.413735260262697e-11, -8.097963393393972e-11, -0.16128817196548875, 0.0, -0.11129817196548875, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6597870690639244, -0.14217422322784248, 0.18101801788998678]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017123784817269778, 0.0, 0.007460970952341179, 0.0, -0.06901213466449378, 0.008378199653079788, -0.0023214821875010673, -1.275958445887273e-06, 0.010296379089629937, 0.04768759364175058, -0.003447292878540187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2695443195895327e-09, 2.8406509819482697e-12, -2.9094800128094425e-13, -0.0017442917286302566, 0.0, -0.0017442917286302566, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15563743350512652, 0.026962880853590117, 0.02994128586029932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23677934705758447, 0.0, 0.036287857474012614, 0.0, 0.046062225877095436, -0.10264921892584082, 0.6477131469450845, -0.15000599582890653, 1.6477725990927503, -0.23248932388863772, -2.3348185532035006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4281202572003042e-08, 6.423930276379507e-11, -8.099007643301268e-11, -0.16136733756994978, 0.0, -0.11137733756994976, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6675704650788893, -0.14081802686696618, 0.18251572668050772]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016451759410160143, 0.0, 0.006890303916177645, 0.0, -0.06924899193873071, 0.008562445769821785, -0.0031948554392167293, -1.9501034147277403e-06, 0.00791354681972478, 0.04843587707290008, -0.0002323801927013149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0828531516636509e-09, 2.0390032233618313e-12, -2.088499814589854e-13, -0.0015833120892204202, 0.0, -0.0015833120892204202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15566792029929752, 0.02712392721752595, 0.029954175810418638]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23685797996953833, 0.0, 0.03661240214024723, 0.0, 0.042585927378595415, -0.10221097253626045, 0.6474969974736152, -0.1500061389569156, 1.6480519616006473, -0.23002813860170257, -2.3346582431822736, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4327883417990788e-08, 6.431247136015673e-11, -8.099757112879815e-11, -0.16144130697709108, 0.0, -0.11145130697709106, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6753552401285802, -0.13945261784217633, 0.18401398482237932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015726582390774649, 0.0, 0.006490893324692341, 0.0, -0.06952596997000039, 0.00876492779160739, -0.0043229894293870105, -2.862560181472778e-06, 0.005587250157937509, 0.049223705738702904, 0.0032062004245446305, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.336169197549133e-10, 1.4633719272332531e-12, -1.4989391570950886e-13, -0.0014793881428260666, 0.0, -0.0014793881428260666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1556955009938171, 0.027308180495797207, 0.029965162837432054]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23694933524983272, 0.0, 0.03692090864053692, 0.0, 0.03912129071603077, -0.10177092146965735, 0.6472930007813744, -0.1500061615655929, 1.648295555120316, -0.22763590586257, -2.334471431055151, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4369850617009422e-08, 6.436497859330579e-11, -8.100294957679762e-11, -0.16151137610962044, 0.0, -0.11152137610962043, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6831446155913444, -0.1380948171248175, 0.1855143891820218]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018271056058877086, 0.0, 0.006170130005793677, 0.0, -0.0692927332512929, 0.00880102133206176, -0.004079933844816905, -4.5217354558235564e-07, 0.004871870393376985, 0.04784465478265147, 0.003736242542449828, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.393439803727027e-10, 1.0501446629811367e-12, -1.0756895998931617e-13, -0.0014013826505872567, 0.0, -0.0014013826505872567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15578750925528548, 0.027156014347176394, 0.030008087192849576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.237053967189467, 0.0, 0.0372963354970549, 0.0, 0.03569559470447108, -0.10133780502446062, 0.647145606078629, -0.1500068490818108, 1.648615891283768, -0.22540122350370165, -2.3344020542731534, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4469470337366317e-08, 6.440265635348307e-11, -8.100680905556043e-11, -0.161603800998119, 0.0, -0.11161380099811899, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6909424090665616, -0.13676552671915873, 0.1870187556621036]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002092638792685378, 0.0, 0.007508537130359608, 0.0, -0.06851392023119378, 0.00866232890393463, -0.0029478940549078287, -1.3750324358166132e-05, 0.006406723269042981, 0.04469364717736692, 0.001387535639947284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9923944071379195e-09, 7.53555203545504e-13, -7.718957525598696e-14, -0.00184849776997103, 0.0, -0.00184849776997103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559558695043424, 0.02658580811317536, 0.030087329601636025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23716700995790874, 0.0, 0.037649836222835624, 0.0, 0.032325875500911226, -0.1009200630475204, 0.6470807979878139, -0.15000685025973154, 1.6490814095551767, -0.2233481638897749, -2.334546378897069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4577118715249255e-08, 6.442969170117006e-11, -8.100957841537605e-11, -0.16169174016233745, 0.0, -0.11170174016233744, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6987512402818523, -0.13547965538677811, 0.1885282395881239]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022608553688346624, 0.0, 0.007070014515614552, 0.0, -0.06739438407119712, 0.008354839538804322, -0.0012961618163012563, -2.355841452901972e-08, 0.009310365428170915, 0.04106119227853482, -0.002886492478307489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152967557658776e-09, 5.407069537399379e-13, -5.538719631250855e-14, -0.0017587832843689315, 0.0, -0.0017587832843689315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15617662430581555, 0.025717426647612125, 0.030189678520405758]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23728689330894384, 0.0, 0.03795790936320141, 0.0, 0.029020474061616484, -0.10052151769536022, 0.6470680377296627, -0.15000685277017245, 1.6497464498611834, -0.22147163543840437, -2.334946160310273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4673729038960226e-08, 6.444909010757307e-11, -8.101156549862678e-11, -0.1617673943784295, 0.0, -0.11177739437842947, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.70657252045747, -0.13424713745698122, 0.1900434252055515]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023976670207022694, 0.0, 0.006161462807315785, 0.0, -0.06610802878589483, 0.007970907043203596, -0.00025520516302466657, -5.020881834384054e-08, 0.013300806120131195, 0.037530569027410705, -0.007995628264084769, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.932206474219441e-09, 3.8796812806002264e-13, -3.9741665014556314e-14, -0.0015130843218406002, 0.0, -0.0015130843218406002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15642560351235346, 0.024650358595937956, 0.030303712348552104]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2374121141416874, 0.0, 0.038220098168286296, 0.0, 0.025781506686477353, -0.10014362129209642, 0.6470679389350972, -0.15000685411633266, 1.650638507477114, -0.21975285693195934, -2.335610003136367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4753930626889778e-08, 6.446300857988708e-11, -8.101299124839965e-11, -0.1618302017635634, 0.0, -0.11184020176356341, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7144066493666529, -0.1330728044374648, 0.19156444142263296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002504416654871073, 0.0, 0.00524377610169774, 0.0, -0.06477934750278262, 0.007557928065276126, -1.9758913116152605e-06, -2.6923203975585464e-08, 0.01784115231861218, 0.03437557012890061, -0.013276856521883288, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6040317585910414e-09, 2.783694462801319e-13, -2.851499545743918e-14, -0.001256147702678704, 0.0, -0.001256147702678704, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15668257818365813, 0.02348666039032816, 0.03042032434162919]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23754133491132326, 0.0, 0.03847602485573955, 0.0, 0.022606985453966513, -0.09978642815976205, 0.6470670882939497, -0.15000687415215558, 1.6517609984550816, -0.21817001745941372, -2.3365256386976423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.483570033066957e-08, 6.447299503429827e-11, -8.101401422153571e-11, -0.1618912927508484, 0.0, -0.11190129275084838, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7222532819136971, -0.13195718973941656, 0.1930910971492343]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002584415392717131, 0.0, 0.0051185337490651395, 0.0, -0.06349042465021679, 0.00714386264668751, -1.701282295076455e-05, -4.007164584183582e-07, 0.022449819559353747, 0.03165678945091258, -0.01831271122550522, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6353940755958975e-09, 1.997290882238085e-13, -2.0459462721256192e-14, -0.0012218197456995996, 0.0, -0.0012218197456995996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15693265094088418, 0.022312293960964687, 0.030533114532027002]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23767345321292993, 0.0, 0.038734946213881974, 0.0, 0.019492485268102374, -0.09944917744521968, 0.6470664531591849, -0.15000687855370295, 1.65309953079513, -0.2167026156583162, -2.337669148140485, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4911072929821587e-08, 6.448016021612105e-11, -8.101474819591653e-11, -0.16195300519398, 0.0, -0.11196300519397999, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7301116125858156, -0.13089773033098567, 0.19462300348287703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0026423660321332368, 0.0, 0.005178427162848446, 0.0, -0.06229000371728278, 0.006745014290847303, -1.2702695296726047e-05, -8.803094755277722e-08, 0.026770646800965442, 0.029348036021950696, -0.022870188856858587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5074519830402969e-09, 1.433036364556565e-13, -1.4679487616338017e-14, -0.0012342488626322355, 0.0, -0.0012342488626322355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.157166613442369, 0.021189188168617423, 0.030638126672854364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23780769215451916, 0.0, 0.0389996394025386, 0.0, 0.016432420878018893, -0.09913048614760898, 0.6470658583478706, -0.15000688598982573, 1.6546303353034566, -0.21533310819171628, -2.339011159476304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.497900534791497e-08, 6.448530113220493e-11, -8.101527481273555e-11, -0.16201602964371062, 0.0, -0.11202602964371061, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7379806018355602, -0.12989010105571003, 0.19615967910280058]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002684778831784691, 0.0, 0.005293863773132512, 0.0, -0.0612012878016696, 0.006373825952213957, -1.1896226285365325e-05, -1.4872245561903305e-07, 0.030616090166535246, 0.02739014933199821, -0.026840226716372956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.358648361867689e-09, 1.028183216775496e-13, -1.0532336380419762e-14, -0.0012604889946123128, 0.0, -0.0012604889946123128, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15737978499489297, 0.020152585505512726, 0.030733512398470792]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23793437483494798, 0.0, 0.039270257562083404, 0.0, 0.013432862873598447, -0.0988351530548976, 0.647064570738704, -0.15000689693617442, 1.656305693308499, -0.21392450273020136, -2.3405036724653425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.503775002572154e-08, 6.448898965165522e-11, -8.101565265161553e-11, -0.16208045904717164, 0.0, -0.11209045904717163, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7458615266003031, -0.1289383004906567, 0.1977015609680967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002533653608576254, 0.0, 0.005412363190896057, 0.0, -0.059991160088408914, 0.005906661854227875, -2.5752183329179606e-05, -2.1892697368712006e-07, 0.03350716010084859, 0.028172109230298364, -0.029850259780770865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.17489355613138e-09, 7.377038900589769e-14, -7.556777599618792e-15, -0.0012885880692204267, 0.0, -0.0012885880692204267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15761849529485703, 0.019036011301066927, 0.030837637305922764]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2380558716550121, 0.0, 0.03951653287050345, 0.0, 0.010473274854080988, -0.09855788135358552, 0.6470644615177139, -0.15000689796039457, 1.6580408024392035, -0.21251563550229896, -2.342058507916928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5085121274870974e-08, 6.449163609424899e-11, -8.101592374397914e-11, -0.16213816805467568, 0.0, -0.11214816805467567, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7537513492688143, -0.12802391051501136, 0.19924724590482906]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002429936401282779, 0.0, 0.004925506168400851, 0.0, -0.05919176039034919, 0.005545434026241498, -2.184419803805401e-06, -2.0484403071975876e-08, 0.03470218261409181, 0.02817734455804772, -0.031096709031709947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.474249829886715e-10, 5.2928851875454684e-14, -5.421847272273831e-15, -0.0011541801500808344, 0.0, -0.0011541801500808344, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15779645337022263, 0.018287799512906544, 0.030913698734646916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2381718284897342, 0.0, 0.039733785868782165, 0.0, 0.007532623497585709, -0.09829249249669303, 0.6470643088916381, -0.15000689984980092, 1.6597546799540908, -0.21113495953793207, -2.3435912519162017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.512242295238432e-08, 6.449353486309206e-11, -8.101611824731938e-11, -0.16218795818194207, 0.0, -0.11219795818194207, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7616468507506395, -0.1271267830646287, 0.20079529440514626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002319136694441705, 0.0, 0.004345059965574409, 0.0, -0.05881302712990557, 0.0053077771378497755, -3.052521516526812e-06, -3.7788126825408766e-08, 0.03427755029774429, 0.027613519287337573, -0.030654879985479278, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.460335502669647e-10, 3.797537686151419e-14, -3.8900668048539624e-15, -0.0009958025453278953, 0.0, -0.0009958025453278953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15791002963650524, 0.017942549007652717, 0.03096097000634401]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23828369286619938, 0.0, 0.039925141323472885, 0.0, 0.0045970621033342715, -0.09803369734145027, 0.6470641036783265, -0.15000690132523006, 1.6613947498944452, -0.20978832455180396, -2.3450475299705666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5151705399777354e-08, 6.449489718955172e-11, -8.101625779938419e-11, -0.16223083521562465, 0.0, -0.11224083521562464, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7695456859017533, -0.12623309018796203, 0.20234471492147338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022372875293038717, 0.0, 0.0038271090938143387, 0.0, -0.05871122788502875, 0.005175903104855141, -4.104266233019173e-06, -2.9508582673796067e-08, 0.03280139880709113, 0.026932699722562, -0.02912556108730081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.856489478606596e-10, 2.7246529193296314e-14, -2.791041296221239e-15, -0.000857540673651474, 0.0, -0.000857540673651474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15797670302227584, 0.017873857533333662, 0.03098841032654215]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23839294696517774, 0.0, 0.04009528952432453, 0.0, 0.0016595941118280485, -0.0977775038604349, 0.6470638837936128, -0.15000690219464743, 1.6629371480870907, -0.20846923147196997, -2.346403193394028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5174798827901478e-08, 6.449587462916352e-11, -8.101635792497284e-11, -0.16226824858306993, 0.0, -0.11227824858306992, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7774464335341716, -0.12533591802884647, 0.20389495354478585]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021850819795672825, 0.0, 0.0034029640170327993, 0.0, -0.058749359830124456, 0.0051238696203072765, -4.3976942732905375e-06, -1.7388347267085484e-08, 0.030847963852907404, 0.026381861596679806, -0.027113268469225602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.618685624824516e-10, 1.9548792235953357e-14, -2.0025117731254598e-15, -0.0007482673489057328, 0.0, -0.0007482673489057328, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1580149526483658, 0.017943443182311315, 0.0310047724662496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23850051047257373, 0.0, 0.04027970693617502, 0.0, -0.0012823676859697927, -0.09752114094101796, 0.6470606718189964, -0.15000691839485097, 1.6643783513862864, -0.20716813946299342, -2.3476538279579793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5195422777408557e-08, 6.449657592044633e-11, -8.101642976287448e-11, -0.16231089901882165, 0.0, -0.11232089901882164, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.785348365437576, -0.12443317674624349, 0.20544575571273305]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021512701479197067, 0.0, 0.0036883482370097713, 0.0, -0.05883923595595682, 0.005127258388338892, -6.423949232822042e-05, -3.240040706741658e-07, 0.028824065983915008, 0.02602184017953096, -0.025012691279028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.1247899014155206e-10, 1.4025825656271501e-14, -1.436758032719708e-15, -0.0008530087150344877, 0.0, -0.0008530087150344877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15803863806808827, 0.018054825652059632, 0.031016043358944305]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2385791089118535, 0.0, 0.04070945381364533, 0.0, -0.004191103500659208, -0.09720707882576833, 0.6469858768993139, -0.15001773058842927, 1.6657191925305468, -0.20576797878081982, -2.3487186052535827, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5201251174111327e-08, 6.44970790803519e-11, -8.101648130485284e-11, -0.16242438576830404, 0.0, -0.11243438576830402, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7930621885287543, -0.12355046813332551, 0.20695150126858516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001571968785595383, 0.0, 0.008594937549406611, 0.0, -0.05817471629378831, 0.006281242304992622, -0.0014958983936505762, -0.00021624387156589654, 0.026816822885207803, 0.028003213643471962, -0.021295545912070956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1656793405538502e-10, 1.0063198111297377e-14, -1.0308395672842973e-15, -0.002269734989647506, 0.0, -0.002269734989647506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15427646182356555, 0.017654172258359645, 0.030114911117042422]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23855916294368004, 0.0, 0.0412605141634229, 0.0, -0.0068981787135183725, -0.09652119380136231, 0.6467647590299413, -0.15018230247866987, 1.6668591514487319, -0.20375379571193902, -2.3493944102048627, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.520041657304294e-08, 6.449744008560816e-11, -8.101651828505279e-11, -0.16256674648453034, 0.0, -0.11257674648453031, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7999681252670063, -0.12277785928491476, 0.20826629303660676]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003989193634688676, 0.0, 0.01102120699555136, 0.0, -0.05414150425718327, 0.013717700488120417, -0.004422357387449625, -0.0032914378048123916, 0.02279917836370264, 0.040283661377615854, -0.013516099025603395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6692021367754102e-11, 7.220105125156111e-15, -7.39603998989827e-16, -0.0028472143245259532, 0.0, -0.0028472143245259532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1381187347650393, 0.015452176968215032, 0.026295835360431875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23850003676858564, 0.0, 0.04187740545815657, 0.0, -0.009298877520243078, -0.09520415745930672, 0.6463696843368351, -0.150681696800619, 1.667811871249101, -0.20089212698893252, -2.3496485561515863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.519713351460739e-08, 6.449769909835557e-11, -8.101654481748601e-11, -0.1627205903254521, 0.0, -0.11273059032545207, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8056272364561627, -0.1222070616239461, 0.2093269206922065]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011825235018879466, 0.0, 0.012337825894673426, 0.0, -0.04801397613449412, 0.026340726841112105, -0.007901493862125138, -0.009987886438982605, 0.019054396007381996, 0.057233374460130076, -0.005082918934475392, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.566116871097933e-11, 5.180254948248252e-15, -5.306486645214548e-16, -0.0030768768184353825, 0.0, -0.0030768768184353825, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11318222378312782, 0.011415953219373456, 0.021212553111994412]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23842679292425567, 0.0, 0.04256808962752821, 0.0, -0.01139874574971478, -0.09318967368164892, 0.6458035848140842, -0.15154195489827857, 1.668636637528928, -0.19712033553124284, -2.3495261346015544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5192838108900896e-08, 6.449788493386587e-11, -8.101656385389674e-11, -0.16288298692115025, 0.0, -0.11289298692115021, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8099905857784119, -0.12186895257894735, 0.2101335633174297]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014648768865993826, 0.0, 0.01381368338743295, 0.0, -0.04199736458943404, 0.04028967555315601, -0.011321990455017831, -0.017205161953191352, 0.016495325596539833, 0.07543582915379365, 0.002448431000639662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.590811412986605e-11, 3.716710206194925e-15, -3.807282146549976e-16, -0.003247931913962711, 0.0, -0.003247931913962711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08726698644498368, 0.00676218089997487, 0.016132852504464196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2383494442874209, 0.0, 0.04332166618809267, 0.0, -0.013280649876254188, -0.09057434615366274, 0.6450855883832823, -0.1526339767004589, 1.6694095146016994, -0.19243266962334843, -2.349106357244482, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5188463195453017e-08, 6.449801826642675e-11, -8.10165775120736e-11, -0.163051818405543, 0.0, -0.11306181840554297, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8132209317535184, -0.12176093203240787, 0.2107206514979358]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0015469727366958026, 0.0, 0.01507153121128907, 0.0, -0.03763808253078816, 0.052306550559723705, -0.01435992861603611, -0.021840436043606574, 0.015457541455426596, 0.09375331815788829, 0.008395547141451704, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.749826895755961e-11, 2.6666512174467505e-15, -2.7316353720508656e-16, -0.003376629687855254, 0.0, -0.003376629687855254, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06460691950213117, 0.0021604109307896135, 0.011741763610122628]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23827296493891417, 0.0, 0.04412842666334804, 0.0, -0.015061605238410611, -0.08754552498712952, 0.6442408202105113, -0.15373746629192575, 1.670207988872258, -0.18684153363787823, -2.348477000601857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5184455002726955e-08, 6.449811392937823e-11, -8.101658731145155e-11, -0.1632270574224112, 0.0, -0.11323705742241116, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8155615758590412, -0.12186645396733613, 0.21113490528649567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0015295869701341643, 0.0, 0.016135209505107374, 0.0, -0.03561910724312845, 0.0605764233306643, -0.01689536345542092, -0.02206979182933732, 0.015969485411172622, 0.11182271970940424, 0.012587132852490938, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.016385452123401e-11, 1.9132590297737796e-15, -1.9598755903602465e-16, -0.0035047803373640324, 0.0, -0.0035047803373640324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04681288211045612, -0.002110438698565111, 0.008285075771197187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23821134778076403, 0.0, 0.0448364731781252, 0.0, -0.016889958737878713, -0.08440096834062265, 0.6433084126288573, -0.15454299155870438, 1.6710903612932089, -0.18048667400502655, -2.3477300060980086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181160497437817e-08, 6.449818256530264e-11, -8.10165943422561e-11, -0.16337889967638167, 0.0, -0.11338889967638162, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8173530249748235, -0.12214429167077728, 0.21143960217578514]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001232343163002948, 0.0, 0.014160930295543158, 0.0, -0.03656706998936207, 0.06289113293013736, -0.01864815163307969, -0.016110505335572813, 0.017647448419015683, 0.1270971926570334, 0.014939890076973304, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.589010578279081e-11, 1.3727184880824241e-15, -1.4061609108534658e-16, -0.0030368450794091085, 0.0, -0.0030368450794091085, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.035828982315646386, -0.005556754068823113, 0.006093937785789431]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23816918364416448, 0.0, 0.045426737980294375, 0.0, -0.018783030844892502, -0.08126076042368698, 0.6423803972129323, -0.15483644604411745, 1.6721930323636371, -0.17340911869362247, -2.347101555430393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5178591121868942e-08, 6.449823180998024e-11, -8.101659938668511e-11, -0.16350338146093743, 0.0, -0.11351338146093737, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8187836578021773, -0.12260880597306174, 0.21167200475270245]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0008432827319910139, 0.0, 0.011805296043383625, 0.0, -0.0378614421402758, 0.06280415833871351, -0.0185603083185006, -0.005869089708261664, 0.022053421408565546, 0.1415511062280818, 0.012569013352308783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.138751137752884e-11, 9.84893551928493e-16, -1.0088858021312673e-16, -0.002489635691115091, 0.0, -0.002489635691115091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0286126565470761, -0.009290286045689308, 0.004648051538346131]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2381606376727112, 0.0, 0.04596455260326306, 0.0, -0.020678581718467304, -0.07815162318287758, 0.6415906908126949, -0.15480384554402285, 1.673678229297357, -0.16574853083316782, -2.3469079863635804, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.51766382094244e-08, 6.449826714189814e-11, -8.101660300594388e-11, -0.16361614125166069, 0.0, -0.11362614125166062, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.819985722640758, -0.12329356920461947, 0.21186051932212996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00017091942906556667, 0.0, 0.010756292459373852, 0.0, -0.037911017471496056, 0.06218274481618803, -0.015794128004746506, 0.0006520100018918892, 0.029703938674400805, 0.15321175720909316, 0.0038713813362545608, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.905824889083861e-11, 7.0663835811013015e-16, -7.238517540968666e-17, -0.0022551958144651765, 0.0, -0.0022551958144651765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02404129677161392, -0.013695264631154506, 0.0037702913885501554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23806147948840892, 0.0, 0.04647860013460228, 0.0, -0.02235478850113412, -0.07514508336845704, 0.6404631419864955, -0.15465598689688642, 1.6757765296721898, -0.1569745300262023, -2.3469703728981663, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5175215070786495e-08, 6.44982924917369e-11, -8.101660560267767e-11, -0.16373127195464066, 0.0, -0.1137412719546406, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8210807417797273, -0.12437070950815352, 0.21203705224403468]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001983163686045729, 0.0, 0.010280950626784467, 0.0, -0.033524135653336305, 0.060130796288410636, -0.02255097652398981, 0.002957172942728542, 0.04196600749665625, 0.17548001613931075, -0.0012477306917181514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8462772758145038e-11, 5.069967750530571e-16, -5.1934675994164054e-17, -0.0023026140595994327, 0.0, -0.0023026140595994327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021900382779387335, -0.021542806070680966, 0.003530658438094395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23797959707941402, 0.0, 0.046931317191207654, 0.0, -0.02383688585248512, -0.07222780036972551, 0.6390173175279479, -0.15446941068972608, 1.6784162134219174, -0.14781083462705305, -2.3472429999802804, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5174189127501115e-08, 6.449831067966389e-11, -8.101660746577399e-11, -0.16383652444638458, 0.0, -0.11384652444638452, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8221304829610446, -0.1257971889081446, 0.2122128067049146]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0016376481798981318, 0.0, 0.009054341132107435, 0.0, -0.029641947027019947, 0.058345659974630724, -0.028916489170951118, 0.003731524143206696, 0.05279367499455243, 0.18327390798298504, -0.005452541642283912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0518865707617408e-11, 3.6375853978477043e-16, -3.726192610528667e-17, -0.002105049834878387, 0.0, -0.002105049834878387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020994823626345215, -0.028529587999821585, 0.0035150892175981967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2379150761340047, 0.0, 0.04737018515739623, 0.0, -0.02517980150653813, -0.06938971432860813, 0.6373425329698833, -0.1542609685174874, 1.6814880823797178, -0.13865253310324024, -2.347706278807634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5173537493181488e-08, 6.449832372908948e-11, -8.101660880250421e-11, -0.1639469139318512, 0.0, -0.11395691393185114, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8231723374508351, -0.1275052672498991, 0.21239307830059997]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001290418908186609, 0.0, 0.008777359323771534, 0.0, -0.02685831308106021, 0.05676172082234758, -0.03349569116129063, 0.004168843444773246, 0.06143737915600869, 0.18316603047625635, -0.009265576547071096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3032686392531367e-11, 2.609885119325376e-16, -2.6734604527142748e-17, -0.0022077897093326806, 0.0, -0.0022077897093326806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020837089795807916, -0.034161566835090425, 0.0036054319137071985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23787405006059295, 0.0, 0.047810168675776914, 0.0, -0.026399774380870576, -0.06662749933133728, 0.6355376342844792, -0.154001502186486, 1.684967560690614, -0.1295413982008961, -2.3484404404396653, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5173189613919042e-08, 6.449833309175656e-11, -8.101660976157868e-11, -0.16406437424755904, 0.0, -0.11407437424755898, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8242373400103982, -0.12947397825626605, 0.2125833765711633]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0008205214682347839, 0.0, 0.00879967036761359, 0.0, -0.024399457486648898, 0.055244299945417026, -0.03609797370808157, 0.005189326620028344, 0.06958956621792602, 0.18222269804688251, -0.014683232640630409, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.957585248958934e-12, 1.872533414111482e-16, -1.9181489473448015e-17, -0.0023492063141566997, 0.0, -0.0023492063141566997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02130005119126188, -0.039374220127338676, 0.00380596541126669]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2374581396269104, 0.0, 0.04823439371059147, 0.0, -0.027045718612566442, -0.06398212757705854, 0.6319647567973641, -0.15392700155081146, 1.68920989157025, -0.12123587201047556, -2.348276301633426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.517302528097271e-08, 6.449833980925964e-11, -8.101661044969364e-11, -0.1641809831975611, 0.0, -0.11419098319756106, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8253091768746338, -0.13212409494255709, 0.21279720860204598]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00831820867365106, 0.0, 0.008484500696291142, 0.0, -0.01291888463391731, 0.05290743508557498, -0.07145754974230295, 0.001490012713491127, 0.08484661759271872, 0.16611052380841104, 0.003282776124780609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.2866589266002716e-12, 1.3435006174056693e-16, -1.3762299019436379e-17, -0.002332179000041554, 0.0, -0.002332179000041554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021436737284713306, -0.05300233372582037, 0.004276640617653853]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23706888405965348, 0.0, 0.04859973188675891, 0.0, -0.027190200554325326, -0.06146501731306316, 0.6266060602521701, -0.15386473206754722, 1.6942056046937428, -0.11337051303028078, -2.3471775340453296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.517295099266099e-08, 6.449834462891605e-11, -8.101661094340084e-11, -0.16428185704623385, 0.0, -0.11429185704623379, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8264496060958886, -0.13545379109172787, 0.21304459499835376]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007785111345138132, 0.0, 0.007306763523348839, 0.0, -0.002889638835177658, 0.05034220527990754, -0.1071739309038792, 0.0012453896652845212, 0.09991426246985398, 0.15730717960389543, 0.021975351761930148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4857662344209342e-12, 9.639312814930264e-17, -9.874143811283036e-18, -0.002017476973454699, 0.0, -0.002017476973454699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02280858442509562, -0.06659392298341583, 0.004947727926155823]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2364189364729939, 0.0, 0.04890294342037375, 0.0, -0.026432970767199665, -0.0591440934147112, 0.6182221200721095, -0.1540127029734837, 1.7004979970183713, -0.1096205182058791, -2.344551700842407, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5172944750529145e-08, 6.449834808691e-11, -8.101661129762465e-11, -0.16436559740764473, 0.0, -0.11437559740764466, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8277772761963251, -0.13983246099066274, 0.2133675786531118]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012998951733192042, 0.0, 0.00606423067229676, 0.0, 0.015144595742513192, 0.04641847796703924, -0.16767880360121257, -0.0029594181187297362, 0.12584784649256986, 0.07499989648803354, 0.05251666405845887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.248426368952391e-13, 6.915987905083939e-17, -7.08447632230504e-18, -0.001674807228217531, 0.0, -0.001674807228217531, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026553402008731877, -0.0875733979786977, 0.0064596730951603076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23580295444099028, 0.0, 0.04934239882620914, 0.0, -0.024897732969668022, -0.057058020377147134, 0.6067753493787232, -0.1538129805369134, 1.7087895434861677, -0.10623590542088146, -2.341040747638808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5174456504221552e-08, 6.449835056799145e-11, -8.101661155162894e-11, -0.1644947993661789, 0.0, -0.11450479936617881, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8293274301905146, -0.14517311478526065, 0.2137953855192022]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012319640640072228, 0.0, 0.00878910811670765, 0.0, 0.030704755950632868, 0.041721460751281324, -0.2289354138677256, 0.00399444873140639, 0.16583092935592814, 0.06769225569995285, 0.07021906407197492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.023507384810748e-11, 4.962162893567506e-17, -5.080085901064169e-18, -0.0025840391706830825, 0.0, -0.0025840391706830825, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.031003079883789197, -0.10681307589195818, 0.008556137321808741]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23531781741836325, 0.0, 0.04983347587617086, 0.0, -0.022839426765270475, -0.05513815963894009, 0.5927680916526522, -0.1531334330047597, 1.7196326040679475, -0.10266860067966216, -2.3376411447015193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5176339885549304e-08, 6.449835234813704e-11, -8.101661173380223e-11, -0.16464051629185814, 0.0, -0.11465051629185806, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8311073833783786, -0.15130866284646668, 0.21434475052403132]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009702740452540687, 0.0, 0.009821540999234416, 0.0, 0.04116612408795093, 0.038397214764140895, -0.2801451545214198, 0.013590950643073675, 0.2168612116355932, 0.07134609482438609, 0.0679920587457763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7667626555076394e-11, 3.5602911785109e-17, -3.6434660020143004e-18, -0.0029143385135850276, 0.0, -0.0029143385135850276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03559906375728162, -0.12271096122412083, 0.010987300096582183]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23473045900067332, 0.0, 0.0502962743123573, 0.0, -0.020390193726895968, -0.05337273434235524, 0.575683733725786, -0.15313343308732288, 1.733838455682556, -0.10266860069378002, -2.334634603625283, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5178088779464382e-08, 6.449835362536366e-11, -8.101661186447427e-11, -0.16477682090060475, 0.0, -0.11478682090060466, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8331038549726266, -0.1581317435157095, 0.21504386876240889]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011747168353798517, 0.0, 0.009255968723728856, 0.0, 0.04898466076749011, 0.0353085059316969, -0.34168715853732584, -1.6512636639987033e-09, 0.2841170322921703, -2.8235715154867336e-10, 0.06013082152473037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4977878301545016e-11, 2.5544532447867728e-17, -2.613440742159875e-18, -0.0027260921749320934, 0.0, -0.0027260921749320934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03992943188495944, -0.13646161338485627, 0.013982364767551315]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2342351437550596, 0.0, 0.05083789729123829, 0.0, -0.01778349954850689, -0.051661459542758144, 0.5548785545232533, -0.1531334344914775, 1.7533075547834913, -0.10266860088559523, -2.3332438193849327, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5179569068564018e-08, 6.44983545417529e-11, -8.101661195819112e-11, -0.1649385691619342, 0.0, -0.1149485691619341, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8352980575585811, -0.1655064280638513, 0.21595217347354215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009906304912274158, 0.0, 0.010832459577619765, 0.0, 0.052133883567781564, 0.034225495991941975, -0.41610358405065223, -2.8083092485468662e-08, 0.3893819820187061, -3.836304276365092e-09, 0.02781568480700653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.960578199273016e-11, 1.8327784758406958e-17, -1.8743369906902994e-18, -0.0032349652265889067, 0.0, -0.0032349652265889067, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04388405171909033, -0.1474936909628363, 0.018166094222665435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23381650999693915, 0.0, 0.051390108434094924, 0.0, -0.01524607457681518, -0.049946159363868745, 0.5300078473293647, -0.15313343460470902, 1.7793145473732213, -0.10266860092263921, -2.3342904399845685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.518072380933283e-08, 6.449835519924594e-11, -8.101661202541169e-11, -0.1651018921065664, 0.0, -0.11511189210656629, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8376706499783856, -0.17331757146111232, 0.21711321936914968]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008372675162409209, 0.0, 0.011044222857132588, 0.0, 0.05074849943383417, 0.03430600357778794, -0.49741414387777233, -2.26463025438855e-09, 0.5201398517945974, -7.408795356207471e-10, -0.020932411992714055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.309481537626665e-11, 1.314986072273927e-17, -1.344411537600275e-18, -0.0032664588926437027, 0.0, -0.0032664588926437027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04745184839608857, -0.15622286794522044, 0.023220917912150432]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23345088197957442, 0.0, 0.05192894462552559, 0.0, -0.01292348702909611, -0.04821513247271113, 0.5012680208527509, -0.15313343470676302, 1.8113110706630198, -0.10266860095693565, -2.3378071051887663, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.518155376974784e-08, 6.44983556709859e-11, -8.101661207363034e-11, -0.165259728597969, 0.0, -0.11526972859796888, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8402036571721596, -0.18147345907425377, 0.2185550129741736]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007312560347294455, 0.0, 0.010776723828613345, 0.0, 0.04645175095438142, 0.034620537823152275, -0.5747965295322759, -2.041080107093845e-09, 0.6399304657959682, -6.859288599761405e-10, -0.07033330408395821, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6599208300198337e-11, 9.434799262581346e-18, -9.643728371619019e-19, -0.0031567298280519157, 0.0, -0.0031567298280519157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05066014387548029, -0.163117752262829, 0.028835872100478412]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23314386669916767, 0.0, 0.05255343483012553, 0.0, -0.0108841903113439, -0.046493324689089524, 0.46923515101853935, -0.15313343514670638, 1.848409897263824, -0.10266860117192815, -2.3433269377044916, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181860428729818e-08, 6.449835600944807e-11, -8.101661210825402e-11, -0.16544020891234335, 0.0, -0.11545020891234323, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8428735195309917, -0.1899026165046443, 0.22029552567455943]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00614030560813504, 0.0, 0.012489804091998779, 0.0, 0.04078593435504418, 0.03443615567243201, -0.6406573966842309, -8.798867167755675e-09, 0.7419765320160882, -4.299849827634146e-09, -0.11039665031450849, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.133179639540851e-12, 6.769243284460647e-18, -6.924738494794126e-19, -0.003609606287486756, 0.0, -0.003609606287486756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.053397247176640815, -0.16858314860781032, 0.034810254007716486]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23293973354060657, 0.0, 0.05314069301109785, 0.0, -0.009150408764237766, -0.044842142439771186, 0.4346039901035703, -0.15313343516988628, 1.889800634715085, -0.10266860117979193, -2.3504231787452925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181916179127113e-08, 6.449835625228658e-11, -8.10166121331093e-11, -0.16560718128925372, 0.0, -0.11561718128925362, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.845637805889954, -0.198553083440997, 0.22234215395398113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0040826631712220385, 0.0, 0.011745163619446351, 0.0, 0.034675630942122705, 0.03302364498636672, -0.692623218299381, -4.635981512571724e-10, 0.8278147490252198, -1.5727550197246543e-10, -0.14192482081601693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1150079458897562e-12, 4.856770027430041e-18, -4.971054858383957e-19, -0.0033394475382077637, 0.0, -0.0033394475382077637, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05528572717924705, -0.17300933872705415, 0.040932565588433834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23279804905040558, 0.0, 0.05372844962140822, 0.0, -0.0077443522920570594, -0.04330433192886994, 0.3977747621082179, -0.15313343526907058, 1.9348246192529166, -0.10266860121426051, -2.3587334030492477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181737703118508e-08, 6.449835642651963e-11, -8.101661215094934e-11, -0.1657718609541812, 0.0, -0.11578186095418111, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8484756015148152, -0.2073803625423391, 0.22470173716169797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002833689804020057, 0.0, 0.011755132206207448, 0.0, 0.028121129443614123, 0.030756210218024965, -0.7365845599070487, -1.983686066882044e-09, 0.900479690756632, -6.893716284635601e-10, -0.16620448607910532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.5695201720969874e-12, 3.4846611586276046e-18, -3.5680070773748413e-19, -0.0032935932985496542, 0.0, -0.0032935932985496542, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.056755912497224295, -0.17654558202684184, 0.04719166415433677]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2326552652305152, 0.0, 0.05434499904321462, 0.0, -0.006693863527023758, -0.04187730495939191, 0.35889486257368275, -0.15313343544644742, 1.9827844184276913, -0.10266860127955095, -2.3677035488067246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.518120591159894e-08, 6.449835655151967e-11, -8.101661216374578e-11, -0.16594329331115923, 0.0, -0.11595329331115914, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8513995132945418, -0.21634203900043433, 0.22738767564680049]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0028556763978078627, 0.0, 0.01233098843612786, 0.0, 0.021009775300666014, 0.02854053938956064, -0.7775979906907025, -3.547536809948411e-09, 0.9591959834954956, -1.3058087762366285e-09, -0.17940291514953735, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.063583039137835e-11, 2.5000007143805996e-18, -2.559288112965856e-19, -0.0034286471395606434, 0.0, -0.0034286471395606434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05847823559453136, -0.1792335291619046, 0.053718769702050216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23251758809107106, 0.0, 0.0549582751956504, 0.0, -0.00601734554683553, -0.0405522569370272, 0.31809257390668827, -0.1531334359443836, 2.0327844171195446, -0.1026686014353254, -2.3767441880120774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5179780981592767e-08, 6.449835664120467e-11, -8.101661217292722e-11, -0.1661156753550082, 0.0, -0.11612567535500813, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8544229099179355, -0.22540313130934725, 0.2304134636836119]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0027535427888824315, 0.0, 0.012265523048715603, 0.0, 0.013530359603764561, 0.02650096044729424, -0.8160457733398896, -9.958724103706892e-09, 0.9999999738370651, -3.115488969568862e-09, -0.18081278410705795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8498600123397965e-11, 1.7937001371996373e-18, -1.8362862728988284e-19, -0.003447640876979839, 0.0, -0.003447640876979839, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.060467932467873506, -0.18122184617825832, 0.06051576073622836]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23239670495160478, 0.0, 0.055571104871543896, 0.0, -0.005717475057439239, -0.03932145259086932, 0.27558216389923157, -0.15313343603283744, 2.082784416922882, -0.10266860146033742, -2.385199575622597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.517808256126718e-08, 6.449835670554005e-11, -8.101661217951566e-11, -0.16629102179167646, 0.0, -0.11630102179167638, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8575524568739482, -0.23453626960527574, 0.23379357321385966]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002417662789326012, 0.0, 0.012256593517869929, 0.0, 0.005997409787925838, 0.024616086923157705, -0.8502082001491336, -1.7690765238712583e-09, 0.999999996066756, -5.002404001877771e-10, -0.16910775221039545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.396840651174699e-11, 1.2867077399564448e-18, -1.317689186637689e-19, -0.0035069287333649776, 0.0, -0.0035069287333649776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06259093912025597, -0.18266276591856961, 0.067602190604955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23227381825161886, 0.0, 0.05632681712354841, 0.0, -0.005805880129470541, -0.03819220220020663, 0.23144470628240532, -0.15313344637082058, 2.1327844113010124, -0.1026686050655052, -2.3925374389628895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5166304218606653e-08, 6.449835675183423e-11, -8.101661218408597e-11, -0.16651448723985973, 0.0, -0.11652448723985966, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8607937855859839, -0.24371915232154473, 0.23753743680428796]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024577339997185997, 0.0, 0.015114245040090308, 0.0, -0.001768101440626048, 0.022585007813253722, -0.8827491523365248, -2.0675966299932653e-07, 0.9999998875626009, -7.210335554302635e-08, -0.1467572668058425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3556685321053996e-10, 9.258837416649198e-19, -9.140636719676175e-20, -0.004469308963665469, 0.0, -0.004469308963665469, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06482657424071259, -0.18365765432537987, 0.07487727180856579]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23213566192047877, 0.0, 0.05706258014776267, 0.0, -0.006299946855483313, -0.037181786036529774, 0.18562744770103873, -0.15313344644011637, 2.18278441124418, -0.10266860507880073, -2.3983620226761873, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5152664950416467e-08, 6.449835678511299e-11, -8.101661218728977e-11, -0.1667311059604873, 0.0, -0.11674110596048722, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8641534837965207, -0.2529330753899315, 0.24164826466741385]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002763126622802015, 0.0, 0.014715260484285174, 0.0, -0.009881334520255435, 0.02020832327353709, -0.9163451716273316, -1.3859157797955176e-09, 0.9999999988633524, -2.659106167568513e-10, -0.11649167426595694, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7278536380372465e-10, 6.655752355851371e-19, -6.407597775466092e-20, -0.0043323744125510905, 0.0, -0.0043323744125510905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06719396421073606, -0.1842784613677346, 0.08221655726251766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2319632265014764, 0.0, 0.057770482237290595, 0.0, -0.007210633493688709, -0.03631973213294236, 0.13818914692060869, -0.15313344669298617, 2.23278441103317, -0.10266860512893017, -2.402454882045091, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5140083647453425e-08, 6.449835680902302e-11, -8.101661218955329e-11, -0.16694001438630976, 0.0, -0.11695001438630967, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8676385016268215, -0.26216224946734557, 0.2461251759565754]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003448708380047142, 0.0, 0.014158041790558417, 0.0, -0.018213732764107912, 0.01724107807174826, -0.9487660156086009, -5.057396124836962e-09, 0.9999999957797983, -1.0025887149796506e-09, -0.08185718737806773, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.5162605926087e-10, 4.782006837362797e-19, -4.5270181613603325e-20, -0.00417816851644912, 0.0, -0.00417816851644912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06970035660601767, -0.18458348154828197, 0.08953822578323085]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23173104700851133, 0.0, 0.05846259660872053, 0.0, -0.008537615134493966, -0.035648819510938186, 0.08928866755855847, -0.153133446975999, 2.2827844108598705, -0.10266860516667987, -2.40482956732299, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5129456485561246e-08, 6.449835682619347e-11, -8.101661219115731e-11, -0.16714590034106, 0.0, -0.11715590034105992, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8712558621315409, -0.2713932207399645, 0.2509657699599279]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004643589859301954, 0.0, 0.013842287428598807, 0.0, -0.026539632816105146, 0.013418252440083479, -0.9780095872410043, -5.660256857419369e-09, 0.9999999965340128, -7.549941392500863e-10, -0.04749370555798135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.125432378435518e-10, 3.434088148950386e-19, -3.208028656262401e-20, -0.004117719095005067, 0.0, -0.004117719095005067, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07234721009438819, -0.18461942545237914, 0.09681188006705028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23141104222420014, 0.0, 0.059088973119694965, 0.0, -0.010267722476716637, -0.03522112581361613, 0.039288643280469646, -0.1531334471910085, 2.332784410797134, -0.10266860517847731, -2.40572005513048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5120976538340005e-08, 6.449835683852151e-11, -8.101661219230342e-11, -0.16733174840413442, 0.0, -0.11734174840413435, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8750123188430854, -0.2806144337404689, 0.25616872659930734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006400095686223723, 0.0, 0.012527530219488686, 0.0, -0.03460214684445339, 0.008553873946441148, -1.0000004855617763, -4.300189833630929e-09, 0.9999999987452631, -2.359488490986696e-10, -0.017809756149802312, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6959894442485648e-10, 2.465609197665229e-19, -2.2922150645620412e-20, -0.003716961261488339, 0.0, -0.003716961261488339, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07512913423088918, -0.1844242600100872, 0.10405913278758819]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23096982086437604, 0.0, 0.059610094166903445, 0.0, -0.012372415846781483, -0.035095026001020616, -0.01071138176099335, -0.15313347984193743, 2.3827844107943843, -0.10266860517907317, -2.4056047163218777, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5114476337657163e-08, 6.449835684737075e-11, -8.101661219312344e-11, -0.16748527184117812, 0.0, -0.11749527184117803, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.878913611844632, -0.2898160089782552, 0.26173669521270304]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00882442719648193, 0.0, 0.010422420944169597, 0.0, -0.04209386740129695, 0.002521996251910276, -1.0000005008292598, -6.530185785309972e-07, 0.9999999999450085, -1.191717988005431e-11, 0.002306776172042873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3000401365680736e-10, 1.769848048487117e-19, -1.6400296063150168e-20, -0.0030704687408736686, 0.0, -0.0030704687408736686, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0780258600309334, -0.18403150475572608, 0.11135937226791391]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23101217788753217, 0.0, 0.06013923085153734, 0.0, -0.014779847226264032, -0.03461757522126543, -0.060711405529473426, -0.15388655706051566, 2.432784409961612, -0.10266860528245277, -2.4051035767174325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5109104446275706e-08, 6.449835685372592e-11, -8.10166121937198e-11, -0.16764292538782805, 0.0, -0.11765292538782796, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.882993401765239, -0.2989815014987048, 0.2676659597185791]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008471404631226059, 0.0, 0.010582733692677745, 0.0, -0.04814862758965098, 0.009549015595103762, -1.0000004753696015, -0.015061544371564787, 0.999999983344559, -2.0675920466798336e-09, 0.010022792088908411, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0743782762911581e-10, 1.2710339242924058e-19, -1.1927150588714577e-20, -0.003153070932998687, 0.0, -0.003153070932998687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08159579841213978, -0.18330985040899092, 0.11858529011752081]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23166096916362228, 0.0, 0.06069844728180941, 0.0, -0.017467751485140307, -0.03315600865469124, -0.11071142628841504, -0.15609643553672656, 2.482784409488149, -0.10266860534438106, -2.4046540117080197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.510470778879998e-08, 6.449835685828496e-11, -8.101661219416032e-11, -0.16781085163138046, 0.0, -0.11782085163138035, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8872813659580655, -0.3080958760385541, 0.2739310444207709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01297582552180187, 0.0, 0.011184328605441374, 0.0, -0.053758085177525484, 0.02923133133148378, -1.0000004151788324, -0.044197569524218314, 0.9999999905307368, -1.2385659558039324e-09, 0.008991300188256925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.793314951453258e-11, 9.118090776345964e-20, -8.810504044423885e-21, -0.0033585248710479576, 0.0, -0.0033585248710479576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08575928385652976, -0.18228749079698595, 0.1253016940438357]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23231091311461602, 0.0, 0.061426229675754, 0.0, -0.020487812432683144, -0.03047972228842628, -0.16071040117553964, -0.16004312160247902, 2.532784401365805, -0.10266860677755257, -2.404459746314448, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5099470222581762e-08, 6.44983568615499e-11, -8.101661219499738e-11, -0.1680341591303878, 0.0, -0.11804415913038771, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918067481223992, -0.31714436187886447, 0.28048703554563337]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299887901987468, 0.0, 0.014555647878891775, 0.0, -0.06040121895085673, 0.053525727325299186, -0.9999794977424918, -0.07893372131504905, 0.9999998375531234, -2.866343021772737e-08, 0.003885307871427466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0475132436431223e-10, 6.529860755311476e-20, -1.6741185686697014e-20, -0.004466149980146987, 0.0, -0.004466149980146987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0905076432866756, -0.1809697168062073, 0.13111982249724963]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23296086532242, 0.0, 0.06215409472709866, 0.0, -0.02392437276710368, -0.02674503752105018, -0.2105817633981625, -0.16561382731665833, 2.5827844013258225, -0.10266860678829268, -2.4046078224207066, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5094715870301405e-08, 6.449835686389057e-11, -8.10166121958493e-11, -0.1682554071836218, 0.0, -0.11826540718362172, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8966191113221037, -0.3261062062074736, 0.2872605000031366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044156079604, 0.0, 0.01455730102689316, 0.0, -0.0687312066884107, 0.07469369534752199, -0.9974272444524571, -0.1114141142835863, 0.9999999992003538, -2.1480196249001482e-10, -0.00296152212516529, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.508704560716088e-11, 4.681360479261919e-20, -1.7038482683341403e-20, -0.004424961064680123, 0.0, -0.004424961064680123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.096247263994089, -0.17923688657218223, 0.1354692891500644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23361081752388146, 0.0, 0.0628508053799112, 0.0, -0.02784263938376655, -0.022316290839102332, -0.26015412376750086, -0.1724837692456318, 2.632784401282506, -0.10266860680981145, -2.4051049133129707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5090870728711455e-08, 6.449835686556409e-11, -8.101661219658032e-11, -0.16846612250000284, 0.0, -0.11847612250000275, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9017766306039234, -0.33495753051188176, 0.2941580202486183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044029229256, 0.0, 0.013934213056250708, 0.0, -0.0783653323332574, 0.088574933638957, -0.991447207386767, -0.1373988385794697, 0.9999999991336712, -4.3037553845922474e-10, -0.00994181784528227, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.690283179901098e-11, 3.3470416807463886e-20, -1.4620468206051482e-20, -0.004214306327620768, 0.0, -0.004214306327620768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10315038563639398, -0.1770264860881631, 0.13795040490963484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23426076965262405, 0.0, 0.06351808585519686, 0.0, -0.03226760423563554, -0.017605180724197828, -0.30950717241445064, -0.18027332003458044, 2.6827844011594446, -0.10266860689586754, -2.405798923004195, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5088168650476983e-08, 6.449835686676262e-11, -8.101661219716285e-11, -0.16866693605027083, 0.0, -0.11867693605027074, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9073312103521671, -0.34367564242710863, 0.3010847318330421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042574851788, 0.0, 0.013345609505713325, 0.0, -0.08849929703737983, 0.09422220229809006, -0.9870609729389952, -0.15579101577897295, 0.999999997538778, -1.7211219437877278e-09, -0.013880193824493153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4041564689418295e-11, 2.3970734751594266e-20, -1.1650638152869926e-20, -0.0040162710053597995, 0.0, -0.0040162710053597995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11109159496487403, -0.17436223830453706, 0.13853423168847506]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2349107218251938, 0.0, 0.06415924023207728, 0.0, -0.03692528791703121, -0.012953309383227089, -0.35869761374305403, -0.18866355862243098, 2.7327844010755875, -0.10266860697854155, -2.406627782416584, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5086476690835496e-08, 6.449835686761823e-11, -8.101661219760747e-11, -0.16885580365123617, 0.0, -0.11886580365123608, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9131786146557287, -0.3522871118930777, 0.3078824838240916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043451394824, 0.0, 0.012823087537608186, 0.0, -0.0931536736279134, 0.09303742681941482, -0.9838088265720679, -0.16780477175701095, 0.9999999983228582, -1.6534801752684214e-09, -0.016577188247773315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383919282975195e-11, 1.7112424024057768e-20, -8.89241380022243e-21, -0.003777352019306943, 0.0, -0.003777352019306943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11694808607123089, -0.172229389319382, 0.13595503982099066]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23556067390849939, 0.0, 0.06478803278538864, 0.0, -0.04183456615147509, -0.008572960011633702, -0.40806390078927407, -0.19748360438472765, 2.782784400791496, -0.10266860719730213, -2.407291329752124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.508617571010874e-08, 6.449835686822646e-11, -8.101661219793906e-11, -0.16903785397931964, 0.0, -0.11904785397931955, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9193752889409146, -0.36076918614489767, 0.3144721097790261]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904166611173, 0.0, 0.01257585106622724, 0.0, -0.09818556468887765, 0.08760698743186775, -0.9873257409244003, -0.17640091524593338, 0.9999999943181707, -4.375211525270041e-09, -0.013270946710809785, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.019614535075065e-12, 1.2164454044679264e-20, -6.631873034439257e-21, -0.0036410065616694046, 0.0, -0.0036410065616694046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12393348570371722, -0.16964148503639906, 0.13179251909868964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.236210626139229, 0.0, 0.06536046745949703, 0.0, -0.04703021406689744, -0.004617444475231801, -0.45798055991983916, -0.20663595352997322, 2.832784400757068, -0.10266860721746252, -2.4074953169164655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5086509559567502e-08, 6.449835686865965e-11, -8.101661219818335e-11, -0.16920172016723956, 0.0, -0.11921172016723948, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9259853034842632, -0.36909590549573923, 0.32081066527974794]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044614591969, 0.0, 0.011448693482167727, 0.0, -0.1039129583084469, 0.07911031072803801, -0.9983331826113014, -0.1830469829049114, 0.999999999311448, -4.0320788269595363e-10, -0.004079743286827765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.676989175211572e-12, 8.663903499395061e-21, -4.885868286263472e-21, -0.003277323758398469, 0.0, -0.003277323758398469, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13220029086697233, -0.16653438701683082, 0.12677111001443597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23686057836931296, 0.0, 0.06587810156161174, 0.0, -0.0524964863405664, -0.00118270585363039, -0.5079805843462595, -0.2160950541819633, 2.882784400716864, -0.10266860724498096, -2.407250737118994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5087157239983762e-08, 6.449835686896832e-11, -8.101661219836138e-11, -0.1693500288244522, 0.0, -0.11936002882445211, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.933051756038837, -0.37724759518933726, 0.3268799032418193]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044601679327, 0.0, 0.010352682042294314, 0.0, -0.10932544547337934, 0.06869477243202822, -1.0000004885284073, -0.1891820130398012, 0.9999999991959225, -5.503687990429099e-10, 0.004891595949425155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2953608325192462e-11, 6.173382684430698e-21, -3.5605898488683896e-21, -0.002966173144252638, 0.0, -0.002966173144252638, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14132905109147714, -0.16303379387196085, 0.12138475924142719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2375105306050451, 0.0, 0.06633846290253478, 0.0, -0.058191351775601974, 0.001668432329925141, -0.5579806092848749, -0.22587296157730907, 2.932784400696764, -0.10266860726613215, -2.4066122039332507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.508792424142453e-08, 6.449835686918893e-11, -8.101661219849074e-11, -0.16948129400264927, 0.0, -0.1194912940026492, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.940598587013591, -0.3852107926240798, 0.33268169117947183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044714642574, 0.0, 0.009207226818460935, 0.0, -0.11389730870071137, 0.05702276367111061, -1.000000498772309, -0.19555814790691595, 0.9999999995979963, -4.2302393165950684e-10, 0.012770663714865474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5340028815336086e-11, 4.412167855239182e-21, -2.5872104320209593e-21, -0.002625303563941781, 0.0, -0.002625303563941781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15093661949507836, -0.15926394869485117, 0.11603575875305036]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23816048284209412, 0.0, 0.0667541920092772, 0.0, -0.06406386082224472, 0.0038888666409760144, -0.6079806341574682, -0.23600022442066063, 2.982784400676464, -0.1026686072896429, -2.405623243830887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.508872929882969e-08, 6.44983568693467e-11, -8.101661219858393e-11, -0.16959939525107245, 0.0, -0.11960939525107236, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9486375546909553, -0.392976246093866, 0.338231045212232]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044740980728, 0.0, 0.008314582134848038, 0.0, -0.11745018093285499, 0.044408686221017464, -1.0000004974518655, -0.2025452568670308, 0.999999999594002, -4.702149838721262e-10, 0.019779202047272564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6101148103212668e-11, 3.1554899151547097e-21, -1.8638372708511323e-21, -0.00236202496846343, 0.0, -0.00236202496846343, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16077935354728673, -0.1553090693957241, 0.11098708065520332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23881043507849506, 0.0, 0.06713184482908141, 0.0, -0.07005742931658411, 0.005448713403224011, -0.6579806591040078, -0.2465303068168445, 3.0327844006582434, -0.10266860732529401, -2.4043287632200925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.514282972494158e-08, 7.788045832160237e-11, -8.560329437215217e-11, -0.16970569426875323, -5.003399515739654e-13, -0.11971569384411146, 1.4031238726829678e-13, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.957150755961286, -0.4005454511699985, 0.34354279610094524]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044728018867, 0.0, 0.007553056396084257, 0.0, -0.11987136988678795, 0.031196935244959915, -1.000000498930792, -0.21060164792367753, 0.9999999996355844, -7.130221769765577e-10, 0.025889612215890707, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0820085222377747e-09, 2.6764202904510995e-10, -9.173364347136461e-11, -0.0021259803536155405, -1.0006799031479392e-11, -0.0021259718607818234, 2.8062477453659823e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17026402540661248, -0.1513841015226497, 0.10623501777426465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23946038731859332, 0.0, 0.06745982263114288, 0.0, -0.07608131544195283, 0.006985865514212323, -0.7079806841127956, -0.25826056162507827, 3.082784400647795, -0.10266860735227312, -2.4030800032637294, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.527012371214173e-08, 1.0864708998263817e-10, -9.677997632206264e-11, -0.16979672706752624, -1.928871302654709e-12, -0.11980672215193221, 2.847132948767664e-13, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9657424103356813, -0.40805883235209867, 0.34846876547088573]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044801965218, 0.0, 0.006559556041229219, 0.0, -0.12047772250737446, 0.030743042219766245, -1.0000005001757544, -0.23460509616467462, 0.9999999997910318, -5.395823536596364e-10, 0.02497519912726212, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5458797440029817e-09, 6.153326332207153e-10, -2.2353363899821064e-10, -0.0018206559754603093, -2.8570627021614932e-11, -0.0018205661564150298, 2.8880181521693924e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17183308748790677, -0.15026762364200294, 0.09851938739881044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24011033953466435, 0.0, 0.0677527459816008, 0.0, -0.0822086278041773, 0.008332059250703178, -0.7579807087765827, -0.2711238912381578, 3.1327844005480205, -0.10266860778403221, -2.40184888287597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.7755034865294392e-08, 7.785868690170071e-10, -3.0716440175586607e-10, -0.1698771715774365, -2.1485484868957436e-11, -0.11988717645968759, 1.0751644402580919e-11, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9745247257379728, -0.4154762821353041, 0.35302023109585084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044321420643, 0.0, 0.005858467009158569, 0.0, -0.12254624724448937, 0.026923874729817117, -1.0000004932757425, -0.25726659226159004, 0.9999999980045062, -8.635181673671529e-09, 0.024622407755194725, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.969822306305346e-08, 1.3398795580687344e-08, -4.207688508676112e-09, -0.0016088901982052723, -3.9113227132605097e-10, -0.0016090861551076078, 2.093386221540805e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17564630804582865, -0.14834899566410767, 0.09102931249930246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24076029177653963, 0.0, 0.06800000696212856, 0.0, -0.08850112972767232, 0.009245438926171438, -0.8079807337982046, -0.28496627182260936, 3.182784400539825, -0.10266860845211243, -2.400607020048759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0008853644981449859, 0.0002637382308716937, -7.146771891412436e-05, -0.16991038573735515, -3.8057901681006385e-06, -0.11994017298333379, 6.410525431392179e-06, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9835661110971916, -0.4227493690965445, 0.357240114665206]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044837505545, 0.0, 0.004945219610555001, 0.0, -0.12585003846990042, 0.018267593509365194, -1.0000005004324353, -0.27684761168903116, 0.9999999998360883, -1.3361604396337824e-08, 0.02483725654421454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017706734862202412, 0.005274749045696493, -0.001429348234994452, -0.0006642831983729642, -7.611537365231539e-05, -0.001059930472923987, 0.0001282102935949555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18082770718437646, -0.1454617392248084, 0.08439767138710356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24141024400779346, 0.0, 0.06821995837171572, 0.0, -0.0954173149560193, 0.01000073734497902, -0.8579807586792207, -0.30134365245337247, 3.2327844004824087, -0.10366299380571066, -2.3993322565561144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0034838259981374462, 0.001075278372717597, -0.00027667944712250346, -0.16989648928945758, -1.0665995980726173e-05, -0.11996402046012122, 2.9197167965890384e-05, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9928493913760116, -0.4298559632274283, 0.36113641751120923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044625076542, 0.0, 0.004399028191743228, 0.0, -0.1383237045669394, 0.015105968376151637, -1.0000004976203232, -0.32754761261526155, 0.9999999988516667, -0.019887707071964605, 0.02549526985289202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05196922999984921, 0.01623080283691807, -0.004104234564167582, 0.0002779289579515554, -0.0001372041162525107, -0.0004769495357487722, 0.0004557328506899641, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1856656055764004, -0.14213188261767673, 0.07792605692006413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24206019613726515, 0.0, 0.06844892257533174, 0.0, -0.10322994962341195, 0.010567485483468524, -0.9075581646694126, -0.3211754490286886, 3.2827844001377096, -0.10633739946830738, -2.3980102125129936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.008058275001504144, 0.0025849065857914445, -0.0006273671868806639, -0.16984517458562104, -1.2865576887126398e-05, -0.1199655901757444, 7.827617340695497e-05, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.002277444823715, -0.4368164476217162, 0.3646931690708545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042589433643, 0.0, 0.004579284072320237, 0.0, -0.15625269334785297, 0.011334962769790083, -0.991548119803838, -0.39663593150632304, 0.9999999931060182, -0.05348811325193439, 0.02644088086241625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09148898006733396, 0.030192564261476942, -0.007013754795163208, 0.0010262940767309845, -4.399161812800449e-05, -3.139431246344614e-05, 0.0009815801088212915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18856106895406935, -0.13920968788575774, 0.07113503119290501]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24271014735545668, 0.0, 0.06874787293089735, 0.0, -0.11181246122470045, 0.010638263384989207, -0.9554400727506829, -0.3439572753134275, 3.3326272902367324, -0.11046176732430736, -2.3970411778031595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.014346171413594525, 0.004781437238488289, -0.001093286566429616, -0.1697671830920926, -5.143484210272699e-07, -0.11995945014555565, 0.0001601188828169425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0117325946551383, -0.4436048593179186, 0.367901924948681]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999024363830792, 0.0, 0.005979007111312021, 0.0, -0.17165023202577, 0.001415558030413662, -0.9576381616254037, -0.4556365256947775, 0.9968578019804555, -0.08248735711999969, 0.01938069419667847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12575792824180765, 0.04393061305393689, -0.009318387590979044, 0.0015598298705688132, 0.00024702456932198255, 0.0001228006037750317, 0.0016368541881997506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1891029966284642, -0.13576823392404802, 0.06417511755653138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24336009339077383, 0.0, 0.06911208095133353, 0.0, -0.12099454928451607, 0.009981495898837137, -1.0006596649569814, -0.3688756086609181, 3.3810430897276267, -0.115549810000113, -2.3965219742173796, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.021883030718840388, 0.007597610194436255, -0.0016255953109058428, -0.16967183363533161, 3.899153842424246e-05, -0.11994583942864961, 0.0002810481335930513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.021152593009951, -0.45012953612448153, 0.37078823184861237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998920706342829, 0.0, 0.007284160408723626, 0.0, -0.18364176119631218, -0.01313534972304141, -0.9043918441259705, -0.4983666669498118, 0.9683159898178832, -0.10176085351611275, 0.010384071715597262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15073718610491732, 0.05632345911895931, -0.010646174889524532, 0.001906989135219824, 0.0007901177369053946, 0.0002722143381207434, 0.0024185850155221756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18839996709625273, -0.13049353613125858, 0.05772613799862674]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24401002931767685, 0.0, 0.06946716407447735, 0.0, -0.13055268892902452, 0.008567826833572266, -1.042635096401456, -0.3951894306300189, 3.4269709053959825, -0.12108094654226279, -2.3964675101427266, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.030065438380500825, 0.010867464926444501, -0.0021724210901542295, -0.16957195787056895, 0.00011163290802802163, -0.1199259998091317, 0.00044033565941127486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0304155316776218, -0.45627700787687003, 0.37337495995121656]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998718538060115, 0.0, 0.007101662462876497, 0.0, -0.19116279289016927, -0.028273381305297413, -0.8395086288894891, -0.5262764393820148, 0.918556313367119, -0.11062273084299575, 0.0010892814930561785, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16364815323320875, 0.06539709464016491, -0.010936515584967731, 0.0019975152952533327, 0.0014528273920755832, 0.00039679239035833916, 0.003185750516364471, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18525877335341703, -0.12294943504777, 0.05173456205208357]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.244638702843577, 0.0, 0.06978804516974647, 0.0, -0.14040087030306717, 0.006448096426094984, -1.0812562667377443, -0.422451826607268, 3.470079183003775, -0.1266889878617854, -2.3967128688421995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.03825354936564267, 0.014322797706453073, -0.002693697588982673, -0.16947901728164144, 0.00021026515893878347, -0.11990413138896315, 0.0006255164001956976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0394773062351537, -0.46197947039692067, 0.3756935510841205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01257347051800293, 0.0, 0.006417621905382441, 0.0, -0.19696362748085303, -0.04239460814954563, -0.7724234067257669, -0.5452479195449826, 0.8621655521558496, -0.11216082639045233, -0.004907173989460893, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16376221970283675, 0.06910665560017146, -0.010425529976568869, 0.0018588117785499649, 0.001972645018215237, 0.00043736840337090893, 0.0037036148156884526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18123549115063742, -0.11404925040101271, 0.04637182265807928]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24521164753546607, 0.0, 0.0701124514909792, 0.0, -0.15048005099341588, 0.003668936385990456, -1.1166898960705396, -0.4503286082028579, 3.51042808204057, -0.13211725877888528, -2.397085287389989, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.04599629838649692, 0.017741987431692453, -0.0031660547062997567, -0.1693960804693822, 0.0003251188479035395, -0.11988091627021663, 0.0008232653127037202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0483350999634555, -0.46721675674792207, 0.3777807302028416]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011458893837781238, 0.0, 0.006488126424654437, 0.0, -0.20158361380697404, -0.055583200802090574, -0.7086725866559038, -0.5575356319117981, 0.8069779807359055, -0.10856541834199768, -0.007448370955783039, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15485498041708512, 0.06838379450478758, -0.009447142346341674, 0.0016587362451847408, 0.0022970737792951195, 0.00046430237493036197, 0.0039549782501604545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17715587456603915, -0.10474572702002777, 0.04174358237442136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2457431790019066, 0.0, 0.07040995868763088, 0.0, -0.16067452973732477, 0.00017563153966600317, -1.149255173945757, -0.4785355477344434, 3.5482980481759143, -0.13728493489067795, -2.397445314253788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05306910501452492, 0.02099266565034233, -0.0035812413581468644, -0.1693246529348996, 0.0004479016872534731, -0.11985968744810045, 0.001023492153873808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0570138598702212, -0.47199494500861205, 0.37967848211931005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010630629328810487, 0.0, 0.005950143933033662, 0.0, -0.2038895748781779, -0.06986609692648905, -0.6513055575043484, -0.5641387906317091, 0.7573993227068856, -0.10335352223585359, -0.007200537275985317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14145613256055994, 0.06501356437299752, -0.008303733036942157, 0.0014285506896522476, 0.002455656786998673, 0.0004245764423236192, 0.004004536823401753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17357519813531241, -0.09556376521379939, 0.03795503832936965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24623682416306564, 0.0, 0.0707079563289476, 0.0, -0.17097816127768922, -0.003965993344349774, -1.1793135886649042, -0.5068601519058047, 3.584009944005424, -0.14200955877775331, -2.397706015072643, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.059346402304760675, 0.023983282525850323, -0.0039368151899130234, -0.16926335536480824, 0.0005715588784351379, -0.11984047213966165, 0.001217855836849493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0655297251300402, -0.4763327419337534, 0.38141946786530345]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009872903223181125, 0.0, 0.005959952826334354, 0.0, -0.2060726308072893, -0.08283249768031553, -0.6011682943829433, -0.5664920834272266, 0.7142379165901928, -0.09449247774150715, -0.005214016377099256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12554594580471498, 0.059812337510159914, -0.007111476635323176, 0.0012259514018271096, 0.002473143823633295, 0.00038430616877598435, 0.0038872736595137016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17031730519637714, -0.08675593850282676, 0.034819714919868]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24669917137160294, 0.0, 0.07110854400390651, 0.0, -0.18137351165665375, -0.008684082437152647, -1.207210518394995, -0.5351144908109712, 3.6178704086659774, -0.1461332576054746, -2.3978152277781444, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06479873207702708, 0.026669539355900506, -0.004235195646961235, -0.16920638279288275, 0.0006912042298969388, -0.11984380408946914, 0.0014009040531841785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0738971398691919, -0.48025640352716864, 0.3830320746007894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009246944170746185, 0.0, 0.008011753499178336, 0.0, -0.20790700757929045, -0.09436178185605745, -0.5579385946018167, -0.5650867781033304, 0.6772092932110652, -0.08247397655442557, -0.002184254110024381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10904659544532808, 0.05372513660100365, -0.005967609140964243, 0.0011394514385099127, 0.002392907029236018, -6.663899614973442e-05, 0.0036609643266937108, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.167348294783036, -0.07847323186830421, 0.032252134709719396]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24713756519619012, 0.0, 0.07161662159460618, 0.0, -0.19181920751019893, -0.013928700345259247, -1.233265553849435, -0.5631305635009443, 3.650163203182221, -0.14954601950098817, -2.3977426910569237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06945302998933739, 0.02903714207045428, -0.004481352498803809, -0.16915443471670596, 0.0008035413628995007, -0.11987115749376802, 0.0015692164366401253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.082139181069535, -0.4837964894678948, 0.3845425922683316]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008767876491743832, 0.0, 0.010161551813993414, 0.0, -0.20891391707090373, -0.104892358162132, -0.5211007090888001, -0.5603214537994627, 0.6458558903248711, -0.06825523791027158, 0.0014507344244152742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09308595824620612, 0.0473520542910755, -0.004923137036851473, 0.0010389615235359142, 0.002246742660051237, -0.0005470680859777075, 0.0033662476691189358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16484082400686262, -0.07080171881452249, 0.030210353350843284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2475549983023322, 0.0, 0.07221804947556329, 0.0, -0.2022520633451531, -0.019659919441386592, -1.2577479030897178, -0.5907710796410779, 3.6811187243890786, -0.15218365542740142, -2.3974697262104225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0733617952878012, 0.03108686676426193, -0.004681185346052456, -0.16911335378890563, 0.0009062177017965661, -0.11992068364232732, 0.0017205143214799351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090271583591517, -0.48698711607074857, 0.3859723144745219]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008348662122841936, 0.0, 0.012028557619142333, 0.0, -0.2086571166990837, -0.11462438192254687, -0.4896469848056584, -0.5528103228026722, 0.6191104241371513, -0.052752718528264936, 0.0054592969300221806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07817530596927597, 0.04099449387615296, -0.003996656944972933, 0.0008216185560068918, 0.00205352677794131, -0.000990522971185916, 0.0030259576967961973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16264805043963856, -0.06381253205707574, 0.02859444412380588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2479472102594153, 0.0, 0.07277340855344801, 0.0, -0.21270860435742253, -0.0257553031992719, -1.280850752184616, -0.6179859183537935, 3.7108818047930496, -0.15394766973952503, -2.3969854451755377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07658252679060347, 0.03282356477000636, -0.004840559327919094, -0.169082526987504, 0.000997256670763036, -0.11996193018387667, 0.0018529057847214154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0982752839084675, -0.48987666725160606, 0.3873289843781169]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007844239141661618, 0.0, 0.011107181557694334, 0.0, -0.20913082024538823, -0.12190767515770617, -0.4620569818979646, -0.5442967742543119, 0.5952616080794234, -0.035280286242472036, 0.009685620697692944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0644146300560456, 0.0347339601148885, -0.0031874796373327595, 0.0006165360280326202, 0.001820779379329397, -0.0008249308309871879, 0.002647829264829606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16007400633900618, -0.05779102361715019, 0.027133398071900464]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24830923659972529, 0.0, 0.07337386558499959, 0.0, -0.22313989557238184, -0.03213087247416113, -1.3026107318144924, -0.6448108712149575, 3.7394798958436555, -0.15474384723208248, -2.396321694120929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07918110565663415, 0.034259845860057904, -0.004965314252016976, -0.16907917721218227, 0.0010753981594887685, -0.12002289436651176, 0.0019653675272334596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1061827568793012, -0.49249649855298394, 0.3886304430224323]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007240526806199981, 0.0, 0.012009140631031652, 0.0, -0.20862582429918639, -0.12751138549778457, -0.43519959259752783, -0.5364990572232802, 0.5719618210121177, -0.015923549851149212, 0.01327502109216846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05197157732061351, 0.028725621801031002, -0.0024950984819576416, 6.699550643474877e-05, 0.0015628297745146522, -0.0012192836527016057, 0.002249234850240885, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15814945941667502, -0.05239662602755755, 0.026029172886307825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24862463085239564, 0.0, 0.07394611704069855, 0.0, -0.2334868214356179, -0.03866522797920096, -1.3228582755315152, -0.6713233661476727, 3.766698009014485, -0.1544932762381133, -2.3956019728805495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08119130327610846, 0.03538729570286875, -0.005060034990195667, -0.16909684923299426, 0.0011380333308511385, -0.12009141847747397, 0.0020549985450074005, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.114034749826976, -0.49486861521606895, 0.3898935680787766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006307885053407134, 0.0, 0.011445029113979188, 0.0, -0.20693851726472104, -0.1306871101007965, -0.4049508743404586, -0.5302498986543039, 0.5443622634165884, 0.005011419879383559, 0.014394424807587222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040203952389486305, 0.02254899685621694, -0.0018944147635738193, -0.0003534404162397632, 0.0012527034272473987, -0.0013704822192443502, 0.001792620355478817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1570398589534946, -0.04744233326170048, 0.025262501126885935]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2488902408213538, 0.0, 0.07457093937817945, 0.0, -0.24368525588475032, -0.04520949421581128, -1.3413731757562728, -0.6975442605548711, 3.792210579966983, -0.15314154581539696, -2.3950046165031367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08270418554636838, 0.03624320988858825, -0.005130517363849807, -0.16915540002066753, 0.0011861582302613296, -0.12018692375812304, 0.0021236421891056073, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.121859340624918, -0.49700967053695455, 0.39113320356853154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005312199379163104, 0.0, 0.012496446749618119, 0.0, -0.20396868898264892, -0.13088532473220646, -0.3702980044951518, -0.5244178881439672, 0.510251419049963, 0.027034608454326873, 0.011947127548261003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030257645405198496, 0.01711828371439004, -0.0014096474730828047, -0.0011710157534653807, 0.0009624979882038237, -0.0019101056129814788, 0.0013728728819641391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1564918159588388, -0.04282110641771238, 0.024792709795098435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24912353621340871, 0.0, 0.07513223207912516, 0.0, -0.2536772728384126, -0.05164389511143233, -1.3580907997199005, -0.7234458610861066, 3.815870628291692, -0.15080311904132584, -2.3946362752860706, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08382363593849158, 0.03687993174972081, -0.005182301129763091, -0.1692215573819852, 0.0012222202733430383, -0.12027941695465248, 0.002174979490205021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1296698499402016, -0.4989414080898131, 0.39235947804980364]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004665907841098379, 0.0, 0.011225854018914055, 0.0, -0.19984033907324586, -0.128688017912421, -0.3343524792725566, -0.5180320106247125, 0.4732009664941699, 0.04676853548142221, 0.007366824341317696, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022389007842464094, 0.012734437222651284, -0.001035675318265673, -0.0013231472263528874, 0.0007212408616341729, -0.00184986393058882, 0.0010267460219882773, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1562101863056704, -0.03863475105717006, 0.024525489625441935]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2493344345873408, 0.0, 0.07563967632388699, 0.0, -0.26341952282290915, -0.05788128941639624, -1.3730749077115205, -0.7489794144675082, 3.837694235913039, -0.1476482398326273, -2.3945344775266433, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08471645046721596, 0.03739691089226394, -0.00522371962957432, -0.1692759901036769, 0.0012509572982918819, -0.12036386595442627, 0.002216012960644409, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1374724259383202, -0.5006880102918698, 0.3935818666634768]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004217967478641756, 0.0, 0.010148884895236805, 0.0, -0.19484499968993063, -0.12474788609927821, -0.29968215983239826, -0.5106710676280313, 0.4364721524269364, 0.06309758417397127, 0.002035955188541833, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017856290574487642, 0.01033958285086268, -0.0008283699962245744, -0.0010886544338339775, 0.0005747404989768734, -0.00168897999547589, 0.0008206694087877571, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15605151996237343, -0.03493204404113411, 0.02444777227346279]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2495291254611555, 0.0, 0.07610743309859812, 0.0, -0.27287351706422835, -0.06386007000921244, -1.386458209829742, -0.7740898896699244, 3.857787198975873, -0.14384533428484642, -2.3946901602483464, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0854231412726906, 0.03781290389683289, -0.005256584665113997, -0.16932647703724382, 0.0012736925265541322, -0.12044372794588123, 0.0022485642461374166, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1452674976683273, -0.5022771875586262, 0.39480428449718397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003893817476293535, 0.0, 0.009355135494222535, 0.0, -0.18907988482638421, -0.11957561185632395, -0.2676660423644314, -0.5022095040483245, 0.40185926125669064, 0.07605811095561746, -0.003113654434061179, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014133816109492768, 0.00831986009137887, -0.0006573007107935482, -0.0010097386713384799, 0.00045470456524500673, -0.0015972398290992655, 0.0006510257098601517, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559014346001425, -0.03178354533512671, 0.02444835667414404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24971127897112055, 0.0, 0.07654770133877788, 0.0, -0.28202049235321547, -0.06954230839885944, -1.39841009718629, -0.7987256849465152, 3.8763066927338796, -0.13952256430313936, -2.3950737502477635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08602912661943857, 0.03818062360835884, -0.005285004379291282, -0.16936674420746403, 0.0012930472728035767, -0.12051849493030337, 0.0022764502291251396, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1530633346958712, -0.5037330045217779, 0.3960326065796455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0036430701993014174, 0.0, 0.008805364803595322, 0.0, -0.1829395057797424, -0.11364476779294014, -0.239037747130961, -0.4927159055318148, 0.37038987516012606, 0.08645539963414126, -0.0076717999883404294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012119706934959314, 0.007354394230518976, -0.0005683942835456974, -0.0008053434044043185, 0.00038709492498888734, -0.0014953396884425615, 0.0005577196597544615, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559167405508805, -0.029116339263036313, 0.024566441649231337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2498811997334895, 0.0, 0.07696791535210463, 0.0, -0.2908505119582744, -0.07490840292520531, -1.4091029551095644, -0.8228576862832844, 3.8934077478201807, -0.13481072107362316, -2.395636361669536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08665705109805102, 0.03857989540280461, -0.00531556344872703, -0.1693847941520483, 0.0013120614635983919, -0.12058461144070116, 0.002304393127038612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1608457475220832, -0.505076987080296, 0.39726780322278493]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0033984152473786307, 0.0, 0.008404280266535249, 0.0, -0.17660039210117842, -0.10732189052691747, -0.21385715846548894, -0.48264002673538264, 0.3420211017260203, 0.09423686459032395, -0.011252228435458242, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012558489572249167, 0.007985435888915442, -0.0006111813887149691, -0.00036099889168517233, 0.0003802838158963023, -0.0013223302079559333, 0.0005588579582694437, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15564825652424044, -0.026879651170361514, 0.02470393286278899]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25000115993437955, 0.0, 0.07737296610074557, 0.0, -0.2994051294674068, -0.07972967766969824, -1.4180548363352028, -0.846838950338786, 3.9088827022417494, -0.13076983364913178, -2.3965707066411355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08720490750152673, 0.038934755676571946, -0.005342607987575832, -0.1694098096627433, 0.001328295122039716, -0.12065251589218774, 0.0023284500129674606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1686696930153928, -0.506346819315667, 0.3985187482679692]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023992040178016263, 0.0, 0.00810101497281858, 0.0, -0.17109235018264904, -0.09642549488985862, -0.17903762451276628, -0.4796252811100323, 0.3094990884313727, 0.08081774848982731, -0.018686899431986294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010957128069514287, 0.007097205475346712, -0.0005408907769760367, -0.0005003102139001786, 0.00032467316882648045, -0.0013580890297316835, 0.0004811377185769764, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15647890986619267, -0.025396644707419605, 0.02501890090368525]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2501128528765304, 0.0, 0.0777500001534744, 0.0, -0.3076626574520455, -0.08398908998894464, -1.4253770195368305, -0.8706588347862696, 3.922838069795817, -0.12737373675756802, -2.3978380776517256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08764483890791952, 0.039222283657003615, -0.00536447615485725, -0.1694426990733101, 0.0013411899074241452, -0.12071852983180784, 0.002347639966393915, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1764936350248556, -0.5075618877322114, 0.3997756683087901]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022338588430173157, 0.0, 0.0075406810545766345, 0.0, -0.16515055969277337, -0.08518824638492802, -0.14644366403255246, -0.4763976889496718, 0.27910735108136014, 0.06792193783127484, -0.025347420211802692, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008798628127855748, 0.0057505596086333995, -0.0004373633456283615, -0.0006577882113359592, 0.0002578957076885856, -0.001320278792401776, 0.0003837990685290854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15647884018925456, -0.024301368330887904, 0.02513840081641829]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.250222107023377, 0.0, 0.07814045360228958, 0.0, -0.31558675468167624, -0.08774208514845928, -1.4313363165262374, -0.8941988204587691, 3.9354755824144307, -0.12439999795243682, -2.3993514994276257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0879830377650946, 0.03944442883754456, -0.005381352453908842, -0.16949046110548174, 0.0013510421824446128, -0.1207898433506332, 0.002362337266378826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1842733442288151, -0.5087324392257867, 0.4010299200038882]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002185082936931633, 0.0, 0.0078090689763035195, 0.0, -0.15848194459261444, -0.07505990319029297, -0.11918593978813569, -0.47079971344998894, 0.2527502523722674, 0.05947477610262393, -0.03026843551800351, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006763977143501597, 0.004442903610818798, -0.00033752598103183225, -0.0009552406434325663, 0.00019704550040935056, -0.0014262703765072612, 0.0002939459996982245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555941840791889, -0.023411029871505826, 0.025085033901963125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.250328588881154, 0.0, 0.07854982634512611, 0.0, -0.32314699141753994, -0.0910615018043292, -1.4362062064183352, -0.91733216606878, 3.9470054616666843, -0.1216692257614047, -2.4010303878620034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08825215548312727, 0.03962308081524697, -0.005394896921203672, -0.16954767309426985, 0.00135854048351819, -0.12086633971100932, 0.002373329976305158, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1919779116487683, -0.5098645693569425, 0.40227705819159126]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021296371555396786, 0.0, 0.008187454856730749, 0.0, -0.15120473471727355, -0.06638833311739835, -0.09739779784195622, -0.462666912200218, 0.23059758504507488, 0.054615443820642505, -0.033577768687551135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005382354360653367, 0.003573039554048211, -0.0002708893458966121, -0.0011442397757623671, 0.00014996602147154326, -0.0015299272075225496, 0.00021985419852663078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15409134839906308, -0.02264260262311428, 0.024942763754061417]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25044677443798924, 0.0, 0.0789310351508406, 0.0, -0.3303914810180706, -0.0940073642956912, -1.4402377407921465, -0.9398617550294959, 3.9577531470201572, -0.11884731069732858, -2.4029501890914604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08888131413347983, 0.0400901811739838, -0.005427818625415681, -0.16956612291601883, 0.0013690491424108756, -0.12093811006109577, 0.0023814325417555182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1998570829218054, -0.5109465285816862, 0.4035890602598723]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023637111367042526, 0.0, 0.007624176114289903, 0.0, -0.14488979201061272, -0.058917249827240135, -0.08063068747622665, -0.45059177921431676, 0.21495370706945977, 0.05643830128152218, -0.03839602458913788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012583173007051151, 0.00934200717473653, -0.0006584340842401881, -0.0003689964349795497, 0.00021017317785371252, -0.0014354070017288175, 0.0001620513090072111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15758342546074328, -0.02163918449487387, 0.026240041365620078]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2505532179037128, 0.0, 0.07929586903932709, 0.0, -0.3373690831277784, -0.09662755946104978, -1.4436190728065044, -0.9618473498290563, 3.9678383447307985, -0.11602930876957356, -2.4050297124221918, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08998955968594656, 0.04095211824572516, -0.005485312955795529, -0.16955045785486964, 0.0013855175680678145, -0.12100880702614375, 0.0023873497559189923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2078212385614393, -0.5119894501275661, 0.40494748046965273]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021288693144714313, 0.0, 0.007296677769729708, 0.0, -0.13955204219415676, -0.0524039033071716, -0.06762664028715556, -0.43971189599120775, 0.2017039542128266, 0.056360038555100564, -0.04159046661462535, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022164911049334525, 0.01723874143482718, -0.0011498866075969482, 0.0003133012229841266, 0.00032936851313877607, -0.0014139393009596631, 0.00011834428326948414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15928311279267743, -0.02085843091759814, 0.02716840419560839]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2506517634511201, 0.0, 0.07964434690229617, 0.0, -0.3440981838528044, -0.09896545280715713, -1.4464855365443796, -0.9833686960106043, 3.9773285492378303, -0.11327696969857846, -2.4071869800940253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09149077261343108, 0.04215558440115099, -0.005561708041550031, -0.16951610028338737, 0.0014084270976688182, -0.12107749989950282, 0.0023916452259841775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2157662453581335, -0.5130047973329463, 0.4063230147980378]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001970910948145528, 0.0, 0.006969557259381621, 0.0, -0.13458201450051924, -0.046757866922146965, -0.057329274757504774, -0.43042692363096063, 0.1898040901406324, 0.05504678141990186, -0.043145353436669726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030024258549690437, 0.02406932310851668, -0.0015279017150900452, 0.0006871514296451799, 0.0004581905920200749, -0.0013738574671815355, 8.590940130370588e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1589001359338853, -0.020306944107604495, 0.027510686567700893]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25073077200964544, 0.0, 0.07998990072013375, 0.0, -0.3505944017270404, -0.10092836899201926, -1.4486131624470993, -1.0046516812355415, 3.9861323799236494, -0.11173409333454518, -2.4095074441614486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.093225656138881, 0.043582872085159916, -0.005647984854840476, -0.1694745756994668, 0.001436726814393381, -0.12114732830509212, 0.0023947512361286475, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2236757441168256, -0.5140110164241644, 0.4077039878514745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015801711705060715, 0.0, 0.006911076356751378, 0.0, -0.12992435748471964, -0.03925832369724269, -0.04255251805439108, -0.4256597044987451, 0.17607661371638397, 0.030857527280665736, -0.04640928134846746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.034697670508998205, 0.028545753680178514, -0.0017255362658089007, 0.0008304916784112001, 0.0005659943344912542, -0.0013965681117859027, 6.212020288940126e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15818997517384187, -0.020124381824360583, 0.027619461068734537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25080897713862554, 0.0, 0.08044152588244509, 0.0, -0.35683265244203677, -0.10254953273507852, -1.4500591173518824, -1.0256942400212732, 3.9943054764795254, -0.11080557356899945, -2.411970532415023, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09502815020830883, 0.045095863809775205, -0.0057364262783810155, -0.16943151060753328, 0.0014674640722687146, -0.12123847113882608, 0.0023969914059407253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2315238505290913, -0.5150135171297713, 0.40907919976109614]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015641025796022537, 0.0, 0.009032503246226719, 0.0, -0.12476501429992826, -0.03242327486118517, -0.02891909809566349, -0.420851175714632, 0.1634619311175191, 0.018570395310914402, -0.04926176507148528, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03604988138855673, 0.030259834492305772, -0.0017688284708107785, 0.0008613018386707719, 0.0006147451575066712, -0.0018228566746791696, 4.480339624155639e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15696212824531636, -0.02005001411213856, 0.027504238192433084]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2508890850624879, 0.0, 0.08100524882298756, 0.0, -0.3627816265074857, -0.1038992066697827, -1.450961301830525, -1.0464243796739299, 4.001949398879483, -0.11009588292026826, -2.4145292759892962, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09674234772988136, 0.04655936232039913, -0.005819631587323354, -0.16939891702274162, 0.0014978398977708535, -0.12135146157420272, 0.0023986043390263408, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2392895434752147, -0.5160131982501563, 0.4104399077604545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016021584772469642, 0.0, 0.011274458810849406, 0.0, -0.11897948130897876, -0.026993478694083292, -0.018043689572848888, -0.4146027930531324, 0.15287844799915015, 0.014193812974623753, -0.05117487148546357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.034283950431450314, 0.02926997021247849, -0.00166410617884676, 0.0006518716958329033, 0.0006075165100427769, -0.0022598087075329323, 3.225866171231416e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15531385892246566, -0.0199936224077015, 0.027214159987168356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25097034216354597, 0.0, 0.08166177260021829, 0.0, -0.36841965812629707, -0.10504204583639816, -1.4514528212931501, -1.0667738171180767, 4.009163851894057, -0.1094531229878194, -2.4171438679628006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0982483854543768, 0.047863170934546416, -0.005891994913857078, -0.16939035260821336, 0.0015254787560757398, -0.12147927189906041, 0.002399764371728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2469610358570717, -0.5170104502290385, 0.41178091879014395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016251420211613034, 0.0, 0.01313047554461474, 0.0, -0.11276063237622722, -0.022856783332309297, -0.009830389252502328, -0.40698874888293507, 0.14428906029146818, 0.012855198648977249, -0.05229183947008239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030120754489908776, 0.026076172282945655, -0.001447266530674482, 0.00017128829056536996, 0.0005527771660977257, -0.002556206497153667, 2.3200654038621596e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15342984763714143, -0.019945039577642314, 0.02682022059378801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2510516357715548, 0.0, 0.08238983040672551, 0.0, -0.37373931888052986, -0.10602558405579081, -1.451636723101241, -1.0867009747543688, 4.01603035192416, -0.10883193500968162, -2.4197886274820073, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09948693644596036, 0.048946450634772765, -0.005951008406069606, -0.16941577211021777, 0.0015488419322775657, -0.12161734675395565, 0.002400598089741445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.254533728220507, -0.5180055434121742, 0.4131003434909167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016258721601768171, 0.0, 0.014561156130144581, 0.0, -0.10639321508465598, -0.019670764387852938, -0.003678036161818359, -0.39854315272584195, 0.13733000060206949, 0.012423759562755585, -0.05289519038413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024771019831671338, 0.021665594004527042, -0.0011802698442505623, -0.0005083900400883748, 0.0004672635240365183, -0.0027614970979048443, 1.66743602634637e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15145384726870115, -0.019901863662714202, 0.026388494015454202]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25113072350251936, 0.0, 0.08316671079778903, 0.0, -0.3787508502494209, -0.10688322005335406, -1.4515869401346837, -1.1061933967026125, 4.022612574827478, -0.10822091811416548, -2.4224489235976785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10053413447045423, 0.04988432002366384, -0.005999585616683752, -0.16945239851070754, 0.0015700793208370388, -0.12176085185538293, 0.0024011969863292843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2620070597950388, -0.5189962436291196, 0.41440058186838186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015817546192903593, 0.0, 0.015537607821270526, 0.0, -0.10023062737782079, -0.017152719951264925, 0.0009956593311480954, -0.3898484389648758, 0.13164445806636133, 0.0122203379103227, -0.05320592231342597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020943960489877154, 0.01875738777782148, -0.0009715442122829234, -0.0007325280097954905, 0.00042474777118946125, -0.0028701020285455936, 1.1977931756787476e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14946663149063966, -0.019814004338908293, 0.026004767549303406]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2512077498607559, 0.0, 0.0839713417336497, 0.0, -0.3834689862330269, -0.10763782587574927, -1.451355323004704, -1.1252540856565276, 4.028958131534314, -0.107617741291297, -2.425117053713206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10147049914294587, 0.05075968485744288, -0.006040501133580966, -0.16948162472260203, 0.0015917127048957383, -0.12190581397054183, 0.0024016270487705743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.269383188225902, -0.5199805547105066, 0.41568456181060137]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015405271647306608, 0.0, 0.016092618717213278, 0.0, -0.09436271967211937, -0.015092116447904307, 0.0046323425995925885, -0.3812137790783025, 0.1269111341367286, 0.012063536457369524, -0.05336260231055568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018727293449832948, 0.017507296675580795, -0.0008183103379442784, -0.0005845242378898277, 0.0004326676811739879, -0.0028992423031777956, 8.60124882580174e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1475225686172621, -0.019686221627741023, 0.02567959884439042]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.251283236033724, 0.0, 0.08479005777822772, 0.0, -0.38790778189684416, -0.1083058200306391, -1.4509789226886234, -1.1438934086373465, 4.03510267516589, -0.10702201970933443, -2.4277888905085194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10234422242273204, 0.051623360896634586, -0.006075212121652766, -0.1694977923462712, 0.0016153865240984893, -0.12205108457547734, 0.0024019358010884543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2766659403596534, -0.520957336272515, 0.41695457405971925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015097234593617792, 0.0, 0.01637432089156036, 0.0, -0.08877591327634525, -0.013359883097796562, 0.0075280063216146, -0.37278645961637474, 0.12289087263149716, 0.011914431639251375, -0.053436735906265645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017474465595723514, 0.017273520783834154, -0.0006942197614360065, -0.0003233524733833357, 0.00047347638405502006, -0.002905412098710196, 6.1750463575958035e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14565504267503143, -0.019535631240165788, 0.025400244982357947]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2513703706317501, 0.0, 0.08560233792714313, 0.0, -0.3914653755268149, -0.10931767661229519, -1.4507202372460386, -1.1615040248686999, 4.041158377999453, -0.10654860150192653, -2.4301595814278203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1031288662475863, 0.05243549333754934, -0.006103568646617251, -0.16950768721629408, 0.001639416326786855, -0.12218852114892764, 0.002402157440366706, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2836370479254333, -0.5218648214860184, 0.41818741861312614]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017426919605227206, 0.0, 0.016245602978308123, 0.0, -0.07115187259941413, -0.020237131633121935, 0.005173708851696833, -0.35221232462706936, 0.12111405667127985, 0.009468364148158047, -0.04741381838601609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01569287649708517, 0.016242648818295107, -0.0005671304992897088, -0.00019789740045794504, 0.0004805960537673125, -0.0027487314690060973, 4.432785565032481e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13942215131559713, -0.018149704270070434, 0.024656891068137697]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2514493477059554, 0.0, 0.08640735379958592, 0.0, -0.39438074012575397, -0.11049767667883857, -1.4504846749983493, -1.1783168217661624, 4.047082425270099, -0.10607602053762469, -2.4323485184059135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10377882459292853, 0.05312604794312293, -0.006125675547297737, -0.16953006966577958, 0.001660681765869331, -0.12231718792113701, 0.002402316536536641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.290366203080503, -0.522726583551331, 0.41938837891773134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015795414841060628, 0.0, 0.016100317448855914, 0.0, -0.05830729197878151, -0.023600001330867752, 0.0047112449537853734, -0.33625593794924863, 0.11848094541290272, 0.009451619286036819, -0.04377873956186737, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999166906844536, 0.01381109211147179, -0.000442138013609722, -0.00044764898970960467, 0.0004253087816495207, -0.002573335444187243, 3.1819233987016685e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13458310310139543, -0.017235241306249663, 0.024019206092104273]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25152137726965274, 0.0, 0.08720634056188904, 0.0, -0.39694784194128746, -0.11162860504159947, -1.4501588634515525, -1.1946168612284684, 4.052821441536157, -0.10557201341794838, -2.4345032700530007, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10428696804614308, 0.05367333725153169, -0.006142384585304982, -0.16957305959306138, 0.001677872515588735, -0.12243918994024111, 0.002402430735385223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2969443548080073, -0.5235699844072766, 0.42056598276904816]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014405912739470898, 0.0, 0.01597973524606254, 0.0, -0.05134203631067011, -0.02261856725521791, 0.0065162309359357, -0.3260007892461209, 0.11478032532116444, 0.010080142393526175, -0.043095032941743765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010162869064290963, 0.010945786168175216, -0.00033418076014491024, -0.0008597985456360133, 0.00034381499438808144, -0.0024400403820820237, 2.283976971636982e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1315630345500841, -0.016868017118913503, 0.023552077026336955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2515895710968562, 0.0, 0.0880038827582948, 0.0, -0.3993571841106828, -0.11257883366699989, -1.4496816148891083, -1.210593772390229, 4.058349833211235, -0.10504560859337787, -2.436714636904913, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10467167667315536, 0.05409095446687562, -0.0061547810938733264, -0.1696364071515194, 0.0016911370611455193, -0.1225578246515458, 0.0024025127075675574, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3034319885042374, -0.5244112287965328, 0.42172666944960296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0013638765440694791, 0.0, 0.015950843928114994, 0.0, -0.04818684338790619, -0.019004572508008532, 0.009544971248885994, -0.3195382232352094, 0.1105678335015558, 0.010528096491410037, -0.04422733703824354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00769417254024549, 0.008352344306878529, -0.00024793017136688064, -0.001266951169160405, 0.0002652909111356853, -0.00237269422609373, 1.6394436466893464e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12975267392460157, -0.016824887785123616, 0.023213733611096164]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25165601234981977, 0.0, 0.08880089468677174, 0.0, -0.401705488789894, -0.1133000700511799, -1.4490392919174342, -1.2263534536172123, 4.0636714740434945, -0.10450946944429648, -2.439020364341578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10495738436931493, 0.05440259411510896, -0.00616387180010065, -0.16971616977015389, 0.0017011019588030409, -0.12267484113871391, 0.0024025715499868044, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.309863737621459, -0.5252574072474873, 0.42287490214630613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001328825059271803, 0.0, 0.015940238569538967, 0.0, -0.04696609358422449, -0.014424727683600187, 0.012846459433482135, -0.31519362453966826, 0.1064328166451877, 0.010722782981627706, -0.046114548733295097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005714153923191549, 0.006232792964666921, -0.00018181412454647971, -0.0015952523726895276, 0.00019929795315043014, -0.0023403297433622454, 1.1768483849375868e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12863498234443288, -0.016923569019088508, 0.022964653934063783]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2517219213707762, 0.0, 0.08959692641837808, 0.0, -0.4040318788854549, -0.11379782598094786, -1.4482468582261694, -1.2419516666479182, 4.068810329934335, -0.10397090018157328, -2.441425229518321, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1051670366962163, 0.05463196907567788, -0.0061704887764203395, -0.16980790546699992, 0.0017084671356192808, -0.12279099914833805, 0.0024026137926661424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3162600404018567, -0.5261104736086814, 0.42401411325666877]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0013181804191289956, 0.0, 0.015920634632126774, 0.0, -0.046527801911218455, -0.009955118595359247, 0.015848673825296693, -0.31196426061411814, 0.10277711781681553, 0.01077138525446414, -0.04809730353485539, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0041930465380275225, 0.004587499211378467, -0.00013233952639378027, -0.001834713936920466, 0.0001473035363247965, -0.002323160192482847, 8.448535867620403e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12792605560795595, -0.017061327223881526, 0.02278422220725272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2517840488892214, 0.0, 0.09039297018418435, 0.0, -0.40630606864495844, -0.11411205211729392, -1.4473502195253878, -1.2572288224036132, 4.073756731239998, -0.10345794360184131, -2.4438787299850278, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10531970381947169, 0.05479932512941808, -0.006175281855884739, -0.1699069376050367, 0.0017138553512427996, -0.12290575888644863, 0.002402644124272723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.322566528822441, -0.5269582940592794, 0.42513566619088144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0012425503689035401, 0.0, 0.01592087531612536, 0.0, -0.045483795190071334, -0.006284522726921066, 0.017932774015629895, -0.3055431151138978, 0.09892802611325544, 0.010259131594639375, -0.04907000933413865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0030533424651077615, 0.0033471210748039436, -9.586158928800168e-05, -0.0019806427607356797, 0.00010776431247037722, -0.0022951947622115894, 6.066321316070164e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12612976841168577, -0.01695640901196175, 0.022431058684253727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25183727523967014, 0.0, 0.09119556850064582, 0.0, -0.4084545037617362, -0.11426976033160821, -1.446363843843916, -1.2718783429389067, 4.078442060445556, -0.10345794448060475, -2.4463114158162225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10543032182927176, 0.05492074213525353, -0.006178742706730733, -0.1700105953147811, 0.0017177713789608316, -0.1230194154144146, 0.0024026659077364685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.328668161853654, -0.527779465347189, 0.42622071250203813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010645270089745392, 0.0, 0.016051966329229284, 0.0, -0.042968702335555255, -0.0031541642862857613, 0.019727513629438115, -0.29299041070586773, 0.0937065841111725, -1.7575268808009414e-08, -0.04865371662389525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002212360196001326, 0.0024283401167090176, -6.921701691987132e-05, -0.002073154194888001, 7.832055436064079e-05, -0.002273130559319578, 4.356692749107305e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12203266062425996, -0.016423425758191737, 0.021700926223133937]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25188632138037004, 0.0, 0.09199312407180757, 0.0, -0.4104344778220663, -0.11431874173510428, -1.445330607035161, -1.2857098174264168, 4.0828465877999625, -0.10345796685082784, -2.4486646599606727, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10551021025493314, 0.055008504621742386, -0.006181236334337058, -0.1701118036766566, 0.0017206052593020298, -0.12312699821340828, 0.0024026815574602627, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3344899417979879, -0.5285604612246441, 0.427256897305005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000980922813997596, 0.0, 0.015951111423234965, 0.0, -0.03959948120660225, -0.0009796280699214416, 0.020664736175099035, -0.2766294897502025, 0.08809054708812164, -4.47404461851312e-07, -0.047064882889001985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015977685132274944, 0.0017552497297770408, -4.987255212649948e-05, -0.002024167237509806, 5.667760682396388e-05, -0.002151655979873508, 3.129944758833179e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1164355988866781, -0.015619917549100942, 0.02072369605933734]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25193259810809177, 0.0, 0.09278820432177419, 0.0, -0.4122345390668309, -0.11429809020395595, -1.444285667178183, -1.2986649594626347, 4.086977892304263, -0.1034579780376268, -2.450908647744438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1055677810459542, 0.055071786407828775, -0.00618303051852708, -0.17020849922150671, 0.0017226502590779302, -0.12322775958521853, 0.0024026928079398384, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3400026927506534, -0.5292963329792928, 0.42823942789731456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0009255345544342075, 0.0, 0.015901604999332252, 0.0, -0.03600122489529118, 0.0004130306229666494, 0.020898797139560794, -0.2591028407243576, 0.08262609008599407, -2.2373597916825168e-07, -0.044879755675313195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011514158204211412, 0.0012656357217277964, -3.588368380043429e-05, -0.0019339108970023349, 4.0899995518008336e-05, -0.00201522743620511, 2.2500959151652763e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11025501905331306, -0.014717435092975711, 0.019650611846191005]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25197645133085544, 0.0, 0.0935816963663875, 0.0, -0.41386182325355364, -0.11423423452844325, -1.4432516187945392, -1.3107651503301205, 4.090854455940515, -0.10345799133382357, -2.453035033714539, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10560920935548486, 0.05511734266221203, -0.006184320226752285, -0.17030023203342265, 0.0017241232447840517, -0.12332207243293278, 0.002402700902757612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.345206334836813, -0.5299872806423424, 0.42916833319696956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008770644552735947, 0.0, 0.015869840892266122, 0.0, -0.03254568373445521, 0.0012771135102540975, 0.02068096767287673, -0.24200381734971804, 0.07753127272505292, -2.659239354982059e-07, -0.042527719402013886, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008285661906132615, 0.0009111250876651154, -2.5794164504089093e-05, -0.001834656238318886, 2.9459714122430193e-05, -0.0018862569542849928, 1.618963554700398e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1040728417231917, -0.013818953260992209, 0.018578105993100516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25201802512904803, 0.0, 0.09437350721371439, 0.0, -0.41533159913780426, -0.11414369129945529, -1.4422414406805852, -1.3220671896363245, 4.094497004565576, -0.10345800665366596, -2.4550470665662116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10563899305640094, 0.05515010352315997, -0.006185246709321951, -0.17038721990956138, 0.001725182926023902, -0.12341067731056632, 0.002402706733468948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3501149588034613, -0.5306358216989933, 0.4300459952102187]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008314759638518819, 0.0, 0.015836216946537772, 0.0, -0.02939551768501207, 0.001810864579759341, 0.020203562279080316, -0.22604078612408063, 0.07285097250122892, -3.063968478377906e-07, -0.04024065703345669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005956740183215744, 0.0006552172189588263, -1.8529651393336408e-05, -0.0017397575227746148, 2.119362479700808e-05, -0.0017720975526707588, 1.1661422672470769e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09817247933296666, -0.012970821133017278, 0.01755324026498267]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25205743042206885, 0.0, 0.09511534537836795, 0.0, -0.41666119148013675, -0.11403647702936102, -1.4412620471670474, -1.3326379436346971, 4.097925033731812, -0.10345801796062243, -2.456952720727884, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10566039137000154, 0.05517364574846635, -0.006185911978192882, -0.1704679239710023, 0.0017259446364386608, -0.1234923477552343, 0.0024027109338961247, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.354747808079967, -0.5312451854624252, 0.43087565409923045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007881058604168197, 0.0, 0.01483676329307122, 0.0, -0.026591846846650086, 0.002144285401885224, 0.019587870270755554, -0.21141507996745212, 0.06856058332472108, -2.261391292873223e-07, -0.038113083233447406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00042796627201193273, 0.0004708445061276411, -1.3305377418628524e-05, -0.001614081228818328, 1.5234208295174606e-05, -0.0016334088933595884, 8.400854353173534e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.092656985530113, -0.012187275268638727, 0.016593177780235432]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25209478266337687, 0.0, 0.09580382268940926, 0.0, -0.417867120756386, -0.11391873667700812, -1.4403168377398459, -1.3425426202850292, 4.101155952106823, -0.10345803089048618, -2.4587609328367837, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10567575910908385, 0.05519055885704734, -0.006186389274443016, -0.17054339769235313, 0.0017264921452987564, -0.12356825332781896, 0.0024027139577310124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3591248277264687, -0.5318185787086221, 0.4316606702905892]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000747044826160569, 0.0, 0.013769546220826238, 0.0, -0.024118585524984592, 0.002354807047058051, 0.018904188544029758, -0.19809353300664106, 0.06461836750021278, -2.5859727492571655e-07, -0.03616424217799424, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0003073547816461414, 0.0003382621716196911, -9.545925002676019e-06, -0.0015094744270168021, 1.0950177201911116e-05, -0.0015181114516932396, 6.047669775742773e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08754039293003056, -0.011467864923938954, 0.015700323827174564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25213020176740003, 0.0, 0.09644781796843163, 0.0, -0.41896405778651435, -0.11379437772857279, -1.4394072407810552, -1.3518404825760437, 4.104205174837294, -0.10345804408800922, -2.4604799490232026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.105686793450238, 0.055202710253189256, -0.0061867313184017165, -0.17061512184675665, 0.001726885897461024, -0.12364000604185366, 0.0024027161337596948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.363264837340766, -0.5323589212783647, 0.4324042216085324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007083820804633355, 0.0, 0.012879905580447286, 0.0, -0.02193874060256702, 0.00248717896870665, 0.01819193917581534, -0.18595724582029133, 0.060984454609432893, -2.6395046092535523e-07, -0.03438032372837389, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00022068682308296934, 0.00024302792283837217, -6.840879174010266e-06, -0.00143448308807027, 7.87504324535279e-06, -0.0014350542806939816, 4.3520573648267073e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08280019228594947, -0.010806851394852098, 0.014871026358864446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2521638085368879, 0.0, 0.09705782276077676, 0.0, -0.4199646444229547, -0.11366604148758092, -1.4385335850126175, -1.3605839703643432, 4.107086456875393, -0.10345805769054033, -2.462116802260276, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10569471584084829, 0.055211445354379246, -0.006186975935433928, -0.17068431229535527, 0.001727169508173785, -0.1237089135105711, 0.002402717698137274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3671849762902262, -0.5328687935469224, 0.4331092111379981]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000672135389757236, 0.0, 0.012200095846902705, 0.0, -0.020011732728806915, 0.002566724819837395, 0.017473115368752734, -0.1748697557659901, 0.057625640761974926, -2.720506219336796e-07, -0.03273706474146647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001584478122058646, 0.00017470202379983146, -4.892340644231018e-06, -0.001383808971972524, 5.672214255219063e-06, -0.0013781493743489491, 3.128755158852691e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0784027789892027, -0.010197445371154277, 0.014099790589313179]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2521957190320927, 0.0, 0.0976424300823295, 0.0, -0.4208796614173853, -0.113535639165772, -1.4376955749217215, -1.3688191362063777, 4.10981218340798, -0.1034580720575404, -2.463677319741626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10570040500700563, 0.05521773575270602, -0.006187150028942731, -0.17075175426220437, 0.0017273746476820554, -0.12377581527194051, 0.0024027188220472426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3709006767410337, -0.53335046266212, 0.43377826211527154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006382099040957203, 0.0, 0.011692146431054809, 0.0, -0.0183003398886113, 0.0026080464361782968, 0.016760201817921035, -0.16470331684068962, 0.05451453065173742, -2.8734000142589386e-07, -0.031210349627006723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011378332314690922, 0.00012580796653543233, -3.4818701760595052e-06, -0.0013488393369818215, 4.102790165410353e-06, -0.0013380352273881992, 2.2478199372823145e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07431400901615198, -0.009633382303953858, 0.013381019545468288]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2522260412962682, 0.0, 0.09820777109321628, 0.0, -0.4217182974288865, -0.11340463898947115, -1.4368925502841448, -1.3765864558089211, 4.11239356997694, -0.1034580887254969, -2.4651663246060536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10570449471598348, 0.055222297425716604, -0.006187271697649338, -0.17081796748869274, 0.0017275253881866624, -0.12384126965526704, 0.0024027196291510687, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3744258152720772, -0.5338059290210464, 0.43441374213360184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006064452835097719, 0.0, 0.011306820217735481, 0.0, -0.016772720230024102, 0.0026200035260172143, 0.01606049275153292, -0.15534639205086667, 0.05162773137921023, -3.3335912999688724e-07, -0.029780097288547903, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.179417955707347e-05, 9.123346021165581e-05, -2.433374132141852e-06, -0.00132426452976708, 3.014810092142655e-06, -0.001309087666530551, 1.61420765195768e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07050277062086902, -0.009109327178527787, 0.012709600366606238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2522548058422406, 0.0, 0.09875983862538447, 0.0, -0.4224884439778365, -0.11327425704616399, -1.4361236393113403, -1.3839216504341916, 4.11484083042943, -0.10345810858862015, -2.466587867529029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10570787740080612, 0.05522890784764913, -0.006187129383718363, -0.17088291626932864, 0.001727879070378211, -0.12390601595288453, 0.00240272020857797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3777728957657804, -0.534236968969182, 0.4350178140206973]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005752909194477611, 0.0, 0.011041350643363894, 0.0, -0.0154029309790006, 0.0026076388661430507, 0.015378219456089094, -0.14670389250540808, 0.04894520904980519, -3.972624648653938e-07, -0.028430858459515016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.765369645287906e-05, 0.00013220843865055694, 2.8462786194922073e-06, -0.0012989756127177409, 7.073643830969089e-06, -0.0012949259523497834, 1.1588538029068464e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06694160987406436, -0.008620798962711979, 0.012081437741909076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2522810826391496, 0.0, 0.09930307409840082, 0.0, -0.4231972469826839, -0.11314620245888432, -1.435387971032144, -1.3908563491443762, 4.1171638296635455, -0.10345813154746225, -2.4679453151694952, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10571719086201957, 0.05528957744876022, -0.0061831654472027054, -0.17093638905762232, 0.001732227096365462, -0.12397061135245838, 0.002402720624471051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3809531611613457, -0.5346451588814208, 0.4355927412850681]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005255359381802212, 0.0, 0.010864709460326982, 0.0, -0.01417606009694806, 0.0025610917455933194, 0.014713365583928011, -0.13869397420369148, 0.04645998468231298, -4.591768420053064e-07, -0.027148952809317645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018626922426898156, 0.0012133920222218725, 7.927873031315128e-05, -0.0010694557658737758, 8.69605197450229e-05, -0.0012919079914769703, 8.317861613487325e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06360530791130661, -0.008163798244776036, 0.011498545287416404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2523049556709934, 0.0, 0.09983980817302991, 0.0, -0.4238508757583281, -0.11302190970905479, -1.4346845719963397, -1.3974186506781736, 4.119371499526478, -0.10345815587459502, -2.4692416838862883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10573817446142976, 0.055458209928084076, -0.006171656846004307, -0.17097062172381056, 0.001744471975500404, -0.12403520936971556, 0.0024027209229453526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3839768053948955, -0.5350319506811975, 0.4361406028308413]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00047746063687615926, 0.0, 0.010734681492581877, 0.0, -0.013072575512883268, 0.0024858549965905297, 0.014067980716087454, -0.13124603067594928, 0.04415339725865123, -4.865426552131862e-07, -0.025927374335864485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004196719882036933, 0.003372649586477127, 0.0002301720239679806, -0.0006846533237645364, 0.0002448975826988396, -0.0012919603451435147, 5.969486031032251e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06047288467099532, -0.00773583599553198, 0.010957230915463263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25231105867045767, 0.0, 0.10032268659628076, 0.0, -0.42446746627060933, -0.11290597500680676, -1.4340071467623623, -1.4036302515566106, 4.121483163477144, -0.10345816738598954, -2.4704868561916666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10602300036644575, 0.05644840990583399, -0.006126919208253724, -0.1709647671816199, 0.0017963618162778734, -0.12409384929284009, 0.0024027211371325657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.386848340805747, -0.5353990642266322, 0.4366769460153868]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012205998928510446, 0.0, 0.009657568465016886, 0.0, -0.012331810245624778, 0.0023186940449606845, 0.013548504679549465, -0.12423201756874025, 0.04223327901331664, -2.302278903075514e-07, -0.0249034461075673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005696518100319927, 0.019803999554998217, 0.0008947527550116634, 0.00011709084381317724, 0.0010377968155493864, -0.0011727984624907164, 4.283744261503167e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05743070821702976, -0.00734227090869527, 0.010726863690910672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2523188094797908, 0.0, 0.10074464917216873, 0.0, -0.42504951425777376, -0.11278915832928407, -1.4333476002082248, -1.4095131832815728, 4.123499300925834, -0.10345816988190619, -2.471686254968168, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10654301939956613, 0.05814535167257401, -0.006055248380414588, -0.17093855232995553, 0.0018807993092550166, -0.1241450852309312, 0.0024027212908256275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3895767672843515, -0.5357475406306564, 0.4372017921544714]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015501618666287543, 0.0, 0.008439251517759594, 0.0, -0.011640959743288451, 0.0023363335504536834, 0.01319093108274753, -0.11765863449924412, 0.040322748973795966, -4.991833310515157e-08, -0.023987975530022763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010400380662407671, 0.03393883533480032, 0.0014334165567827142, 0.0005242970332873035, 0.0016887498595428655, -0.0010247187618219879, 3.0738612348291766e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.054568529572089366, -0.006969528080483983, 0.010496922781692026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25232885862824356, 0.0, 0.10116024567945477, 0.0, -0.4255961205029673, -0.11266379064750323, -1.4327009916678688, -1.4150884027982873, 4.125418168118807, -0.10345818450485329, -2.472842467687111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10721255203362133, 0.06027569963772623, -0.005968390000174377, -0.17090554310000322, 0.001983890023619507, -0.12419636302586053, 0.0024027214011058374, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3921711124662541, -0.5360782591893937, 0.43771177977817916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020098296905553546, 0.0, 0.008311930145720783, 0.0, -0.010932124903870284, 0.002507353635616749, 0.012932170807119288, -0.11150439033428819, 0.03837734385944171, -2.9245894199194703e-07, -0.0231242543788592, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013390652681103975, 0.04260695930304441, 0.0017371676048042206, 0.0006601845990460799, 0.0020618142872898077, -0.0010255558985866617, 2.205604198864253e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05188690363805183, -0.006614371174744213, 0.010199752474154828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25233978743735, 0.0, 0.10153958509369299, 0.0, -0.4261066533264455, -0.1125256081626484, -1.4320649867357211, -1.4203755507597082, 4.127239650367151, -0.10345818634608428, -2.4739570242530036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10795575531660262, 0.0626041941710074, -0.00587603027607318, -0.1708740392195339, 0.0020940761458180975, -0.124242964716481, 0.0024027214802336723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3946396185457506, -0.5363920878285561, 0.4382039229803152]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00021857618212894488, 0.0, 0.007586788284764475, 0.0, -0.010210656469563829, 0.0027636496970966525, 0.012720098642952277, -0.10574295922841706, 0.03642964496687413, -3.682461984830631e-08, -0.022291131317851706, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014864065659625888, 0.04656989066562343, 0.0018471944820239333, 0.0006300776093866601, 0.002203722443971815, -0.0009320338124093223, 1.5825566985773357e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04937012158993097, -0.006276572783247628, 0.009842864042720797]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25235081238131624, 0.0, 0.10188010687161837, 0.0, -0.42658151396548233, -0.11237304327453626, -1.4314387002731135, -1.425392779282794, 4.128965635970542, -0.10345818878354753, -2.4750312016139193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10872086664217569, 0.06497296374650176, -0.005784486389953149, -0.17084605420882681, 0.0022037771703792897, -0.12428444395244008, 0.0024027215370081545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3969897165402927, -0.5366898988034393, 0.43867646379442005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002204988793241671, 0.0, 0.006810435558507696, 0.0, -0.009497212780736777, 0.0030512977622426008, 0.012525729252154399, -0.10034457046171488, 0.034519712067826946, -4.8749265024789204e-08, -0.02148354721831199, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015302226511461223, 0.04737539150988701, 0.0018308777224006194, 0.000559700214141463, 0.002194020491223848, -0.0008295847191816055, 1.1354896463247653e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04700195989084004, -0.005956219497665675, 0.009450816282096928]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2523615518493593, 0.0, 0.10218726546571343, 0.0, -0.4270219788164988, -0.1122060834171935, -1.4308219122795724, -1.4301567071834642, 4.130599386530522, -0.10345819145130036, -2.4760663295793854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10947733479528081, 0.06729055243874994, -0.0056972992032803295, -0.17082147255211852, 0.002308715574222338, -0.12432163777486833, 0.002402721577743542, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3992281273912792, -0.536972549330397, 0.43912874478502045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00021478936086224702, 0.0, 0.006143171881901009, 0.0, -0.008809297020328632, 0.0033391971468551946, 0.012335759870818929, -0.0952785580134033, 0.032675011199605065, -5.335505688550676e-08, -0.02070255930932595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015129363062102306, 0.04635177384496364, 0.0017437437334563933, 0.0004916331341660921, 0.0020987680768609625, -0.0007438764485651794, 8.147077489777581e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0447682170197297, -0.005653010539153125, 0.009045619812007726]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25237180432570033, 0.0, 0.10246770684300431, 0.0, -0.4274298720423899, -0.11202549641134905, -1.430214654632429, -1.434682490214723, 4.132144917315334, -0.10345819412846476, -2.477063828051916, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.110209559510599, 0.06951168524394583, -0.005616123643615657, -0.17079966186833437, 0.0024068672006875317, -0.12435553777525776, 0.0024027216069707285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4013609639450544, -0.5372408634039042, 0.43956087529949484]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020504952682063983, 0.0, 0.005608827545817632, 0.0, -0.008157864517822317, 0.0036117401168888016, 0.012145152942866515, -0.09051566062517595, 0.030910615696239055, -5.3543287884058287e-08, -0.019949969450617815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014644494306363958, 0.04442265610391772, 0.0016235111932934412, 0.0004362136756832034, 0.001963032529303876, -0.0006780000077885038, 5.845437301617798e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.042656731075501886, -0.0053662814701439816, 0.008642610289487096]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25238146729099886, 0.0, 0.10272726560371492, 0.0, -0.4278072816896573, -0.11183237069216756, -1.4296170193905635, -1.438983962857811, 4.133606548978579, -0.10345819667964753, -2.478025164345737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11091124954441599, 0.07161952821038192, -0.0055414738815414985, -0.17077999815497685, 0.002497575674379573, -0.12438697670761464, 0.0024027216279407953, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4033938203181482, -0.5374956216835886, 0.4399734245601298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00019325930597105238, 0.0, 0.00519117521421219, 0.0, -0.007548192945348385, 0.003862514383629993, 0.011952704837308318, -0.08602945286175687, 0.029232633264897296, -5.1023655601979586e-08, -0.019226725876418098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014033800676339744, 0.0421568593287219, 0.0014929952414831674, 0.000393274267150515, 0.0018141694738408242, -0.0006287786471375757, 4.194013393674222e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040657127461877954, -0.005095165593687294, 0.008250985212698882]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.252390498619779, 0.0, 0.10297054659822659, 0.0, -0.4281563625357159, -0.11162786300695883, -1.4290290783612039, -1.4430738043909863, 4.1349886238260884, -0.10345819906531699, -2.4789518057430064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11158131597285993, 0.07361295746927608, -0.005473243221318875, -0.17076199936251932, 0.0025809316914033277, -0.12441657427680099, 0.0024027216429864484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.405331849454142, -0.5377375581661414, 0.44036719778333466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018062657560339655, 0.0, 0.004865619890233428, 0.0, -0.00698161692117084, 0.004090153704174718, 0.01175882058719403, -0.08179683066350556, 0.02764149695018586, -4.7713389156000937e-08, -0.018532827945387548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013401328568879003, 0.03986858517788333, 0.0013646132044524797, 0.0003599758491505228, 0.0016671203404750878, -0.0005919513837269764, 3.0091306327358426e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03876058271987631, -0.004838729651057456, 0.007875464464097757]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25239912014465093, 0.0, 0.10320074871406983, 0.0, -0.4284789728327183, -0.11141292446113953, -1.4284508411738002, -1.4469637486864482, 4.136295091832374, -0.10345820115612882, -2.479845078873402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11221675201287994, 0.07548885154843417, -0.005411099751601362, -0.17074550205563596, 0.002657228456062587, -0.12444472181421161, 0.0024027216537814127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4071799123529072, -0.5379673526596446, 0.44074284351978865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017243049743785943, 0.0, 0.004604042316864782, 0.0, -0.006452205940048214, 0.004298770916386131, 0.011564743748072957, -0.07779888590923667, 0.026129360125708784, -4.181623651505934e-08, -0.017865462607910006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012708720800400164, 0.03751788158316165, 0.001242869394350254, 0.00032994613766736846, 0.0015259352931851925, -0.0005629507482125733, 2.1589928957066197e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03696125797530156, -0.004595889870062838, 0.007512914729080267]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25240788883287985, 0.0, 0.10341921090359552, 0.0, -0.42877628638766924, -0.11118805108569497, -1.4278822331579157, -1.4506647982331757, 4.137529094262974, -0.10345820251928418, -2.4807060067310833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11280518750251034, 0.07722351517365207, -0.005354843772584346, -0.17073082535817635, 0.0027264559802593477, -0.12447152516526674, 0.002402721661526578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4089427333317257, -0.5381856232370856, 0.4411004400034654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017537376457820027, 0.0, 0.004369243790513728, 0.0, -0.0059462710990193166, 0.004497467508891094, 0.011372160317688475, -0.07402099093455003, 0.024680048611995072, -2.7263107276517037e-08, -0.017218557153624272, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011768709792608191, 0.034693272504357955, 0.001125119580340323, 0.00029353394919214915, 0.001384550483935208, -0.000536067021102832, 1.5490330273349073e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.035256419576371614, -0.00436541154882128, 0.007151929673534652]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524165283047511, 0.0, 0.10367626904295699, 0.0, -0.42904960059587494, -0.11095396924352419, -1.4273231563224698, -1.4541871698337983, 4.1386939108002325, -0.10345820920579682, -2.481535591477113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11333946222009197, 0.07880623630250141, -0.005303986410941733, -0.17071674179455218, 0.0027890023901728065, -0.124504331360235, 0.0024027216670835685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4106246560266353, -0.5383929598937067, 0.4414403062931066]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017278943742480877, 0.0, 0.005141162787229341, 0.0, -0.005466284164113492, 0.00468163684341589, 0.011181536708917477, -0.07044743201244882, 0.02329633074516376, -1.3373025259099935e-07, -0.016591694920593734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010685494351632619, 0.03165442257698698, 0.0010171472328522554, 0.0002816712724833791, 0.0012509281982691733, -0.0006561238993651669, 1.1113980964272267e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03363845389819144, -0.004146733132421199, 0.006797325792824263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524247754735371, 0.0, 0.10397725529916613, 0.0, -0.42930046387087295, -0.11071150764304778, -1.4267734895842392, -1.4575403605727661, 4.139792986169174, -0.10345821955408305, -2.4823349753426234, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1138195195301069, 0.08024282762714313, -0.005257830302466809, -0.17070282362717393, 0.002845605639976733, -0.12454279676792503, 0.002402721671070587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4122296542545412, -0.5385899313663324, 0.44176311765439663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016494337572021898, 0.0, 0.006019725124182855, 0.0, -0.00501726549996023, 0.00484923200952796, 0.010993334764610691, -0.06706381477935658, 0.02198150737882517, -2.0696572446165557e-07, -0.01598767731020425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00960114620029839, 0.028731826492834293, 0.0009231221694984696, 0.00027836334756486947, 0.0011320649960785275, -0.0007693081538004969, 7.974037597446838e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0320999645581175, -0.003939429452512818, 0.006456227225800288]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25243208614273377, 0.0, 0.10427135883619229, 0.0, -0.4295309231646412, -0.11046155496924469, -1.4262330960093574, -1.4607331500367289, 4.140830075613454, -0.10345822102089722, -2.4831056354956518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11425669845215781, 0.08156666134715308, -0.005215448235800749, -0.1706901848597512, 0.002897468501116762, -0.12457975761167994, 0.0024027216739311843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4137612699071913, -0.5387770943321168, 0.4420701458417623]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001462133839337144, 0.0, 0.005882070740523317, 0.0, -0.004609185875365357, 0.004999053476061811, 0.010807871497634, -0.06385578927925532, 0.020741788885613857, -2.9336283382280514e-08, -0.015413203060570717, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008743578441018394, 0.02647667440019904, 0.0008476413333212132, 0.000252775348454132, 0.001037257222800585, -0.0007392168750983597, 5.7211944552818607e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030632313053001264, -0.003743259315689659, 0.006140563747312932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524386161026168, 0.0, 0.1045927287012955, 0.0, -0.42974293641997124, -0.11020533035715467, -1.4257018210528243, -1.4637737146905603, 4.141808986840661, -0.10345823703472296, -2.4838488591929044, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1146624738036024, 0.08280884715242881, -0.005176196904034627, -0.17067732097166968, 0.0029455046386646683, -0.12462037582836553, 0.002402721675983598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4152228835522174, -0.538954973602994, 0.4423626521076397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013059919766130167, 0.0, 0.006427397302064168, 0.0, -0.0042402651066003934, 0.005124492241800449, 0.01062549913066165, -0.06081129307662716, 0.019578224544135474, -3.2027651469270726e-07, -0.014864473945057242, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00811550702889161, 0.024843716105514484, 0.0007850266353224452, 0.0002572777616304568, 0.0009607227509581214, -0.000812364333711761, 4.1048279311635796e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.029232272900520426, -0.0035575854175441627, 0.005850125317548449]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25244451568747894, 0.0, 0.10489862283535707, 0.0, -0.42993816963933745, -0.10994310611565047, -1.4251794223257293, -1.4666697889232347, 4.142732716349441, -0.10345823836208652, -2.4845661404424435, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1150448657919448, 0.08398940194690599, -0.0051397788787799475, -0.1706653452387719, 0.0029902006336061685, -0.1246585288455415, 0.0024027216774561585, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4166176983244227, -0.539124057021721, 0.4426416716482021]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001179916972422966, 0.0, 0.006117882681231457, 0.0, -0.0039046643873242755, 0.005244484830083867, 0.01044797454190189, -0.057921484653488065, 0.018474590175589518, -2.654727123789898e-08, -0.0143456249907856, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007647839766848121, 0.02361109588954369, 0.0007283605050935847, 0.00023951465795565388, 0.0008939198988300027, -0.000763060343519305, 2.9451209208577416e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027896295444105598, -0.0033816683745381375, 0.005580390811248256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25244988641889987, 0.0, 0.10518199744623236, 0.0, -0.4301180496360858, -0.10967538557074491, -1.4246656559747581, -1.469428624463279, 4.14360414428067, -0.10345824123782917, -2.4852587040167173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11540915481497344, 0.0851204843307938, -0.0051060637260996545, -0.17065383872086512, 0.003031811634252953, -0.12469346161789656, 0.002402721678512687, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4179487915457625, -0.5392847995178365, 0.4429080618486328]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010741462841893505, 0.0, 0.0056674922175057865, 0.0, -0.0035975999349672234, 0.005354410898111162, 0.010275327019424232, -0.055176710800887735, 0.01742855862457895, -5.751485300868667e-08, -0.01385127148547518, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007285780460572703, 0.02262164767775639, 0.0006743030536058526, 0.00023013035813520557, 0.0008322200129356811, -0.0006986554471011754, 2.11305718614372e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026621864426793235, -0.003214849922309842, 0.005327804008613766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524547922057172, 0.0, 0.10544930140808326, 0.0, -0.4302838006950364, -0.10940266274535936, -1.4241602685060817, -1.4720570551915202, 4.144425933069922, -0.1034582466533407, -2.4859276357431375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11575848211774693, 0.0862085254031375, -0.005075000365721078, -0.17064245759939803, 0.0030704631480591173, -0.124726343370833, 0.002402721679270722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4192191052832688, -0.5394376270012365, 0.44316253346337764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.811573634710679e-05, 0.0, 0.005346079237017992, 0.0, -0.0033150211790126827, 0.0054544565077110155, 0.010107749373529722, -0.052568614564821745, 0.016435775785042225, -1.0831023090621251e-07, -0.013378634528403013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00698654605547001, 0.021760821446873916, 0.0006212672075715294, 0.00022762242934179372, 0.0007730302761232925, -0.0006576350587290871, 1.5160702567309994e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025406274750124073, -0.0030565496680004297, 0.005089432294897381]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.252459274395601, 0.0, 0.10570629192834773, 0.0, -0.4304364879411714, -0.10912528936848931, -1.4236629891980808, -1.474561544920135, 4.145200490700179, -0.10345825312111441, -2.486573972171318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11609456321952229, 0.08725641785299225, -0.005046556891630503, -0.17063119221573195, 0.0031062276650514415, -0.12475807999134682, 0.002402721679814595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.42043144158421, -0.5395829399993146, 0.44340569001868446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.964379767591536e-05, 0.0, 0.0051398104052893375, 0.0, -0.0030537449226994626, 0.005547467537400983, 0.00994558616001968, -0.050089794572297924, 0.01549115260514667, -1.293554741874651e-07, -0.01292672856361362, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006721622035506979, 0.02095784899709504, 0.0005688694818115101, 0.0002253076733215942, 0.0007152903398464851, -0.0006347324102761264, 1.0877456978425782e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024246726018825313, -0.002906259961562272, 0.004863131106137004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524635734915108, 0.0, 0.10593104038006644, 0.0, -0.43057684410276603, -0.10884316570100643, -1.4231735090549147, -1.4769482763375057, 4.145929685259788, -0.10345825341644023, -2.487198714891492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11641439453289071, 0.08825603321375018, -0.0050206092363928225, -0.17062125274194356, 0.00313916308548637, -0.12478562146172324, 0.0024027216802048113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4215885267665547, -0.5397211094653114, 0.44363784764567277]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.598191819541807e-05, 0.0, 0.004494969034374295, 0.0, -0.0028071232318923945, 0.005642473349657707, 0.009789602863322599, -0.04773462834741495, 0.01458389119218786, -5.906516286848044e-09, -0.012494854403477175, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006396626267368406, 0.01999230721515869, 0.0005189531047535984, 0.0001987894757678545, 0.0006587084086985737, -0.0005508294075284662, 7.804326224009938e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02314170364689233, -0.002763389319935588, 0.004643152539765884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.252467739865164, 0.0, 0.10614580339440124, 0.0, -0.43070548762660604, -0.10855658712638953, -1.4226915504491129, -1.479223076025764, 4.146615470099531, -0.10345825787520677, -2.4878026118170773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11671409921661106, 0.0891979329372975, -0.00499692075396499, -0.17061166236190262, 0.0031694186990919152, -0.12481238850871189, 0.0024027216804847827, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4226929836684181, -0.5398524850348708, 0.4438592521182718]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.332747306456586e-05, 0.0, 0.004295260286696001, 0.0, -0.002572870476800208, 0.005731571492337872, 0.009639172116036777, -0.045495993765169045, 0.013715696794846284, -8.917533067036723e-08, -0.012077938511707104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0059940936744071515, 0.018837994470946428, 0.0004737696485566646, 0.0001918076008191951, 0.0006051122721109054, -0.0005353409397728478, 5.599425198486464e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022089138037269307, -0.002627511391187949, 0.004428089451981261]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524716859677797, 0.0, 0.10633475718654596, 0.0, -0.43082305276414157, -0.10826551205490864, -1.422216806660039, -1.481391488195598, 4.147259574200346, -0.10345825826889866, -2.4883865709276605, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11699138872585549, 0.09007709364228711, -0.004975206159162721, -0.17060329202444285, 0.0031972266101797362, -0.12483589289191199, 0.002402721680685656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.423747262913884, -0.5399774016702159, 0.44407020923412377]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.892205231327277e-05, 0.0, 0.0037790758428943826, 0.0, -0.0023513027507103147, 0.005821501429617749, 0.009494875781479154, -0.043368243396681584, 0.012882082016302334, -7.873837879013814e-09, -0.011679182211665131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005545790184888488, 0.017583214099792337, 0.000434291896045383, 0.00016740674919524815, 0.0005561582217564198, -0.0004700876640021326, 4.017459232354812e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021085584909318524, -0.002498332706901068, 0.0042191423170392095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524753745920427, 0.0, 0.10651870813228476, 0.0, -0.43093022795364755, -0.10797035308305296, -1.4217490083092552, -1.4834587127742427, 4.147863971224743, -0.10345826133416983, -2.4889513403214854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11724596007680599, 0.09089383235207912, -0.004955156674448521, -0.17059513401288232, 0.00322288605442226, -0.12485927295140747, 0.0024027216808297776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.424753689755081, -0.5400961804005612, 0.44427111742136455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.377248526034217e-05, 0.0, 0.0036790189147758, 0.0, -0.002143503790119236, 0.005903179437113761, 0.009355967015673289, -0.04134449157289196, 0.012087940487950637, -6.13054232698171e-08, -0.011295387876499889, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005091427019009989, 0.016334774195840288, 0.00040098969428398776, 0.00016316023121097875, 0.0005131888848504735, -0.0004676011899097486, 2.882434891018568e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020128536823939683, -0.002375574606904648, 0.004018163744815867]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524787788106196, 0.0, 0.10668304225041257, 0.0, -0.4310277035766627, -0.1076711703571787, -1.4212878575381216, -1.485429700571354, 4.148430397309103, -0.10345826174528196, -2.4894978236195318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11747859425597898, 0.09165100377170586, -0.004936501362399924, -0.17058793057651367, 0.0032466824113629176, -0.12488013963685018, 0.0024027216809331814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4257144489094233, -0.5402091279840887, 0.4444624133123931]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.808437153732487e-05, 0.0, 0.0032866823625562844, 0.0, -0.0019495124603028198, 0.005983654517485078, 0.009223015422672743, -0.03941975594222403, 0.011328521687197097, -8.222242744538874e-09, -0.01092966596093072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004652683583459854, 0.015143428392534807, 0.0003731062409719403, 0.00014406872737276317, 0.00047592713881315093, -0.0004173337088542328, 2.06808094903569e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.019215183086844927, -0.0022589516705498287, 0.0038259178205714748]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524819008345845, 0.0, 0.10684616128974027, 0.0, -0.43111616885107557, -0.10736833562159828, -1.4208330848480126, -1.4873091025667247, 4.14896071589166, -0.10345826410485444, -2.490026782683878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11769087464088479, 0.09235343662341491, -0.004918998192612217, -0.1705807873377292, 0.0032688901530525116, -0.1249012880951034, 0.0024027216810073716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4266316249459219, -0.5403165362231217, 0.4446445630982576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.244047929864852e-05, 0.0, 0.003262380786553835, 0.0, -0.0017693054882575406, 0.006056694711608286, 0.009095453802178601, -0.03758803990741561, 0.010606371651151374, -4.719144959587418e-08, -0.01057918128692068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004245607698116235, 0.014048657034181105, 0.00035006339575414393, 0.00014286477568966547, 0.00044415483379188004, -0.00042296916506411465, 1.4838006615542238e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018343520729972865, -0.0021481647806605364, 0.003642995717290597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25248474625669926, 0.0, 0.10701404662060518, 0.0, -0.4311962775832543, -0.10706213025485642, -1.4203844178802578, -1.4891013276386371, 4.149456672068131, -0.10345826695097833, -2.490538988087432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11788457002442443, 0.09300611020786191, -0.00490245849495804, -0.17057363945648912, 0.0032897347396003214, -0.12492337526522385, 0.002402721681060601, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4275071979300304, -0.5404186819974677, 0.44481802595938247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.690844229531458e-05, 0.0, 0.003357706617298197, 0.0, -0.0016021746435744832, 0.006124107334837373, 0.008973339355094466, -0.03584450143824733, 0.009919123529411322, -5.692247788077616e-08, -0.010244108071072323, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0038739076707928, 0.01305347168893981, 0.00033079395308353317, 0.00014295762480124143, 0.000416891730956194, -0.0004417434024090064, 1.0645929494327913e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017511459682169783, -0.002042915486918923, 0.003469257222496691]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524873195837004, 0.0, 0.10718727730866164, 0.0, -0.4312686404900011, -0.10675272435527558, -1.4199415794425212, -1.4908105613202647, 4.149919876349894, -0.10345826981376927, -2.4910352214982967, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11806144583505773, 0.0936137367221106, -0.004886739421437854, -0.17056659356990211, 0.003309396004975799, -0.12494627637487345, 0.0024027216810987924, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4283430487038942, -0.5405158277826762, 0.44498324389653]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.1466540023485414e-05, 0.0, 0.003464613761129012, 0.0, -0.0014472581349360082, 0.006188117991616877, 0.008856768754733938, -0.03418467363255006, 0.009264085635251627, -5.725581868737553e-08, -0.009924668217298184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0035375162126659305, 0.012152530284973817, 0.00031438147040371205, 0.00014091773174026789, 0.0003932253075095509, -0.00045802219299204323, 7.638210276439825e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016717015477274378, -0.0019429157041698057, 0.0033043587429501444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25248962769742034, 0.0, 0.10736433148657494, 0.0, -0.431333822634857, -0.10644019931569673, -1.419504290214717, -1.4924407791350558, 4.150351816644547, -0.10345827212079356, -2.491516263140614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11822315837711983, 0.09418054994632133, -0.004871735877537195, -0.17055974878967384, 0.003328013877569058, -0.12496965582159764, 0.0024027216811261937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4291409658822323, -0.5406082222689998, 0.44514063666456366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6162274399102916e-05, 0.0, 0.0035410835582661048, 0.0, -0.0013036428971182359, 0.006250500791576933, 0.0087457845560824, -0.032604356295823055, 0.008638805893064528, -4.614048582057343e-08, -0.009620832846350106, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0032342508412419686, 0.01133626448421468, 0.0003000708780131881, 0.00013689560456526468, 0.0003723574518651859, -0.0004675889344839244, 5.480240711177716e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015958343566763726, -0.0018478897264734883, 0.003147855360673664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249167948626344, 0.0, 0.10754306922408581, 0.0, -0.43139234430061313, -0.10612458699755443, -1.4190722732372134, -1.4939957565565247, 4.150753881996881, -0.10345827318844707, -2.491982874629639, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11837120961281215, 0.09471024616845379, -0.0048573724555174645, -0.17055316743702842, 0.0033456954258704948, -0.1249931753402874, 0.0024027216811458533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4299026529050363, -0.5406961010189989, 0.44529060023858547]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.103577686229883e-05, 0.0, 0.0035747547502174557, 0.0, -0.0011704333151225726, 0.006312246362845803, 0.008640339550071258, -0.03109954842937842, 0.00804130704667184, -2.135307021638489e-08, -0.009332229780496977, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0029610247138464915, 0.010593924442649278, 0.0002872684403946214, 0.0001316270529081837, 0.00035363096602873624, -0.0004703903737952492, 3.9319470425399304e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015233740456079944, -0.0017575749999807853, 0.002999271480435555]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524934911260325, 0.0, 0.10772249826139851, 0.0, -0.4314446864618676, -0.10580604919695182, -1.4186452695148812, -1.4954790630762134, 4.151127467039792, -0.10345827410380912, -2.4924357233240344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11850695535402547, 0.09520608139217204, -0.004843593926912102, -0.1705470186276672, 0.0033625245338653235, -0.12501671743944043, 0.0024027216811599588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4306297411069726, -0.5407796869910159, 0.44543350951879745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.623279538113905e-05, 0.0, 0.0035885807462540343, 0.0, -0.0010468432250894868, 0.006370756012052337, 0.008540074446642143, -0.02966613039377476, 0.007471700858234771, -1.830724096789972e-08, -0.00905697388790408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0027149148242662773, 0.009916704474364987, 0.0002755705721072495, 0.00012297618722484092, 0.00033658215989657356, -0.00047084198306061474, 2.821081843409112e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014541764038728505, -0.0016717194403401657, 0.0028581856042399407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249507368369367, 0.0, 0.10790216023418471, 0.0, -0.4314912916425668, -0.10548477808715775, -1.4182230299738428, -1.496894084327711, 4.151473919356777, -0.10345827501599586, -2.4928754267687028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11863159711450412, 0.09567087061012845, -0.004830360970047671, -0.17054144756277034, 0.0033785659604634423, -0.1250402426708643, 0.002402721681170079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4313237897442812, -0.5408591913684799, 0.44556971772598714]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.165115322443363e-05, 0.0, 0.003593239455723793, 0.0, -0.0009321036139827227, 0.006425422195881235, 0.008444790820768258, -0.028300425029951996, 0.006929046339684343, -1.824373477070205e-08, -0.008794068893368898, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002492835209573, 0.009295784359128147, 0.00026465913728860755, 0.00011142129793676669, 0.00032082853196237427, -0.00047050462847774235, 2.0240615372600666e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013880972746170357, -0.0015900875492814758, 0.0027241641437940113]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524964366796926, 0.0, 0.10808181540993243, 0.0, -0.43153256628691666, -0.1051609532564025, -1.4178053117320677, -1.498244037227448, 4.151794518855292, -0.1034582759460892, -2.4933025732228913, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11874619447415971, 0.09610704663542627, -0.004817645697155328, -0.17053655410781382, 0.0033938700611185904, -0.12506373684919642, 0.0024027216811773403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4319862876542928, -0.5409348142978782, 0.44569955731604965]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7259919979148523e-05, 0.0, 0.0035931035149544504, 0.0, -0.0008254928869975312, 0.006476496615105239, 0.00835436483549922, -0.02699905799473933, 0.006411989970306879, -1.8601866734863772e-08, -0.008542929083766054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022919471931118207, 0.008723520505956296, 0.00025430545784686375, 9.786909913044658e-05, 0.00030608201310296235, -0.00046988356664205504, 1.4522177436833575e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01324995820023286, -0.0015124585879634838, 0.0025967918012505995]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524975897731293, 0.0, 0.1082613245810364, 0.0, -0.43156888390044784, -0.10483474255969862, -1.4173918780831523, -1.4995319795682136, 4.152090481723463, -0.10345827693153219, -2.4937177233840915, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11885168415373029, 0.09651673421248405, -0.0048054277491277105, -0.17053240220673796, 0.0034084770949922806, -0.1250871945495201, 0.00240272168118255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4326186565664267, -0.5410067455283744, 0.44582334161554116]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3061868733526988e-05, 0.0, 0.003590183422079326, 0.0, -0.0007263522706236663, 0.006524213934077648, 0.008268672978310567, -0.02575884681531397, 0.005919257363424423, -1.9708859711931857e-08, -0.008303003224001432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021097935914117273, 0.008193751541155599, 0.00024435896055235415, 8.303802151746029e-05, 0.00029214067747380094, -0.0004691540064737523, 1.0419329339563495e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012647378242680194, -0.0014386246099239112, 0.002475685989830201]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249854263872257, 0.0, 0.10844059233646682, 0.0, -0.43160058812608276, -0.10450631084444476, -1.4169824992484992, -1.5007608179600203, 4.152362968614254, -0.10345827799900396, -2.49412140859432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11894889820507813, 0.0969018145221682, -0.004793691364773112, -0.1705290299851458, 0.0034224205400884117, -0.12511061230370477, 0.002402721681186288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4332222545990734, -0.5410751649934131, 0.4459413664627785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.905731186535969e-05, 0.0, 0.003585355108608104, 0.0, -0.0006340845126982769, 0.006568634305077152, 0.008187576693060727, -0.024576767836132874, 0.005449737815820441, -2.134943542660433e-08, -0.008073704204571095, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0019442810269567703, 0.007701606193682989, 0.00023472768709197734, 6.744443184321146e-05, 0.0002788689019226203, -0.0004683550836933626, 7.475629903089368e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012071960652933986, -0.0013683893007750431, 0.0023604969447464145]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249930505025237, 0.0, 0.10861956606690039, 0.0, -0.4316279956097521, -0.10417583216528904, -1.4165769534495283, -1.5019333146888618, 4.152613094531208, -0.10345827915103799, -2.494514127359418, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1190385797522423, 0.09726397687264945, -0.004782423291103255, -0.17052645997797503, 0.003435729514873332, -0.12513398978184814, 0.00240272168118897, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4337983797537546, -0.541140243342709, 0.44605391172283676]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5248230595957057e-05, 0.0, 0.003579474608671497, 0.0, -0.0005481496733869447, 0.006609573583114158, 0.008110915979417566, -0.023449934576831845, 0.005002518339096259, -2.3040680536778058e-08, -0.007854375301952859, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017936309432833955, 0.007243247009625181, 0.00022536147339713804, 5.140014341561327e-05, 0.0002661794956984067, -0.00046754956286728007, 5.3635930523944134e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011522503093624452, -0.0013015669859192287, 0.002250905201165234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524998883945725, 0.0, 0.10879840095990594, 0.0, -0.43165139913500833, -0.10384353283451074, -1.4161750304355354, -1.503052090635296, 4.15284195579909, -0.10345828049217003, -2.4948963284139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11912139826657485, 0.09760476824587222, -0.0047716110186357035, -0.17052472744838323, 0.0034484308682004414, -0.12515735561646552, 0.002402721681190894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4343482746843161, -0.5412021423929178, 0.44616124302137655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1666886402755246e-05, 0.0, 0.0035766978601109024, 0.0, -0.00046807050512428713, 0.006645986615565914, 0.00803846027985905, -0.022375518928682902, 0.0045772253576376425, -2.6822640793726503e-08, -0.007644021089639064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016563702866510554, 0.006815827464455172, 0.00021624544935104276, 3.465059183604228e-05, 0.00025402706654218657, -0.00046731669234727766, 3.848255036555525e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010997898611231634, -0.0012379810041748445, 0.0021466259707954268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525003043050153, 0.0, 0.10897741810911275, 0.0, -0.43167106991511683, -0.10350970293975632, -1.4157765321287095, -1.5041196312536773, 4.153050639099335, -0.10345828232845566, -2.495268407235448, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11919795940845908, 0.09792561977080978, -0.0047612419515256875, -0.1705238767980194, 0.0034605502131995463, -0.12518075966064138, 0.0024027216811922745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.434873130019234, -0.5412610155948835, 0.44626361290612115]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.318208855958413e-06, 0.0, 0.003580342984136435, 0.0, -0.00039341560216962844, 0.006676597895088218, 0.007969966136519546, -0.021350812367625347, 0.004173666004893266, -3.672571269730873e-08, -0.007441576430964209, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015312228376845422, 0.006417030498751312, 0.00020738134220031138, 1.7013007276802883e-05, 0.00024238689998210168, -0.0004680808835174641, 2.7610347528415173e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010497106698361675, -0.0011774640393141323, 0.002047397694891744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250056199777027, 0.0, 0.10915685015769623, 0.0, -0.43168725851356654, -0.10317464192197127, -1.4153812681838234, -1.5051382992175388, 4.153240193213947, -0.10345828462556604, -2.495630730789191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11926880806461108, 0.09822784316821245, -0.004751303726670063, -0.17052392839602434, 0.0034721116582265535, -0.12520423361065364, 0.002402721681193265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4353740844553402, -0.5413170085581582, 0.4463612610236851]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.153855099642811e-06, 0.0, 0.003588640971669454, 0.0, -0.00032377196899458714, 0.006701220355701015, 0.007905278897723933, -0.020373359277231502, 0.0037910822922489857, -4.594220747090706e-08, -0.00724647107486297, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014169731230401397, 0.00604446794805331, 0.0001987644971124929, -1.0319600992743894e-06, 0.0002312289005401437, -0.0004694790002449638, 1.9809791266289073e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010019088722122042, -0.0011198592654958323, 0.001952962351279709]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525006716811663, 0.0, 0.10933681581224193, 0.0, -0.4317001967343679, -0.10283867091869037, -1.4149890567719554, -1.5061103393116713, 4.153411638040677, -0.1034582873773915, -2.49598363339406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11933443571876777, 0.09851264759327906, -0.004741783894691773, -0.17052488196939983, 0.003483138278404697, -0.12522779039415452, 0.002402721681193976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4358522275973402, -0.5413702594531301, 0.446454415053972]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.1936679209689417e-06, 0.0, 0.003599313090913898, 0.0, -0.00025876441602703073, 0.00671942006561824, 0.00784422823735728, -0.01944080188265033, 0.0034288965345937853, -5.503650913848695e-08, -0.007058052097376657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0013125530831337255, 0.005696088501332263, 0.0001903966395657832, -1.907146750953426e-05, 0.00022053240356287258, -0.00047113567001759183, 1.4213070995845063e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009562862839999096, -0.001065017899437826, 0.0018630806057371003]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525006446467645, 0.0, 0.10951734351084795, 0.0, -0.4317100995416548, -0.10250215550925255, -1.4145997262435115, -1.507037881779375, 4.1535659793374275, -0.10345829057457463, -2.4963274080266666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11939528715516118, 0.09878115489616926, -0.004732669679308067, -0.17052672350806422, 0.0034936524958262124, -0.12525142978831266, 0.002402721681194486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.436308603230223, -0.5414208993717876, 0.44654329168760876]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.406880356466864e-07, 0.0, 0.0036105539721204877, 0.0, -0.00019805614573874199, 0.006730308188756361, 0.007786610568879249, -0.018550849354073744, 0.0030868259350038023, -6.394366261586799e-08, -0.006875492652131085, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0012170287278680466, 0.005370146057804128, 0.00018228430767412249, -3.683077328768231e-05, 0.0002102843484303052, -0.0004727878831630051, 1.0197552520541675e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009127512657657266, -0.0010127983731496384, 0.001777532672735091]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250024683646244, 0.0, 0.10967991520443256, 0.0, -0.4317170846093674, -0.10216053568502476, -1.4142127050299458, -1.5079235121463859, 4.153701428164187, -0.10345829079875102, -2.496664459227406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11945154707052118, 0.09903336044673502, -0.004723986163199914, -0.17052714226277949, 0.0035036329183928214, -0.1252724761111067, 0.002402721681194852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4367439888839186, -0.5414690608296366, 0.44662804378220056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.956206041913836e-06, 0.0, 0.0032514338716922745, 0.0, -0.000139701354252904, 0.006832396484556028, 0.007740424271313811, -0.01771260734021741, 0.0027089765351797288, -4.48352785201282e-09, -0.006741024014788602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011251983072000742, 0.005044111011315333, 0.0001736703221630695, -8.375094305022139e-06, 0.00019960845133218364, -0.00042092645588075964, 7.316510112001781e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008707713073914315, -0.0009632291569807933, 0.0016950418918363368]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249976094537047, 0.0, 0.10982153734125799, 0.0, -0.4317213397255061, -0.1018145229347189, -1.4138278636710668, -1.5087691101015954, 4.153819103841309, -0.10345829105358656, -2.496994885558162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11950361384393553, 0.0992703840138673, -0.004715714819038201, -0.17052617261007352, 0.0035131068050698808, -0.1252905957803363, 0.0024027216811951142, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.437159340840383, -0.5415148609795127, 0.4467088694299034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.717821839101677e-06, 0.0, 0.0028324427365087313, 0.0, -8.510232277329901e-05, 0.006920255006116923, 0.007696827177577579, -0.016911959104189262, 0.002353513542450804, -5.096710801979133e-09, -0.006608526615123668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010413354682871094, 0.004740471342645429, 0.00016542688323424834, 1.9393054119149533e-05, 0.0001894777335411861, -0.0003623933845919471, 5.249428252535549e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008307039129290967, -0.000916002997520956, 0.001616512954056842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250137358761393, 0.0, 0.11013386519272177, 0.0, -0.43172381699032564, -0.10151690216714954, -1.413446790007604, -1.509571672313606, 4.153949458913465, -0.1034606672104238, -2.497296659055861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11955705046445445, 0.09951887041172326, -0.0047068856210787345, -0.17055112558538887, 0.0035231734292377574, -0.12533706312028953, 0.0024027216811953024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4375583357137551, -0.5415583897038049, 0.44678677310347054]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.225284486937632e-05, 0.0, 0.006246557029275519, 0.0, -4.954529639090937e-05, 0.0059524153513873124, 0.007621473269254952, -0.016051244240207534, 0.0026071014431222326, -4.752313674480964e-05, -0.0060354699539849135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001068732410378395, 0.00496972795711925, 0.00017658395918932618, -0.0004990595063071539, 0.00020133248335753643, -0.0009293467990643485, 3.766343035045179e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007979897467438416, -0.0008705744858426893, 0.0015580734713430563]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250123319896933, 0.0, 0.11046367066295873, 0.0, -0.43172411246470266, -0.1012275962349581, -1.4130692874470165, -1.5103361374992912, 4.154070511372676, -0.10346066756890546, -2.4975869636407295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11960598277190915, 0.09974912229180803, -0.004698624136039197, -0.17057913801075325, 0.0035325697273976974, -0.12538669966808283, 0.0024027216811954378, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4379396460698677, -0.5415997397477195, 0.4468611627746132]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8077728922242697e-06, 0.0, 0.006596109404739374, 0.0, -5.909487540367595e-06, 0.005786118643828867, 0.007550051211747151, -0.015289303713704506, 0.002421049184198503, -7.16963324977728e-09, -0.005806091697372856, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0009786461490941753, 0.004605037601695376, 0.00016522970079075943, -0.0005602485072877552, 0.00018792596319879522, -0.0009927309558659463, 2.7022641121889272e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0076262071222490515, -0.0008270008782914171, 0.0014877934228533375]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525007292779986, 0.0, 0.1107730504389141, 0.0, -0.4317221549418397, -0.10093469709835044, -1.4126943808247012, -1.5110653811061423, 4.154176157822125, -0.10346067243821684, -2.497871222673151, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11964997869359197, 0.0999584462207124, -0.004691046235532908, -0.1706037962145071, 0.003541169409691249, -0.12543216789452802, 0.002402721681195535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4383034194738122, -0.5416390222467217, 0.4469320388955833]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0078419414195723e-05, 0.0, 0.006187595519107414, 0.0, 3.91504572596842e-05, 0.0058579827321530685, 0.007498132446305204, -0.01458487213702452, 0.00211292898898495, -9.738622780715217e-08, -0.005685180648430174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008799184336562582, 0.004186478578087279, 0.0001515580101257763, -0.000493164075077061, 0.00017199364587103618, -0.0009093645289040094, 1.938812223432029e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0072754680788898905, -0.0007856499800441572, 0.0014175224194024325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250017251356, 0.0, 0.11105437173998403, 0.0, -0.43171803357329985, -0.10063668670859607, -1.412321410974244, -1.5117613531275305, 4.154266158791327, -0.10346067775202093, -2.498150486312361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11968981161970005, 0.1001502113900759, -0.004684038876394425, -0.1706240592715194, 0.0035491032938626296, -0.12547217808998107, 0.0024027216811956043, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4386503743922627, -0.541676345568565, 0.44699957814219665]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1135288771855741e-05, 0.0, 0.0056264260213985855, 0.0, 8.242737079706473e-05, 0.005960207795087284, 0.007459397009145204, -0.013919440427765144, 0.0018000193840611973, -1.0627608180664975e-07, -0.005585272784201395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007966585221615804, 0.00383530338727013, 0.00014014718276967927, -0.0004052611402459578, 0.00015867768342760926, -0.0008002039090609101, 1.3910531636821325e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006939098369007831, -0.0007464664368673386, 0.001350784932266651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249960517041925, 0.0, 0.11130994429950984, 0.0, -0.4317119055304327, -0.10033583263386532, -1.4119501084311115, -1.5124255118211523, 4.154342387483122, -0.10346068276661556, -2.498424169608367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11972633334296749, 0.10032824509932194, -0.004677469989685064, -0.1706406192012513, 0.0035565230894252543, -0.12550739685946583, 0.002402721681195654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4389814060540655, -0.5417118081757079, 0.4470639944459756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1346862815409195e-05, 0.0, 0.005111451190516094, 0.0, 0.00012256085734345352, 0.006017081494614951, 0.007426050862649289, -0.013283173872437229, 0.0015245738358913262, -1.0029189264180334e-07, -0.005473665920116116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007304344653489404, 0.003560674184920708, 0.00013137773418721942, -0.0003311985946376716, 0.00014839591125249827, -0.0007043753896950072, 9.980486718486138e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006620633236054182, -0.0007092521428554155, 0.0012883260755792822]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525001384373557, 0.0, 0.1117050192891867, 0.0, -0.43170436900186454, -0.10006576368687699, -1.4115803122696655, -1.5130566697447685, 4.154424442521445, -0.10346308571835948, -2.4986785013611303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1197646631853682, 0.10051870249933413, -0.004670340489154515, -0.17067602305255583, 0.003564547883005011, -0.12556336701526652, 0.00240272168119569, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4392991754655564, -0.541745510335605, 0.44712608062212517]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0665338728663511e-05, 0.0, 0.007901499793537149, 0.0, 0.0001507305713631738, 0.005401378939766552, 0.0073959232289202035, -0.01262315847232582, 0.0016411007664546785, -4.805903487831204e-05, -0.005086635055265355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007665968480142496, 0.003809148000243815, 0.00014259001061098394, -0.0007080770260910116, 0.00016049587159513884, -0.00111940311601398, 7.160756158517093e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0063553882298192236, -0.0006740431979440943, 0.0012417235229906737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250000610788326, 0.0, 0.11209411001814666, 0.0, -0.4316952662242287, -0.09980524104495966, -1.4112133297647802, -1.5136573042948216, 4.154500725766428, -0.10346308626118651, -2.4989224480148606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1197995995660239, 0.10069395450060291, -0.004663734164297208, -0.17071145257965203, 0.0035719712807648018, -0.12561846584493908, 0.0024027216811957157, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.439603012924848, -0.5417774931899243, 0.4471854049468531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.646589448364274e-06, 0.0, 0.007781814579199122, 0.0, 0.00018205555271695706, 0.005210452838346618, 0.007339650097706639, -0.012012691001060534, 0.001525664899654792, -1.0856540568420598e-08, -0.004878933074607122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006987276131141497, 0.003505040025375655, 0.00013212649714613355, -0.0007085905419242748, 0.0001484679551958168, -0.001101976593451383, 5.137671509296194e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006076749185834609, -0.0006396570863848082, 0.0011864864945589867]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249962144075555, 0.0, 0.11244605294697997, 0.0, -0.43168457320367054, -0.09954748596863551, -1.4108486459487477, -1.5142293507289228, 4.154567889258225, -0.10346309509115553, -2.4991591516070817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11983089597366163, 0.10085236216300913, -0.004657723870433551, -0.17074203477995611, 0.0035787144210383095, -0.12566726131852235, 0.002402721681195734, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4398931515837508, -0.5418078370077145, 0.4472419948645333]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.693342554454928e-06, 0.0, 0.007038858576666083, 0.0, 0.00021386041116345578, 0.0051551015264829705, 0.007293676320648721, -0.011440928682023063, 0.0013432698359509628, -1.765993803859804e-07, -0.004734071844420179, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006259281527545936, 0.0031681532481245478, 0.00012020587727314016, -0.0006116440060817338, 0.00013486280547015766, -0.0009759094716655546, 3.686158203834384e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0058027731780533115, -0.0006068763558047287, 0.0011317983536046066]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249957286519636, 0.0, 0.11291105001908276, 0.0, -0.4316725796237195, -0.09930873162805244, -1.4104845594478104, -1.5147734315263812, 4.154635734494015, -0.10346566666853016, -2.4993823421973334, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11986346121231904, 0.10101988057910342, -0.004651294549655318, -0.17078692635800605, 0.00358590801036463, -0.12573171610384903, 0.002402721681195747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.440171348248949, -0.5418366595919201, 0.44729646504611703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.715111832212327e-07, 0.0, 0.009299941442055856, 0.0, 0.00023987159902028637, 0.0047750868116613505, 0.007281730018745863, -0.01088161594916629, 0.0013569047157915284, -5.143154749257046e-05, -0.0044638118050375625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006513047731483317, 0.0033503683218857206, 0.00012858641556464748, -0.0008978315609988181, 0.00014387178652640578, -0.0012890957065336793, 2.644731444288415e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0055639333039663435, -0.0005764516841108768, 0.0010894036316740792]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249939957111855, 0.0, 0.11336490963706723, 0.0, -0.43165924659737326, -0.09907658820700373, -1.4101227996290768, -1.5152909551032032, 4.154697547813176, -0.10346571652271423, -2.4995971660286918, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11989301202149834, 0.10117313740778036, -0.00464537917342248, -0.17083080453302915, 0.00359251770894912, -0.12579359409639249, 0.0024027216811957565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4404372423415666, -0.5418639840760764, 0.44734849415962974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.4658815559833157e-06, 0.0, 0.009077192359689493, 0.0, 0.00026666052692491386, 0.004642868420974282, 0.007235196374672906, -0.01035047153644131, 0.001236266383221228, -9.970836815166966e-07, -0.0042964766271680185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005910161835857875, 0.0030651365735388713, 0.00011830752465675056, -0.0008775635004621102, 0.00013219397168979892, -0.0012375598508688114, 1.8975331751156095e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005317881852348869, -0.0005464896831253916, 0.0010405822702546361]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524991175333611, 0.0, 0.11376903100444105, 0.0, -0.4316445581937212, -0.09884734552449141, -1.4097630225416558, -1.5157834009442641, 4.154751632465885, -0.10346572932866722, -2.4998054134093515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11991907507680505, 0.10130929215868707, -0.004640097656576569, -0.1708684626021264, 0.0035984122442281807, -0.12584738954286698, 0.0024027216811957634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4406911617342395, -0.541889877827432, 0.44739811438904004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0" + }, + "execution_count": 20, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "reset_giskard()\n", + "\n", + "# variables\n", + "gripper_link = 'r_gripper_tool_frame'\n", + "\n", + "# adding the object\n", + "cyl_pose = PoseStamped()\n", + "cyl_pose.header.frame_id = 'map'\n", + "cyl_pose.pose.orientation.w = 1\n", + "cyl_pose.pose.position = Point(2, -0.2, 1.2)\n", + "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", + "\n", + "obstacle_pose = PoseStamped()\n", + "obstacle_pose.header.frame_id = 'mycyl'\n", + "obstacle_pose.pose.orientation.w = 1\n", + "obstacle_pose.pose.position = Point(-0.1, 0.1, 0)\n", + "gs.world.add_box('obstacle', size=(0.02, 0.06, 0.05), pose=obstacle_pose, parent_link='mycyl')\n", + "\n", + "# define the robot features\n", + "robot_pointing_feature = Vector3Stamped()\n", + "robot_pointing_feature.header.frame_id = gripper_link\n", + "robot_pointing_feature.vector = Vector3(1, 0, 0)\n", + "\n", + "robot_point_feature = PointStamped()\n", + "robot_point_feature.header.frame_id = gripper_link\n", + "robot_point_feature.point = Point(0, 0, 0)\n", + "\n", + "robot_gripper_z_axis_feature = Vector3Stamped()\n", + "robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", + "robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "\n", + "# define the world features\n", + "world_cylinder_center_feature = PointStamped()\n", + "world_cylinder_center_feature.header.frame_id = 'mycyl'\n", + "world_cylinder_center_feature.point = Point(0, 0, 0)\n", + "\n", + "world_cyl_z_axis_feature = Vector3Stamped()\n", + "world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", + "world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "\n", + "# define the constraints\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cylinder_center_feature,\n", + " robot_feature=robot_point_feature,\n", + " lower_limit=0.03,\n", + " upper_limit=0.03)\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='HeightFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cylinder_center_feature,\n", + " robot_feature=robot_point_feature,\n", + " lower_limit=-0.05,\n", + " upper_limit=0.05)\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='PointingFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cylinder_center_feature,\n", + " robot_feature=robot_pointing_feature)\n", + "gs.motion_goals.add_motion_goal(motion_goal_class='AlignFeatureFunction',\n", + " root_link='map',\n", + " tip_link=gripper_link,\n", + " world_feature=world_cyl_z_axis_feature,\n", + " robot_feature=robot_gripper_z_axis_feature)\n", + "gs.motion_goals.avoid_collision(min_distance=0.1, group1='obstacle')\n", + "gs.add_default_end_motion_conditions()\n", + "gs.execute()\n", + "\n", + "# EXERCISE:\n", + "# 1. Change Pose and size of the obstacle and see of the robot behaves." + ], "metadata": { "collapsed": false, "pycharm": { @@ -443,13 +607,13 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 22, "outputs": [ { "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999943677873273, 0.036489651127809095, -0.34861191507695366, 0.0, -1.0029954720697876, 0.48869320376572917, -0.9525215184807941, -1.3886278121725906, -2.334452544500386, -0.4558788900739724, 0.11051798980155325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424639103, 0.01537723122151193, 1.7420423753144298, -2.031187242709937, -1.4888851823925482, -0.10085496898309822, 0.2189845498620707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529550045, -0.0006253905029041468, -0.0006249999999543101]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011264425345431811, -0.10782259036973244, 0.24007968118780842, 0.0, 0.03470669267139551, 0.02650595782943679, -0.0749999999999986, 0.07499999999999744, -0.06632406743743047, -0.02018751168584966, -0.07499999999999926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999737, 0.074999999999998, 0.07499999999999606, -0.012777139263307391, -0.04774843784840461, -2.521049782918791e-13, -0.04371418946734415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059100089, -0.012507810058082935, -0.012499999999997631]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998925805181444, 0.0267630596697571, -0.3278931585753566, 0.0, -1.0000224659428705, 0.49049653362158574, -0.9619301047404497, -1.379593523733744, -2.3410342122554755, -0.4572018850649818, 0.10116315485063393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8674174204432588, 0.025183583202972704, 1.751384115653074, -2.0317932410205013, -1.493464451596551, -0.10085496898310194, 0.21493079853658995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024960475280989564, -0.0025039454747618935, -0.0018977869579240155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00010219471025693422, -0.1945318291610399, 0.4143751300319408, 0.0, 0.05946012253834131, 0.03606659711713095, -0.1881717251931117, 0.18068576877693243, -0.13163335510178822, -0.026459899820186556, -0.18709669901838655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.17671844041302845, 0.19612703962921552, 0.18683480677288364, -0.012119966211281892, -0.09158538408005376, -7.442134995683418e-14, -0.0810750265096152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742876550287904, -0.037571099437154934, -0.025455739159394107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998493688783553, 0.014583839048681577, -0.30283958239639125, 0.0, -0.9965298716413223, 0.4921355227464133, -0.9760200982822472, -1.36680060810211, -2.349875174327609, -0.45803239691922115, 0.08685564365031923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8549868214394558, 0.03999234575967991, 1.7648047375765166, -2.0314752473307713, -1.4992752177285162, -0.10085496898347529, 0.20999822574163152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005922552841754735, -0.005952405107086799, -0.003193360879578438]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.642327957848494e-05, -0.2435844124215104, 0.5010715235793077, 0.0, 0.06985188603096355, 0.03277978249655097, -0.2817998708359508, 0.25585831263267966, -0.17681924144267328, -0.016610237084787073, -0.2861502240062941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24861198007606106, 0.2961752511341441, 0.26841243846885016, 0.006359873794598259, -0.11621532263930487, -7.467089435582319e-12, -0.09865145589916838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853010627311555, -0.06896919264649809, -0.025911478433088442]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999809068351237, 0.0014335378704646243, -0.2761944917194697, 0.0, -0.9929074957979815, 0.49347927487126664, -0.9934337460668297, -1.3521735729677822, -2.3599662038298526, -0.457824273575296, 0.06884865106772532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8406534822932354, 0.058139594719090186, 1.7805125395519898, -2.029647170337682, -1.505313962569741, -0.10102857327294908, 0.20517189543805536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010643678979208298, -0.010710374037979753, -0.0038867220396985465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.06010542364428e-05, -0.26300602356433905, 0.5329018135384308, 0.0, 0.07244751686681615, 0.02687504249706601, -0.34827295569164807, 0.29254070268655696, -0.2018205900448637, 0.004162466878503277, -0.3601398516518781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2866667829244086, 0.3629449791882055, 0.31415603950946397, 0.0365615398617862, -0.12077489682449417, -0.0034720857894756426, -0.09652660607152291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09442252274907126, -0.09515937861785909, -0.013867223202402175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997690652879782, -0.011702002331867939, -0.24928874587665734, 0.0, -0.989246276057703, 0.49468681123771097, -1.0130856680342577, -1.3371594841759553, -2.370582763613108, -0.45628347991271506, 0.04830253205125776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8255901082630048, 0.07823517963514391, 1.7972253898468225, -2.026066250201851, -1.510779505665099, -0.10158468126685208, 0.20121590048948146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01641292307501113, -0.01652437680067441, -0.0038640671749981628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.000612651748077e-05, -0.26271080404665126, 0.5381149168562469, 0.0, 0.0732243948055711, 0.024150727328886127, -0.39303843934856075, 0.3002817758365387, -0.21233119566511, 0.030815873251618307, -0.41092238032935124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30126748060461117, 0.40191169832107443, 0.3342570058966499, 0.07161840271662138, -0.10931086190716179, -0.01112215987806014, -0.07911989897147827, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11538488191605661, -0.1162800552538931, 0.00045309729400767884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997283474068714, -0.02422006317593057, -0.22265032601038354, 0.0, -0.9854888087372059, 0.4959988791581555, -1.0342328168154162, -1.3226446897264197, -2.381293431749223, -0.45328812762035114, 0.026100264362257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8104723735088248, 0.09932762778084879, 1.8141873846479377, -2.020712517349157, -1.5151246688409317, -0.10266626822918933, 0.1986374242225254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023024727213398023, -0.023179169679737342, -0.003240362997743023]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.143576221380755e-05, -0.2503612168812526, 0.532768397325476, 0.0, 0.07514934640994225, 0.026241358408890046, -0.42294297562316907, 0.2902958889907117, -0.21421336272229458, 0.05990704584727803, -0.4440453537800151, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3023546950835998, 0.42184896291409757, 0.3392398960223039, 0.10707465705388071, -0.08690326351665349, -0.021631739246744976, -0.05156952533912154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13223608276773788, -0.13309585758125864, 0.0124740835451028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996865980793582, -0.03577252767613231, -0.19642956701394904, 0.0, -0.9815406337022685, 0.4976208882400833, -1.056396033113364, -1.3090816174212576, -2.3918853969091396, -0.4488199833015818, 0.0028533308283817463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7956428661300832, 0.12084202839815208, 1.831009251468635, -2.013679421858163, -1.5180326510469635, -0.10435473103804188, 0.19771778927297087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030315445650636933, -0.03050174984173772, -0.002180320475781348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.349865502641323e-05, -0.2310492900040347, 0.5244151799286898, 0.0, 0.07896350069874844, 0.032440181638556685, -0.44326432595895465, 0.271261446103241, -0.21183930319833585, 0.08936288637538736, -0.4649386706775051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.29659014757483493, 0.43028801234606573, 0.3364373364139436, 0.14066190981987875, -0.058159644120635956, -0.03376925617705119, -0.018392698991090466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1458143687447782, -0.14645160324000756, 0.02120085043923349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996442330373115, -0.04616995896947086, -0.17062210968011732, 0.0, -0.9773194217804638, 0.49955824438821456, -1.07920000541233, -1.2966864109287906, -2.402273896109887, -0.44290888219037877, -0.021025607826192387, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7812463341514053, 0.1424741886154075, 1.8475146134884695, -2.0051054194168927, -1.519369528373308, -0.10669360940779955, 0.1985627728675731, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03815425881537758, -0.03835359792954218, -0.0008307438256598999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.473008409361587e-05, -0.20794862586677107, 0.5161491466766346, 0.0, 0.08442423843609374, 0.03874712296262459, -0.45607944597932065, 0.24790412984934107, -0.20776998401494684, 0.11822202222406095, -0.47757877309148267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2879306395735574, 0.4326432043451085, 0.3301072403966928, 0.17148004882540202, -0.02673754652688798, -0.04677756739515352, 0.016899671892044166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1567762632948129, -0.15703696175608922, 0.026991533002428958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996040725524014, -0.055314282637708795, -0.14516865212623695, 0.0, -0.9727456966265481, 0.5009982242991801, -1.1019427606501693, -1.2858660976682268, -2.412379732756123, -0.4355618582535085, -0.04519470760038505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.767324519208989, 0.1640966399781355, 1.8636348863947714, -1.9951358832689376, -1.5191345486479253, -0.10970712890896582, 0.20115281807469315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04643623664364146, -0.046624149490955655, 0.0006903032687336236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.0320969820218e-05, -0.1828864733647586, 0.5090691510776074, 0.0, 0.0914745030783143, 0.028799598219310777, -0.4548551047567852, 0.216406265211273, -0.202116732924724, 0.14694047873740462, -0.48338199548385324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2784362988483254, 0.43244902725455975, 0.3224054581260395, 0.19939072295909918, 0.004699594507654364, -0.060270390023325224, 0.05180090414240096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656395565652775, -0.1654110312282694, 0.03042094188787047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995656080170937, -0.06315356264304221, -0.1199941524971841, 0.0, -0.9677747180971222, 0.5012873611605031, -1.1241369183257128, -1.2768487140584996, -2.422146155899913, -0.42689116470085037, -0.06940616153652623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.753877220547299, 0.18568829153512362, 1.8793483881907975, -1.983904792192392, -1.517416586876193, -0.11341034879709012, 0.20538601171981455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.055076911032641694, -0.05522545682713539, 0.002283205327204916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.692907061534153e-05, -0.15678560010666837, 0.5034899925810568, 0.0, 0.09941957058851723, 0.005782737226461488, -0.44388315351087204, 0.18034767219454395, -0.19532846287580571, 0.1734138710531634, -0.4842290787228237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26894597323380076, 0.43183303113976196, 0.3142700359205242, 0.22462182153091065, 0.03435923543464532, -0.07406439776248616, 0.08466387290242797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17281348778000474, -0.17202614672359462, 0.03185804116942584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995281641503582, -0.06966866451748287, -0.09502117513016206, 0.0, -0.9624003387814247, 0.500116271030617, -1.1455779972015496, -1.269654870766623, -2.431548357049536, -0.4170777138025503, -0.09350309815341745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7408879145352454, 0.2072870992331846, 1.8946485238828072, -1.9715281295513343, -1.5143590200051038, -0.11781302443341707, 0.21111215767328254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06400807277254862, -0.0640877832741035, 0.003868547243061622]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.488773347092766e-05, -0.13030203748881303, 0.4994595473404408, 0.0, 0.10748758631395008, -0.023421802597722835, -0.42882157751673766, 0.14387686583753134, -0.1880440229924549, 0.1962690179660015, -0.4819387323378244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2597861202410735, 0.43197615396121986, 0.3060027138401966, 0.24753325282115302, 0.06115133742178465, -0.08805351272653884, 0.11452291906935952, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17862323479813863, -0.17724652893936235, 0.03170683831713413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994913107957552, -0.07486978452803561, -0.07017347678394761, 0.0, -0.9566474214950237, 0.4974535442189808, -1.1662723818940892, -1.2641571779351852, -2.4405939888037196, -0.406312552106569, -0.11740332790066152, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7283317732074577, 0.22895947583181858, 1.9095291082817134, -1.9581026453043, -1.5101332014272366, -0.12292019476310419, 0.21815816901528123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07317453423226578, -0.07315595397288652, 0.005390281978841689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.370670920623152e-05, -0.1040224002110549, 0.4969539669242888, 0.0, 0.11505834572802173, -0.0532545362327229, -0.4138876938507903, 0.10995385662875751, -0.1809126350836694, 0.2153032339196265, -0.4780045949448813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25112282655575346, 0.43344753197267905, 0.29761168797812365, 0.2685096849406872, 0.08451637155734373, -0.10214340659374235, 0.1409202268399741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18332922919434316, -0.18136341397566022, 0.030434694715601344]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999454778588323, -0.0787932511944504, -0.04537638636620607, 0.0, -0.9505610930258132, 0.4934320662590068, -1.186347623731432, -1.2601449452411397, -2.4493170870303422, -0.394757933766431, -0.1410787049015602, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7161772892543037, 0.2507809650795023, 1.9239788941423313, -1.9437069608164215, -1.504919569294214, -0.1287315809038877, 0.22634589764778879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08253162230411247, -0.0823863518059898, 0.006815783357143117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.306441486449107e-05, -0.07846933332829581, 0.49594180835483076, 0.0, 0.12172656938421006, -0.08042955919948017, -0.401504836746858, 0.08024465388091005, -0.1744619645324521, 0.23109236680276088, -0.4735075400179733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24308967906307802, 0.4364297849536748, 0.28899571721235584, 0.2879136897575728, 0.10427264266044811, -0.11622772281567015, 0.1637545726501511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18714176143693387, -0.1846079566620657, 0.028510027566028558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999418401004553, -0.08149615548172884, -0.020556340685526725, 0.0, -0.9441966043754932, 0.4882542696256191, -1.205982998975845, -1.2573734263664906, -2.457768988172567, -0.3825317687870865, -0.16453548044579352, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7043869252787127, 0.27282430441754935, 1.9379806416962566, -1.9284037276933006, -1.4988950104392036, -0.13524091820649173, 0.2355038109280024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09204320725190959, -0.09174447697766148, 0.008132419216196427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.275516754014441e-05, -0.054058085745568765, 0.49640091361358685, 0.0, 0.12728977300639832, -0.10355593266775534, -0.39270750488825773, 0.05543037749298321, -0.16903802284449532, 0.24452329958688943, -0.4691355108846665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23580727951181774, 0.44086678676094054, 0.28003495107850934, 0.30606466246241537, 0.12049117710021234, -0.13018674605208075, 0.18315826560427226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19023169895594233, -0.1871625034334337, 0.026332717181066216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993820843096527, -0.08304951929192882, 0.004359732278485691, 0.0, -0.9376112471486444, 0.48212994460053066, -1.2253658774053524, -1.2555963712456997, -2.466009239976215, -0.36970820743538035, -0.18779826770983304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6929184906149766, 0.2951523694979101, 1.9515121768008965, -1.9122422732104816, -1.4922250618411221, -0.14243568346670238, 0.24547391998940069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10168012295086909, -0.10120299526375542, 0.009342140285319461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.263338980055095e-05, -0.031067276203999572, 0.4983214592802483, 0.0, 0.13170714453697593, -0.12248650050176803, -0.3876575685901491, 0.035541102415818024, -0.16480503607295707, 0.256471227034123, -0.4652557452807905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22936869327472115, 0.4465613016072156, 0.27063070209279794, 0.32322908965637986, 0.13339897196162795, -0.1438953052042129, 0.19940218122796569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19273831397919, -0.18917036572187879, 0.024194421382460668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999345787218696, -0.08353142067439112, 0.029445008079205522, 0.0, -0.9308586256850422, 0.47524219487126584, -1.244668886932497, -1.2545853835584841, -2.4740982777286065, -0.35632634252206563, -0.21089833098617597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6817271814852262, 0.31781441248440706, 1.9645481115374919, -1.8952614045937972, -1.4850596725245517, -0.15029731022491274, 0.2561152164303628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1114188792209438, -0.11074019912926589, 0.010455772812928171]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.259418191355444e-05, -0.009638027649246223, 0.5017055160143966, 0.0, 0.1350524292720445, -0.13775499458529636, -0.38606019054289176, 0.0202197537443123, -0.16178075504782638, 0.2676372982662945, -0.4620012655268586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22382618259500872, 0.4532408597299385, 0.26071869473190895, 0.33961737233368844, 0.14330778633140898, -0.1572325351642074, 0.2128259288192421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1947751254014942, -0.1907440773102094, 0.02227265055217421]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999310607111454, -0.08302938996233994, 0.05477321513919481, 0.0, -0.923991414112252, 0.46773330417573744, -1.2640402128919723, -1.2541392907820497, -2.482092733130743, -0.34240177658041, -0.23386587648540366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.670773099558801, 0.3407370161374479, 1.9768575873766403, -1.877623985725392, -1.4775504600158724, -0.1588547607254304, 0.2672813611253824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12124067996820441, -0.12033872601129876, 0.011496409058730188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.036021448414886e-05, 0.010040614241023614, 0.5065641411997858, 0.0, 0.13734423145580163, -0.1501778139105684, -0.38742651918950577, 0.00892185552869019, -0.15988910804273, 0.2784913188331126, -0.459350909984554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21908163852850127, 0.4584520730608169, 0.24618951678296816, 0.3527483773681055, 0.1501842501735842, -0.17114901001035326, 0.2233228939003923, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19643601494521215, -0.19197053764065736, 0.020812724916040352]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992804213393903, -0.08165764022566474, 0.08041948891832457, 0.0, -0.9170770735508773, 0.45970313497894394, -1.283601065526524, -1.254086813416885, -2.490043326135137, -0.3279381466345287, -0.2567255882798957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6600365308914813, 0.3634496468522489, 1.9875244374976193, -1.859987029478487, -1.4699013151136944, -0.1682919919079088, 0.2787573864212014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13113083499134293, -0.12998432922857048, 0.012517509370653924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0371544126995355e-05, 0.027434994733504064, 0.512925475582595, 0.0, 0.13828681122749548, -0.16060338393586998, -0.3912170526910351, 0.0010495473032916588, -0.15901186008788104, 0.28927259891762647, -0.4571942358898413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21473137334639292, 0.45425261429602043, 0.21333700241957979, 0.35273912493810033, 0.15298289804356144, -0.1887446236495683, 0.2295205059163795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1978031004627706, -0.19291206434543448, 0.020422006238474722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992545743305098, -0.0795159245272511, 0.10646074018709453, 0.0, -0.9101708458552307, 0.45121181250340664, -1.3034525260914236, -1.254290785018126, -2.4979930325894326, -0.31293292071170853, -0.2794942992600252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6494984100499197, 0.38552614818554565, 1.995875388686491, -1.842962512642937, -1.4623139445105957, -0.1786552829958554, 0.2903352443415077, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14107795986408048, -0.13966523005111176, 0.013562634334371814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.169401776087522e-05, 0.04283431396827265, 0.5208250253753994, 0.0, 0.13812455391293332, -0.16982644951074582, -0.39702921129799257, -0.004079432024817522, -0.15899412908591287, 0.30010451845640373, -0.45537421960259006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2107624168312294, 0.44153002666593455, 0.16701902377743577, 0.340490336711002, 0.15174741206197195, -0.20726582175893182, 0.23155715840612628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19894249745475076, -0.19361801645082535, 0.02090249927435781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992322813680996, -0.07670867382958221, 0.1329763188290542, 0.0, -0.9032348264408785, 0.44214690901905485, -1.323493252842749, -1.254855348925615, -2.5059698634130587, -0.2980366560047832, -0.3021668847623032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.639108140516877, 0.40669613074814553, 2.001651537455167, -1.8269615651281002, -1.4549582247240107, -0.18982475365300422, 0.30184944505258826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15107350323247298, -0.14937142693135094, 0.014685286317639549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4585924820379004e-05, 0.05614501395337779, 0.5303115728391934, 0.0, 0.13872038828704258, -0.18129806968703563, -0.40081453502650954, -0.0112912781497776, -0.15953661647252596, 0.2979252941385066, -0.45345171004555895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20780539066085135, 0.42339965125199724, 0.11552297537352055, 0.32001895029673716, 0.1471143957317011, -0.22338941314297658, 0.23028401422161135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991086736785002, -0.19412393760478375, 0.02245303966535469]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992130626790985, -0.07340491572848924, 0.15994061314862004, 0.0, -0.8962724789649682, 0.4324964947242017, -1.3438263294093244, -1.2556221171898703, -2.514013184406461, -0.2835484250369043, -0.3247341376957751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6288354085764698, 0.42682450613392386, 2.0049347917272113, -1.8121833806064307, -1.4479642065666531, -0.20157012497956966, 0.31318554591657793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16111059208723302, -0.15909494212136988, 0.01586729616881353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8437378001899175e-05, 0.06607516202185941, 0.5392858863913167, 0.0, 0.13924694951820532, -0.19300828589706293, -0.4066615313315085, -0.015335365285106062, -0.1608664198680467, 0.28976461935757797, -0.4513450586694377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20545463880814627, 0.40256750771556626, 0.06566508544089172, 0.2955636904333909, 0.1398803631471516, -0.23490742653130897, 0.22672201727979394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007417770952007, -0.19447030380037839, 0.023640197023479626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991966840970793, -0.06977970537894607, 0.18726994136662176, 0.0, -0.8892701283554084, 0.42224521192470754, -1.3645891160146304, -1.256394921929232, -2.5221558967836404, -0.2696095747926342, -0.3471787210740257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6186465895692452, 0.4458749683982276, 2.0060105202825427, -1.7986622006434627, -1.4414223202292344, -0.21361339867696572, 0.32427683434982835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1711835067910226, -0.1688296131239169, 0.017074813798622437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.275716403852687e-05, 0.07250420699086339, 0.5465865643600344, 0.0, 0.14004701219119592, -0.20502565598988312, -0.4152557321061212, -0.015456094787236955, -0.16285424754359026, 0.27877700488540236, -0.44889166756501203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20377638014449317, 0.3810092452860746, 0.021514571106627384, 0.2704235992593596, 0.13083772674837285, -0.240865473947921, 0.22182576866500847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2014582940757915, -0.19469342005094056, 0.024150352596178155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991829704491304, -0.06595164889716351, 0.21486738391251042, 0.0, -0.8821869876742153, 0.4113580694793555, -1.3858915903241376, -1.2570265264617904, -2.5304170095375724, -0.25627574742973624, -0.36947639220324785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6085015888525278, 0.46387136236181853, 2.005249868742743, -1.7863216674809272, -1.4353896885281745, -0.22567821158055126, 0.3350945463214575, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18128738829199612, -0.17857079626743272, 0.01827446757476247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.742729589774109e-05, 0.07656112963565102, 0.5519488509177736, 0.0, 0.14166281362386218, -0.21774284890704082, -0.4260494861901423, -0.012632090651166567, -0.165222255078642, 0.26667654725795925, -0.44595342258444315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.202900014334348, 0.3599278792718181, -0.015213030795990373, 0.24681066325070852, 0.12065263402119997, -0.24129625807171087, 0.21635423943258303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20207763001947027, -0.19482366287031647, 0.02399307552280062]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999171936687081, -0.06200489325961712, 0.24262760650810797, 0.0, -0.8749077381951124, 0.3997031550632148, -1.4076775335683605, -1.25758594128843, -2.5387972096710043, -0.24417857712991742, -0.391590489618162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.598342974240442, 0.48087099638066244, 2.003027721377976, -1.7750238484235246, -1.4298975236623708, -0.2375200347171883, 0.34563704259039363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19141825256944675, -0.1883148717070868, 0.019458676694438536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2067524098460056e-05, 0.07893511275092788, 0.555204451911951, 0.0, 0.1455849895820586, -0.23309828832281398, -0.43571886488445577, -0.011188296532793842, -0.16760400266863723, 0.24194340599637676, -0.4422819482982835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20317229224171607, 0.33999268037687863, -0.044442947295344856, 0.22595638114805344, 0.10984329731607509, -0.23683646273274064, 0.2108499253787216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20261728554901254, -0.19488150879308166, 0.023684182393521297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991632893154915, -0.057955381131714064, 0.27043383512585756, 0.0, -0.867367996397315, 0.3872512299726996, -1.429980287645491, -1.2580481042981049, -2.5472886953391627, -0.23334210046732623, -0.4134925815781258, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.588134021490493, 0.49694044611680416, 1.9996814247534958, -1.7646048459974841, -1.4249597077185387, -0.24894317319441417, 0.3559190350014655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20157257289412323, -0.1980592924005522, 0.020596362724224826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7294743179113573e-05, 0.0809902425580611, 0.5561245723549918, 0.0, 0.1507948359559485, -0.24903850181030343, -0.4460550815426122, -0.009243260193495056, -0.16982971336316888, 0.21672953325182365, -0.43804183919927536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2041790549989801, 0.321388994722834, -0.06692593248960249, 0.20838004852081085, 0.09875631887663844, -0.2284627695445175, 0.2056398482214377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20308640649352938, -0.1948884138693078, 0.022753720595725828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991570323469426, -0.053798476309639034, 0.29815606018178514, 0.0, -0.8595176351390179, 0.37399993210151256, -1.4528474884205413, -1.2583752085214903, -2.5558745158296525, -0.22360631004274767, -0.43515990202702315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5778455511123288, 0.5121486757206983, 1.9954893594833063, -1.7549029483419794, -1.4205778231805546, -0.2598038304006368, 0.36596427551383576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21174720324770274, -0.20780235697116883, 0.0216640683540259]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2513937097453594e-05, 0.08313809644150058, 0.5544445011185514, 0.0, 0.1570072251659406, -0.2650259574237416, -0.4573440155010057, -0.006542084467708544, -0.17171640980979766, 0.19471580849157094, -0.4333464089779465, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2057694075632873, 0.30416459207788243, -0.08384130540378956, 0.19403795311009459, 0.08763769075968289, -0.2172131441244532, 0.2009048102474056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2034926070715904, -0.1948612914123327, 0.021354112596021484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991532140068302, -0.0495261124340122, 0.32565129367259676, 0.0, -0.8513100937361373, 0.3599504123409985, -1.4763174109024948, -1.2585407040120304, -2.564530809104911, -0.21478922970344114, -0.4565740300787786, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5674527919006813, 0.5265628008053821, 1.9906665842974844, -1.7457735158233119, -1.4167452974479746, -0.27000673079348886, 0.375800257381472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22193937709696854, -0.21754296453507113, 0.02265058158026335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.636680224744883e-06, 0.08544727751253674, 0.5499046698162328, 0.0, 0.16415082805761122, -0.28099039521028146, -0.4693984496390691, -0.0033099098108013477, -0.17312586550517142, 0.17634160678613053, -0.42828256103510925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20785518423294885, 0.288282501693675, -0.09645550371643657, 0.1825886503733485, 0.07665051465159964, -0.2040580078570406, 0.1967196373527248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20384347698531594, -0.19481215127804613, 0.019730264524749012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991519586375045, -0.04514634070765176, 0.3514006435865091, 0.0, -0.8426592115557481, 0.3450548782274425, -1.5003302905499343, -1.2586417207195475, -2.5732270149977454, -0.2073179997627597, -0.4777153494071629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5569252279431307, 0.5402475213617974, 1.9853689104517105, -1.737095556272282, -1.41345007180058, -0.279497516553597, 0.3854550071751034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23214684001108826, -0.2272802767874083, 0.023568252139719102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.510738651493572e-06, 0.08759543452720886, 0.5149869982782466, 0.0, 0.1730176436077857, -0.2979106822711192, -0.4802575929487916, -0.002020334150341435, -0.17392411785668363, 0.1494245988136289, -0.42282638656768645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.210551279151014, 0.27369441112830695, -0.10595347691547766, 0.17355919102059403, 0.06590451294789099, -0.18981571520216345, 0.1930949958726276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2041492582823945, -0.19474624504674332, 0.018353411189115012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991531433682683, -0.040652203443944004, 0.3734640331474745, 0.0, -0.8335255223283966, 0.32932626206854554, -1.5248929540006286, -1.2586880015078965, -2.581930858881691, -0.20105999855085718, -0.498573411877532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5462492593169215, 0.5532608933159537, 1.9797051056484585, -1.7287711810021689, -1.4106774840942202, -0.28825605805658827, 0.3949547180241143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24236763948430182, -0.23701378075307267, 0.02441571502677804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.369461527810091e-06, 0.08988274527415509, 0.4412677912193081, 0.0, 0.18267378454702882, -0.3145723231779398, -0.4912532690138861, -0.0009256157669812709, -0.1740768776789138, 0.12516002423805006, -0.4171612494073814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2135193725241847, 0.26026743908312594, -0.11327609606504076, 0.16648750540226392, 0.055451754127197606, -0.17517083005982564, 0.18999421698021818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20441598946427111, -0.19467007931328703, 0.016949257741178766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991568038104338, -0.03604378387140768, 0.39102189623055855, 0.0, -0.8238822059508757, 0.3127923029678555, -1.5500276807358593, -1.2586642221456124, -2.5906074666517895, -0.19576593852907737, -0.5191436384328104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5354166890823266, 0.5656565402075744, 1.9737468833513334, -1.7207250504230756, -1.4084109998532808, -0.29628753156221943, 0.4043231753796419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25260010035560265, -0.24674318402336615, 0.02519559589684357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.320884331225334e-06, 0.09216839145072646, 0.35115726166168076, 0.0, 0.1928663275504183, -0.33067918201380153, -0.502694534704615, 0.0004755872456812329, -0.17353215540196934, 0.10588120043559658, -0.4114045311055688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21665140469189534, 0.2479129378324135, -0.11916444594250003, 0.16092261158186555, 0.045329684818788706, -0.1606294701126236, 0.1873691471105526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20464921742601713, -0.1945880654058694, 0.015597617401310607]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991629762965907, -0.0313301511200436, 0.4042356347770096, 0.0, -0.8137036635729823, 0.2954815505203647, -1.5757550714762791, -1.2585520824471372, -2.599220977602953, -0.19121333064802526, -0.539425331861611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5244213501439687, 0.5774842648355991, 1.9675384844805521, -1.7129005387961165, -1.4066329340866166, -0.30361497808066934, 0.41358166513866096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26284282183271745, -0.25646830713754026, 0.025915311458413366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2344972314041837e-05, 0.0942726550272815, 0.26427477092902024, 0.0, 0.2035708475578688, -0.3462150489498161, -0.5145478148083986, 0.0022427939695019595, -0.17227021902327067, 0.09105215762104218, -0.4056338685760125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21990677876715797, 0.2365544925604943, -0.12416797741562423, 0.15649023253918076, 0.03556131533328266, -0.14654893036899808, 0.18516979518038082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20485442954229588, -0.19450246228348259, 0.014394311231395939]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991716731154052, -0.026525558340783968, 0.41380240247527866, 0.0, -0.8029623156404427, 0.2774207428798835, -1.6020897913705852, -1.2583369909018103, -2.607736646785377, -0.1872381734880999, -0.5594203751179667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5132583434356306, 0.5887901948276059, 1.9611049586567002, -1.7052552910862158, -1.405324980846817, -0.3102732739851018, 0.42274918911505466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.273094660675004, -0.2661890497572536, 0.026584619763713735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.739363762884511e-05, 0.09609185558519262, 0.19133535396538198, 0.0, 0.21482695865079082, -0.36121615280962405, -0.5266943978861184, 0.0043018309065368885, -0.17031338364847823, 0.0795031431985073, -0.3999008651271129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2232601341667642, 0.22611859984013546, -0.12867051647703923, 0.15290495419801506, 0.026159064795992434, -0.13316591808864933, 0.1833504795278738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20503677684573077, -0.19441485239426728, 0.013386166106007354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991828863620853, -0.021645009132675964, 0.4205907108636889, 0.0, -0.791628159543138, 0.258635880996209, -1.6290408846014002, -1.2580090366093195, -2.6161224405769827, -0.18372994186970218, -0.5791323817827055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5019239113415281, 0.5996168454478135, 1.9544588074527132, -1.6977572570550705, -1.404468556059473, -0.31630444289788495, 0.4318428320375456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28335470022604436, -0.27590532282194086, 0.027213481376127325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.242649336002097e-05, 0.09761098416216009, 0.13576616776820377, 0.0, 0.22668312194609339, -0.3756972376734905, -0.5390218646163004, 0.006559085849813688, -0.16771587583211528, 0.07016463236795442, -0.39424013329477636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22668864188205057, 0.21653301240415293, -0.1329230240797412, 0.1499606806229051, 0.01712849574688053, -0.12062337825566287, 0.18187285844981813, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2052007910208073, -0.19432546129374453, 0.01257723224827178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19991965916541216, -0.016701056200382057, 0.4254225939679053, 0.0, -0.7796690759648334, 0.23915418238325292, -1.6566134421122871, -1.25756206611305, -2.624349893978199, -0.18061804771119994, -0.5985661845110753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4904153737741563, 0.6100031613137556, 1.947604948074933, -1.6903814793287308, -1.404045026353251, -0.32175417684037083, 0.44087815263000113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29362221457316656, -0.285617048995376, 0.027810817361409907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7410584072310096e-05, 0.0988790586458781, 0.09663766208432883, 0.0, 0.23918167156609368, -0.3896339722591212, -0.5514511502177396, 0.008939409925390817, -0.16454906802433, 0.062237883170044736, -0.3886760545673955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23017075134743417, 0.20772631731884392, -0.1370771875556067, 0.1475155545267934, 0.008470594124443212, -0.10899467884971732, 0.18070641184911032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20535028694244367, -0.1942345234687028, 0.011946719705651644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992127501286358, -0.011702208613917686, 0.4289739422232274, 0.0, -0.7670512784878643, 0.21900591760066124, -1.684810411942989, -1.2569922982686135, -2.632394354661889, -0.17785914352096863, -0.617727581249097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4787309925001368, 0.6199845755451108, 1.9405442054172986, -1.683107685070384, -1.4040358776467259, -0.3266693798282774, 0.44986952770788047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30389663225850994, -0.2953241545968568, 0.028383949432997407]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2316949028507026e-05, 0.09997695172928742, 0.0710269651064412, 0.0, 0.25235594953938256, -0.4029652956518339, -0.563939396614037, 0.011395356888729244, -0.1608892136737929, 0.0551780838046262, -0.3832279347604332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23368762548039063, 0.19962828462710325, -0.14121485315268698, 0.14547588516693374, 0.0001829741305017802, -0.09830405975813139, 0.17982750155758723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548835370686713, -0.1941421120296164, 0.01146264143174999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992313101318812, -0.006652692565644477, 0.4317498358492036, 0.0, -0.7537397487466786, 0.19822584140021687, -1.7136341431009776, -1.2562970072993924, -2.6402348296879428, -0.17542754335129496, -0.6366232662843543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4668697844299083, 0.6295930893252552, 1.933275611045951, -1.6759185806028578, -1.404422861464175, -0.33109652878027634, 0.458830413805529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31417750276953854, -0.30502657383305176, 0.02893846063414057]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.712000649054735e-05, 0.10099032096546418, 0.05551787251952504, 0.0, 0.2662305948237139, -0.4156015240088871, -0.5764746231597715, 0.01390581938442012, -0.15680950052107492, 0.04863200339347323, -0.37791370070514646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2372241614045679, 0.19217027560288796, -0.1453718874269521, 0.14378208935052617, -0.00773967634898096, -0.08854297903997929, 0.1792177219529715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056174102205722, -0.1940483847238996, 0.011090224022863238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999252208256924, -0.0015530650799208427, 0.43409950235886813, 0.0, -0.7396986511357861, 0.17685419495564528, -1.7430875667126164, -1.255473436518051, -2.6478536261191183, -0.1733086480035227, -0.6552608821508061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4548313208956247, 0.638857379542875, 1.9257978066239203, -1.6687987189318956, -1.4051881357602882, -0.3350806539796887, 0.46777352030281205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32446446710359783, -0.3147242513390845, 0.02947827750528296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.179625008542345e-05, 0.10199254971447269, 0.04699333019329052, 0.0, 0.2808219522178488, -0.4274329288914317, -0.5890684722327764, 0.01647141562682765, -0.1523759286235147, 0.04237790695544556, -0.37275231732903635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24076927068567405, 0.1852858043523969, -0.14955608844061632, 0.14239723341924326, -0.015305485922267837, -0.07968250398824721, 0.17886212994566003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20573928668118585, -0.19395355012065485, 0.010796337422847802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19992753700588597, 0.003598798511559146, 0.43624739217648045, 0.0, -0.724891741690841, 0.15493734916362287, -1.77317503344434, -1.2545179696671447, -2.65523591858819, -0.17149465918198545, -0.6736491402359694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4426155419967504, 0.6478029342278301, 1.9181098129680592, -1.6617337984280063, -1.4063144055645729, -0.33866476616335506, 0.4767109036375887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3347572324029258, -0.3244171475426142, 0.030005856709231834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6323603871767203e-05, 0.10303727182959976, 0.04295779635224643, 0.0, 0.2961381888989033, -0.43833691584044815, -0.6017493346344696, 0.01910933701812804, -0.1476458493814388, 0.036279776430745134, -0.36776516170326684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24431557797748968, 0.17891109369910227, -0.15375987311722422, 0.14129841007778507, -0.0225253960856932, -0.07168224367332676, 0.17874766669553313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20585530598655982, -0.19385792407059352, 0.010551584078977523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999300727479941, 0.008804094513933344, 0.43832674680155004, 0.0, -0.7092734812854777, 0.1325250230096199, -1.8038896617668416, -1.2534467156304505, -2.662369107290451, -0.170136386354041, -0.6917974923403458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4302206397529396, 0.656452392197265, 1.91021119496771, -1.654710318457212, -1.4077850093685291, -0.3418894014845274, 0.48565401651967277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34505557801701003, -0.3341052161568823, 0.03052500721608979]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.071484216269138e-05, 0.10410592004748395, 0.041587092501391226, 0.0, 0.3123652081072662, -0.4482465230800592, -0.6142925664500328, 0.02142508073388495, -0.14266377404522404, 0.02716545655888939, -0.3629670420875271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.247898044876214, 0.1729891593886999, -0.15797236000698112, 0.1404695994158832, -0.029412076079125125, -0.06449270642344677, 0.17886225764168148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596691228168415, -0.1937613722853621, 0.01038301013715913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993281607735924, 0.014069201764168223, 0.440554074676966, 0.0, -0.6928109809552064, 0.10967925831495132, -1.8352409943354022, -1.2522513346602826, -2.6692418402322686, -0.16918147937709843, -0.7097178193704274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4176478262465135, 0.6648252180781782, 1.9021025352490581, -1.6477151275537387, -1.4095841982762256, -0.3447930230988332, 0.4946136536266191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35535929515115294, -0.3437884526041532, 0.031034178355589064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.4866587303167144e-05, 0.10530214500469758, 0.044546557508319394, 0.0, 0.329250006605426, -0.4569152938933719, -0.627026651371214, 0.023907619403360444, -0.1374546588363505, 0.0190981395388514, -0.3584065406016334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2514562701285214, 0.1674565176182633, -0.16217319437304076, 0.13990381806946717, -0.035983778153928975, -0.05807243228611571, 0.17919274213892625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20607434268285799, -0.19366472894541778, 0.010183422789985429]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993575682648196, 0.019400616468993246, 0.44289768829019843, 0.0, -0.6754744605295335, 0.08646953830834081, -1.8672451722132992, -1.2509139006384626, -2.6758434597702183, -0.1685470814504019, -0.7274240181573949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4048984576701506, 0.6729382830732726, 1.8937852932352317, -1.640735717797071, -1.4116971315210167, -0.3474117904117522, 0.5035999569603018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3656681770246601, -0.3534668961450138, 0.031531318896992885]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.8814982454298406e-05, 0.10662829409650044, 0.04687227226464876, 0.0, 0.3467304085134582, -0.46419440013220997, -0.6400835575579383, 0.02674868043639765, -0.1320323907589963, 0.012687958533930593, -0.3541239757393488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2549873715272559, 0.16226129990188878, -0.16634484027652924, 0.1395881951333539, -0.04225866489582044, -0.05237534625838001, 0.17972606667365373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617763747014317, -0.1935688708172126, 0.009942810828076472]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19993888393816484, 0.0248040893394555, 0.44529375356535134, 0.0, -0.657234770570855, 0.06297094490393922, -1.8999212050323753, -1.249412458692867, -2.682164551083141, -0.16816676905990524, -0.7449317767870256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3919731590322595, 0.6808061382983573, 1.8852615233704535, -1.6337601318767279, -1.4141099807966149, -0.3497796362304216, 0.5126224001403346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37598173324735323, -0.36314035844652015, 0.03201440817113183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.254223365770543e-05, 0.10806945740924509, 0.04792130550305777, 0.0, 0.3647937991735709, -0.4699718680880319, -0.6535206563815221, 0.03002883891191481, -0.12642182625846027, 0.007606247809932947, -0.35015517259261514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2585059727578234, 0.15735710450169496, -0.17047539729556585, 0.1395117184068595, -0.048256985511962884, -0.04735691637338743, 0.18044886360065446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20627112445386322, -0.19346924603012725, 0.00966178548277895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994218755304446, 0.03028111445937137, 0.4476983151298864, 0.0, -0.638051332776127, 0.03926257745153229, -1.9332743876008847, -1.2477508441344103, -2.688197452370262, -0.16810928445998144, -0.7622579496811501, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3788697670593844, 0.6884412863522363, 1.8765336079476393, -1.6267770578307548, -1.4168099483184164, -0.35192815298540625, 0.521689746529341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38629983835555937, -0.3728089685767702, 0.03248476983167084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.607229759236975e-05, 0.10954050239831736, 0.04809123129070107, 0.0, 0.3836687558945604, -0.4741673490481384, -0.6670636513701855, 0.03323229116913221, -0.12065802574241588, 0.001149691998475956, -0.3465234578824916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2620678394575032, 0.15270296107757883, -0.17455830845628348, 0.13966148091946143, -0.053999350436031546, -0.04297033509969325, 0.1813469277801277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063621021641231, -0.19337220260500151, 0.009407233210780217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994565462695438, 0.035833492498871876, 0.4500905981744083, 0.0, -0.6178842585120434, 0.015431057167064749, -1.9673061459951764, -1.2459416831053933, -2.6939362728567957, -0.16848615907127737, -0.7794214344100959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3655861790610817, 0.695854000809875, 1.8676041606193066, -1.6197754582617239, -1.4197854587358523, -0.35388704398114024, 0.5308099776510703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3966223687317779, -0.382472854002744, 0.03294257592190131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.934147819820369e-05, 0.11104756079001019, 0.04784566089043712, 0.0, 0.40334148528167124, -0.47663040568935083, -0.6806351678858344, 0.03618322058034058, -0.11477640973067882, -0.007537492225918648, -0.3432696945789163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26567175996605197, 0.1482542891527731, -0.1785889465666572, 0.14003199138061714, -0.05951020834871641, -0.03917781991467974, 0.18240462243458555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064506075243705, -0.1932777085194761, 0.009156121804609322]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994927114146885, 0.04146423281254037, 0.4524652423308594, 0.0, -0.5967002839762974, -0.008428315810264247, -2.002019540532723, -1.2439956941687156, -2.6993758339653144, -0.16940299491767172, -0.7964438610998594, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3521212162123777, 0.7030525069188116, 1.8584760797939717, -1.6127446918799009, -1.4230261952653138, -0.35568434019006, 0.539990275195647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4069491874556222, -0.3921321596665384, 0.0333861414163522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.233029028954226e-05, 0.1126148062733699, 0.04749288312902246, 0.0, 0.42367949071492217, -0.4771874595465799, -0.694267890750924, 0.038919778733553526, -0.10879122217037608, -0.018336716927886926, -0.3404485337952699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2692992569740784, 0.14397012217873117, -0.18256161650669792, 0.14061532763645895, -0.0648147305892294, -0.035945924178395046, 0.1836059508915353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20653637447688533, -0.19318611327588817, 0.008871309889017753]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995302292547737, 0.04717719163981723, 0.45482467173455715, 0.0, -0.5744743481247945, -0.03221191560342329, -2.0374207516577627, -1.2419173313528997, -2.704510349690118, -0.17094461988618306, -0.8133500607854194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.338474363592058, 0.710043323425046, 1.849152611281147, -1.6056747744240032, -1.4265230589240911, -0.3573465118464638, 0.5492370613052514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4172801236089696, -0.40178706148223914, 0.03381250417578785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.50356801704552e-05, 0.1142591765455371, 0.0471885880739552, 0.0, 0.4445187170300572, -0.47567199586318076, -0.7080242225007946, 0.041567256316315505, -0.10269031449607864, -0.030832499370226814, -0.3381239937112001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27293705240639565, 0.13981633012468742, -0.18646937025649496, 0.14139834911795557, -0.06993727317554597, -0.03324343312807645, 0.18493572219208787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2066187230669484, -0.1930980363140145, 0.008527255188713103]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19995689562569696, 0.0529764013584553, 0.4571740315963459, 0.0, -0.5511892882837658, -0.05580878834381451, -2.0735186015691505, -1.2397038596385224, -2.70933229877117, -0.17317392474171134, -0.8301683189783522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3246456650861915, 0.716831383794669, 1.8396373038523934, -1.5985564082349324, -1.4302681534635762, -0.3588985346995499, 0.558555999158406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42761497664776876, -0.4114377704488579, 0.03421828106622663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.745400439178555e-05, 0.1159841943727615, 0.046987197235774894, 0.0, 0.4657011968205729, -0.4719374548078243, -0.7219569982277539, 0.04426943428754573, -0.09643898162103368, -0.044586097110565416, -0.33636516385865606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2765739701173271, 0.1357612073924629, -0.19030614857507142, 0.1423673237814152, -0.07490189078970134, -0.03104045706172176, 0.18637875706309256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20669706077598285, -0.1930141793323752, 0.008115537808775676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996089890845417, 0.05888883692989693, 0.4595184800629568, 0.0, -0.526901883015525, -0.07893182781676603, -2.110092321432455, -1.2373198520905968, -2.7134998146319544, -0.17613304333447521, -0.8465907922731724, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.310653127481421, 0.7234196128227636, 1.8299352386537378, -1.5913806634700793, -1.4342550396317781, -0.36036587707562534, 0.5679520932180644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4379532912986751, -0.421084771078369, 0.03457703990224904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.006565514422405e-05, 0.11824871142883255, 0.046888969332218, 0.0, 0.485748105364817, -0.4624607894590302, -0.7314743972660956, 0.047680150958511774, -0.08335031721568739, -0.05918237185527777, -0.32844946589640434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27985075209540916, 0.13176458056189136, -0.19404130397311342, 0.14351489529706157, -0.07973772336403934, -0.029346847521508145, 0.18792188119316772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20676629301812666, -0.1929400125902228, 0.007175176720448172]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999650598841945, 0.06497439219545284, 0.4618620525147836, 0.0, -0.5017975861345425, -0.10103100307083646, -2.1465184654326808, -1.234674623861658, -2.7161027121378716, -0.17985000619381897, -0.8617340947443358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2965438552155464, 0.7298096042905275, 1.8200545056691093, -1.5841400898195637, -1.4384785532693973, -0.36177571462075087, 0.5774299590274339, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4482940391134155, -0.43072916432052577, 0.034829289387686035]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.3219514806687e-05, 0.12171110531111831, 0.046871449036536506, 0.0, 0.5020859376196491, -0.4419835050814085, -0.7285228800045104, 0.05290456457877694, -0.052057950118340725, -0.07433925718687479, -0.30286604942326895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28218544531749395, 0.1277998293552787, -0.1976146596925673, 0.14481147301031166, -0.0844702727523845, -0.028196750902510892, 0.18955731618739077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2068149562948069, -0.19288786484313503, 0.0050449897087399016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19996936354723793, 0.07126622309335441, 0.4642074181845505, 0.0, -0.4760551418039262, -0.12167984801784872, -2.1822476332991476, -1.2316783456747256, -2.716361757472941, -0.18434645519981743, -0.8748556332219445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.282349992373356, 0.7360038559743707, 1.8100036805633035, -1.5768306365002767, -1.4429338617451328, -0.36315222153362153, 0.5869939497017014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4586358746761437, -0.44037239127138705, 0.0349420811878866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.607326086861515e-05, 0.12583661795803136, 0.046907313395338227, 0.0, 0.5148488866123256, -0.4129768989402451, -0.7145833573293369, 0.05992556373864878, -0.005180906701383242, -0.08992898011996939, -0.26243076955217426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28387725684381143, 0.12388503367686289, -0.20101650211611713, 0.14618906638573945, -0.08910616951470839, -0.027530138257413045, 0.1912798134853488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683671125456485, -0.19286453901722592, 0.0022558360040113136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997379143001764, 0.07776899639084262, 0.46655600538470354, 0.0, -0.4498147428041323, -0.1406513385680828, -2.2169279753438587, -1.228267958933324, -2.7138063538676853, -0.18962681856315414, -0.8855349017778712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2680810973387941, 0.7420045623063706, 1.7997893976568422, -1.5694488605442787, -1.4476169525708655, -0.36451601216623863, 0.5966479672555021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46897740788126946, -0.4500159440950995, 0.03491072156614704]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.855765559401911e-05, 0.13005546594976414, 0.046971744003060124, 0.0, 0.5248079799958779, -0.3794298110046814, -0.6936068408942236, 0.0682077348280285, 0.05110807210511245, -0.1056072672667343, -0.21358537111853512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2853779006912345, 0.12001412663999692, -0.20428565812922733, 0.1476355191199587, -0.09366181651465605, -0.02727581265234201, 0.19308035107601457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20683066410251555, -0.1928710564742491, -0.00062719243479135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19997859488869993, 0.08449411927742755, 0.46890829058041245, 0.0, -0.423228987139392, -0.15802175540469443, -2.249987385598714, -1.2241457216270608, -2.7084187345750443, -0.1957180323196668, -0.893782711064083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.253748187745712, 0.7478123549353348, 1.7894169406863398, -1.5619896511407834, -1.4525252844554515, -0.36588689044702444, 0.6063954373352898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4793171384805335, -0.4596614333567058, 0.03472380389854716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.606917364578337e-05, 0.1345024577316986, 0.047045703914178304, 0.0, 0.5317151132948059, -0.3474083367322327, -0.6611882050971059, 0.08244474612526588, 0.10775238585281527, -0.12182427513025361, -0.1649561857242356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.286658191861644, 0.11615585257928451, -0.20744913941004678, 0.14918418806990458, -0.09816663769171755, -0.027417565615715768, 0.19494940159575466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2067946119852808, -0.19290978523212576, -0.0037383533519975355]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998346517918872, 0.09141406724463508, 0.4712641065329575, 0.0, -0.3963772718905486, -0.17371562945071847, -2.2814760175244753, -1.219360925440738, -2.7002327508410016, -0.20256769550311668, -0.8997134077907735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.239329617790521, 0.7534266524824335, 1.7788887401772873, -1.5544474328996274, -1.4576573351045903, -0.3672799495537857, 0.6162389829320788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48965387642560615, -0.4693104482638417, 0.03440900117209651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.740580977579372e-05, 0.13839895934415067, 0.047116319050902106, 0.0, 0.5370343049768674, -0.31387748092048084, -0.629772638515227, 0.0956959237264568, 0.16371967468085852, -0.13699326366899722, -0.11861393453380784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28837139910381737, 0.11228595094197273, -0.21056401018104937, 0.15084436482312133, -0.1026410129827759, -0.027861182135225065, 0.19687091193577935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20673475890145315, -0.19298029814271903, -0.006296054529012879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19998837262983027, 0.0984876371474542, 0.4736228512128817, 0.0, -0.36931688053387773, -0.18773598357623295, -2.3116213955634004, -1.2140251347964188, -2.6893801310269607, -0.21009366952295444, -0.903551021511901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2247864723311725, 0.7588446208607488, 1.7682046484249256, -1.5468142979099502, -1.463013101024749, -0.3687074540384244, 0.6261802995106079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49998676525617464, -0.47896382469304655, 0.03400803337286887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.814901283098824e-05, 0.14147139805638256, 0.04717489359848419, 0.0, 0.5412078271334178, -0.2804070825102892, -0.6029075607785047, 0.1067158128863861, 0.21705239628081968, -0.15051948039675508, -0.07675227442255034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2908629091869693, 0.10835936756630725, -0.21368183504723234, 0.1526626997935423, -0.1071153184031709, -0.028550089692774814, 0.1988263315705836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20665777661136933, -0.19306752858409676, -0.008019355984552914]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999333034850686, 0.105673669795564, 0.4759836606629676, 0.0, -0.3420989319308359, -0.2001784404608327, -2.3406676079286513, -1.2082366255708006, -2.676068847338364, -0.2181991233110978, -0.9055950446480462, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.210074347685301, 0.7640609965663732, 1.7573630303574068, -1.53907990480734, -1.4685941695923914, -0.3701801278166298, 0.636220089338161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5103153663581976, -0.4886219727508629, 0.03356302377694085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.915437353183409e-05, 0.14372065296219605, 0.047216189001717875, 0.0, 0.5443589720608369, -0.2488491376919947, -0.5809242473050138, 0.11577018451236276, 0.2662256737719409, -0.16210907576286726, -0.04088046272290302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2942424929174305, 0.10432751411248795, -0.2168323613503749, 0.1546878620522016, -0.11162137135285063, -0.02945347556410772, 0.2007957965510602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20657202204046005, -0.19316296115632664, -0.00890019191856041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999985724046607, 0.11296025548712392, 0.47834557029358193, 0.0, -0.314801405808413, -0.21118625359244553, -2.3685314160903346, -1.2018226217381398, -2.660668603774185, -0.2268306392523497, -0.906272283081831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.195169438262761, 0.7690689721673792, 1.746363206779349, -1.531232376173149, -1.474403504951756, -0.3717100360535933, 0.6463583943527268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5206393882958547, -0.49828517094116875, 0.03308743223331075]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010484112307689969, 0.1457317138311984, 0.04723819261228707, 0.0, 0.5459505224484582, -0.22015626263225668, -0.5572761632336668, 0.12828007665321645, 0.3080048712835719, -0.17263031882503777, -0.013544768675696726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.298098188450805, 0.10015951202012112, -0.21999647156115473, 0.15695057268381932, -0.11618670718729492, -0.030598164739270173, 0.20276610029131695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20648043875314065, -0.19326396380611774, -0.00951183087260194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000386188984348, 0.1203205677287292, 0.48070759131574803, 0.0, -0.287474989770132, -0.22085635045821775, -2.3954222793204267, -1.1948892232481507, -2.643436904418872, -0.23587381765469737, -0.9059314193362062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.180038166023946, 0.7738608510681475, 1.7352056038860497, -1.5232611904860027, -1.4804446693925655, -0.3733069528951633, 0.6565944608268954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5309588079582727, -0.5079534101611066, 0.032609806416965675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010578970365539403, 0.14720624483210576, 0.04724042044332186, 0.0, 0.5465283207656204, -0.19340193731544422, -0.5378172646018428, 0.1386679697997807, 0.34463398710626403, -0.18086356804695347, 0.006817274912495987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30262544477629516, 0.09583757801536633, -0.22315205786598608, 0.15942371374292477, -0.12082328881618842, -0.031938336831399336, 0.20472132948337274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2063883932483591, -0.1933647843987567, -0.009552516326901475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20000916494083057, 0.12770763567726107, 0.4830687392069244, 0.0, -0.26019308643958283, -0.22931048175714647, -2.4215463400455506, -1.1875815492128718, -2.6246036628231084, -0.24515225513938024, -0.9048815573555332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1647218529199097, 0.7783765005428815, 1.723859375416625, -1.5150999797468971, -1.486737404398827, -0.37496984157688623, 0.6669070107583583, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5412740650655505, -0.5176261007453624, 0.03217890689697536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010606101974169083, 0.1477413589706372, 0.04722295782352715, 0.0, 0.5456380666109822, -0.16908262597857465, -0.522481214502478, 0.1461534807055757, 0.37666483191527816, -0.1855687496936574, 0.020997239613460877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30632626208072616, 0.09031298949467995, -0.22692456938849484, 0.16322421478210972, -0.12585470012523042, -0.03325777363445849, 0.20625099862925758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20630514214555695, -0.19345381168511577, -0.008617990399806234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001438740509397, 0.13491240604240237, 0.4854280578776173, 0.0, -0.23325017153039881, -0.23668803750654724, -2.4469621100956136, -1.180043409121759, -2.604441923727538, -0.2542616803190728, -0.9034046231800951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1500139995816223, 0.7820642540186723, 1.711999903987663, -1.5061554522402196, -1.4934494542740804, -0.37658879725504163, 0.6770756911532064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5515865469940715, -0.5272662582455687, 0.03200561485251141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444928526822455, 0.1440954073028262, 0.04718637341385814, 0.0, 0.5388582981836805, -0.14755111498801532, -0.5083154010012589, 0.15076280182225638, 0.4032347819114077, -0.18218850359385164, 0.029538683508763354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2941570667657477, 0.07375506951581443, -0.23718942857923855, 0.17889055013354835, -0.13424099750506613, -0.03237911356310805, 0.20337360789696188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2062496385704195, -0.1928031500041254, -0.0034658408892790024]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20001956923917136, 0.14209490819490286, 0.48778483406484985, 0.0, -0.20719014955641507, -0.2431537045007487, -2.4717559018778976, -1.1723466381173246, -2.5832851837647595, -0.26272698890159707, -0.9018119287954139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1362925875347156, 0.7846942107354439, 1.6995945594881667, -1.4962533594938423, -1.500654434469294, -0.37804175814020746, 0.6869377230363743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5618772554935478, -0.5362481924237863, 0.03193009384487926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001036366815479113, 0.14365004305001008, 0.047135523744650826, 0.0, 0.5212004394796748, -0.12931333988402918, -0.4958758356456816, 0.15393542008868819, 0.42313479925557457, -0.16930617165048542, 0.031853887693621664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2744282409381327, 0.052599134335431535, -0.24810688998992422, 0.1980418549275443, -0.1440996039042721, -0.029059217703316893, 0.1972406376633577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20581416998952623, -0.17963868356435048, -0.001510420152642911]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20002491398495875, 0.1494178801698363, 0.49014213867983025, 0.0, -0.18248615642303045, -0.24874252779424932, -2.495791256850934, -1.1643342319297219, -2.561549609322388, -0.27017462278306265, -0.9004516927928198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1235910388524077, 0.7862627988346579, 1.686786930289798, -1.4854969415594632, -1.5083462475227143, -0.3792270963843562, 0.6964032961833078, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5721284937799476, -0.544042023523245, 0.03174277720679715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010689491574809543, 0.14645943949866824, 0.047146092299607985, 0.0, 0.494079862667692, -0.11177646587001251, -0.4807070994607294, 0.1602481237520551, 0.43471148884742883, -0.14895267762931144, 0.027204720051883843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.25403097364615596, 0.031371761984279836, -0.2561525839673737, 0.21512835868758007, -0.15383626106840426, -0.023706764882974334, 0.1893114629386691, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2050247657279953, -0.15587662198917399, -0.00374633276164229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000302436587149, 0.1568804363366327, 0.4925089959261279, 0.0, -0.15942620646426864, -0.2535716429058741, -2.5191037233799887, -1.1561081590561926, -2.5395311185199434, -0.2762882019431225, -0.8995733094187667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1117286539701878, 0.7868744141902151, 1.6737792940401723, -1.474100709544747, -1.5164731868474546, -0.3800749465354888, 0.705439711141863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.582334625025694, -0.5505038053914475, 0.031328551739566904]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010659347512320952, 0.14925112333592852, 0.04733714492595309, 0.0, 0.46119899917523643, -0.09658230223249553, -0.4662493305810919, 0.16452145747058344, 0.4403698160488929, -0.12227158320119691, 0.017567667481062112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23724769764439968, 0.012232307111143079, -0.26015272499251113, 0.2279246402943277, -0.16253878649480763, -0.016957003022651775, 0.1807282991711045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.204122624914929, -0.12923563736404983, -0.008284509344604833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000355409762551, 0.1643493632969471, 0.4948989781480506, 0.0, -0.138134306608576, -0.25778286324663996, -2.541755761063006, -1.1478203450866038, -2.517453701537978, -0.2808626769029118, -0.8993496529219878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1004377528853015, 0.7866677740581992, 1.6607635289911855, -1.4622859299485154, -1.5249653079719356, -0.38055155981383115, 0.7140521457823096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5924971178994362, -0.5556901650508949, 0.03066177407118626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010594635080377414, 0.14937853920628794, 0.047799644438453984, 0.0, 0.42583799711385245, -0.08422440681531787, -0.45304075366034996, 0.16575627939177673, 0.4415483396393033, -0.09148949919578589, 0.00447312993557779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22581802169772486, -0.004132802640316704, -0.2603153009797381, 0.2362955919246301, -0.16984242248962297, -0.00953226556684723, 0.17224869280893232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324985747484237, -0.1037271931889466, -0.01333555336761289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004081292641204, 0.17163111684490254, 0.4973273540293955, 0.0, -0.11861098806654552, -0.261506003937954, -2.563792455725704, -1.1396190617008346, -2.4954889007469143, -0.2838319038624897, -0.8998890469110882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0894421809363275, 0.7857788657157315, 1.6478909021820578, -1.4502320834056803, -1.5337515051369732, -0.3806565744431942, 0.7222674722419069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6026210959822068, -0.559746501253625, 0.029776897416194534]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010543900313926698, 0.14563507095910855, 0.048567517626897164, 0.0, 0.3904663708406098, -0.0744628138262803, -0.44073389325396295, 0.1640256677153848, 0.4392960158212723, -0.059384539191558075, -0.010787879782008984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21991143897947918, -0.017778166849353613, -0.2574525361825549, 0.2410769308567017, -0.17572394330075108, -0.0021002925872602293, 0.16430652919194655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20247956165541275, -0.08112672405460414, -0.01769753309983457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20004606432832564, 0.1785368757147403, 0.4998084022537411, 0.0, -0.10078082637104352, -0.264847160038961, -2.5852379440488384, -1.131630598596612, -2.4737657902986205, -0.28524416183276086, -0.9012452613483256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.078500262559309, 0.7843260714150962, 1.6352650158000486, -1.4380627524161154, -1.5427684175926506, -0.3804169066440311, 0.7301226067745017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6127129574718959, -0.5628429113478618, 0.028737698239593924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001050280382721323, 0.1381151773967553, 0.04962096448691232, 0.0, 0.35660323391003995, -0.06682312202014098, -0.4289097664626888, 0.15976926208445047, 0.43446220896587195, -0.02824515940542372, -0.027124288744748738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21883836754036934, -0.029055886012705798, -0.2525177276401867, 0.24338661979130038, -0.1803382491135461, 0.004793355983261567, 0.1571026906518956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20183722979378182, -0.06192820188473633, -0.020783983532012218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005129930180776, 0.1849245954383537, 0.5023535969404489, 0.0, -0.0845365476780033, -0.26789192708329723, -2.606108693073243, -1.1239444492086228, -2.452378330247755, -0.2852004259172213, -0.903428031037695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0674226840202274, 0.7824081342080057, 1.6229472251942958, -1.4258507451503226, -1.5519634683297958, -0.3798798984965973, 0.7376575659920607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6227788903479773, -0.5651382965458367, 0.027612209173982813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010469946964228746, 0.12775439447226813, 0.05090389373415543, 0.0, 0.32488557386080436, -0.06089534088672406, -0.4174149804880978, 0.1537229877597814, 0.42774920101731634, 0.0008747183107913163, -0.04365539378738713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22155157078163232, -0.038358744141811715, -0.24635581211505642, 0.24424014531585422, -0.18390101474290552, 0.010740162948676057, 0.15069918435117943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2013186575216267, -0.0459077039594976, -0.02250978131222222]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20005652136933838, 0.1907115542078159, 0.5049708022133425, 0.0, -0.06976173780440523, -0.27070753685227544, -2.6264208198234114, -1.116616946684467, -2.4313907896673914, -0.2838218803566358, -0.906412585221189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0560736135802962, 0.7801058082827312, 1.6109657132036308, -1.4136290432962257, -1.5612950664604608, -0.37910605441542466, 0.7449113819247415, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6328242153560852, -0.5667667343942321, 0.026461026087480004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010444135061213921, 0.1157391753892438, 0.052344105457870035, 0.0, 0.29549619747196143, -0.05631219537956404, -0.40624253500336754, 0.14655005048311465, 0.4197508116072699, 0.02757091121170977, -0.05969108366987838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22698140879862486, -0.046046518505490075, -0.23963023981329837, 0.24443403708193845, -0.18663196261329876, 0.015476881623452673, 0.14507631865361617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200906500162158, -0.032568756967906835, -0.023023661730056176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006173377981204, 0.19586946360562876, 0.5076644609626558, 0.0, -0.05634179204398947, -0.27334548158613015, -2.646193322366273, -1.1096790839813315, -2.410842927702957, -0.2812329746831892, -0.9101485177967618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0443638223042633, 0.7774845919923008, 1.5993249042842526, -1.4014024614291, -1.570731417155611, -0.3781624858127281, 0.751920026015881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6428532286355354, -0.5678352846961159, 0.025332638215552584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010424820947313969, 0.10315818795625725, 0.05387317498626852, 0.0, 0.26839891520831505, -0.05275889467709448, -0.3954500508572305, 0.138757254062713, 0.4109572392886899, 0.051778113468932276, -0.07471865151145703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23419582552065923, -0.05242432580860899, -0.23281617838756566, 0.24453163734251182, -0.1887270139030052, 0.018871372053931603, 0.14017288182279053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005802655890033, -0.02137100603767564, -0.02256775743854842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006693974018563, 0.20041148659983554, 0.5104356354131638, 0.0, -0.04416856961827303, -0.2758444403769414, -2.6654490711305923, -1.103143801672166, -2.3907551627710806, -0.2775528776658062, -0.9145677909379701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.032240873995808, 0.7745974410638581, 1.588013709038981, -1.3891577880418844, -1.5802488161344124, -0.37711757562047643, 0.7587156306949181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6528692669109263, -0.5684268272253782, 0.024262524580118537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010411920747207684, 0.09084045988413576, 0.0554234890101607, 0.0, 0.24346444851432894, -0.049979175816224464, -0.3851149752863885, 0.1307056461833094, 0.4017552986375233, 0.07360194034765936, -0.08838546282416829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2424589661691047, -0.05774301856885468, -0.2262239049054323, 0.24489346774431225, -0.19034797957602634, 0.020898203845033683, 0.13591209358074058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032076550781866, -0.011830850585245457, -0.02140227270868092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007214257134473, 0.2043774343813399, 0.5132834444778108, 0.0, -0.033141879221293254, -0.27823311442357535, -2.684214783748266, -1.0970116831686958, -2.3711334911723347, -0.27289151361168223, -0.9195916030855968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0196792372387637, 0.7714870996542419, 1.577012080120262, -1.3768717128358068, -1.5898299178620672, -0.376037003117718, 0.7653264677326032, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6628748614477549, -0.5686045085855391, 0.023274225345194223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010405662318178713, 0.07931895563008712, 0.05695618129293898, 0.0, 0.22053380793959546, -0.04777348093267944, -0.3753142523534738, 0.12264237006940129, 0.3924334319749157, 0.09322728108248012, -0.10047624295253367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.251232735140885, -0.06220682819232286, -0.22003257837437873, 0.24572150412155103, -0.191622034553094, 0.02161145005516844, 0.13221674075370154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001118907365725, -0.003553627203219339, -0.019765984698486314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20007734580778586, 0.20782070618049545, 0.5162057356413299, 0.0, -0.02316952921589255, -0.2805327086574647, -2.7025206472294165, -1.0912751301891823, -2.3519738846130913, -0.26734808709481267, -0.9251359659670314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0066716891018626, 0.7681879876718668, 1.5662958363212114, -1.364516539676587, -1.5994622264425942, -0.3749810550619353, 0.7717773035049438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728719094996554, -0.5684161418783988, 0.022381311534141354]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010406472882246143, 0.06886543598311097, 0.0584458232703806, 0.0, 0.19944700010801403, -0.04599188467778787, -0.36611726962300406, 0.11473105959026818, 0.3831921311848679, 0.11086853033739165, -0.11088725762869056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26015096273802274, -0.06598223964750083, -0.21432487598101155, 0.24710346318439644, -0.19264617161054026, 0.021118961115654065, 0.1290167154468116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19994096103801032, 0.003767334142805944, -0.017858276221057384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008255327007832, 0.2107984551058236, 0.5192101868201725, 0.0, -0.014166840177746965, -0.2827589651423013, -2.7203998728202277, -1.085921389661834, -2.333265997210729, -0.2610109256209237, -0.9311159707638332, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.993222525276789, 0.76472770791297, 1.5558399599130788, -1.3520640084958147, -1.609136898369661, -0.3740030351449078, 0.7780898891731596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6828618146769264, -0.5678979208460078, 0.02158961746419203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010414924584927073, 0.059554978506562724, 0.060089023576853036, 0.0, 0.18005378076291173, -0.044525129696731926, -0.35758451181622114, 0.10707481054696666, 0.3741577480472417, 0.12674322947777925, -0.11960009593603711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2689832765014719, -0.06920559517793774, -0.2091175281626519, 0.24905062361544741, -0.19349343854133583, 0.01956039834054967, 0.12625171336431662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19979810354541996, 0.01036442064782242, -0.015833881398986463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20008787845500087, 0.21333432017666262, 0.522278620524105, 0.0, -0.005963419259842758, -0.2847067784692105, -2.737706908660592, -1.0808938141815105, -2.3150267722676117, -0.25438667800412285, -0.9374635516762867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9793618168468088, 0.7611051078601969, 1.545609423592007, -1.3394608678986315, -1.6188542055022237, -0.3731361931769705, 0.784273511539081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6928467960164502, -0.5671346529160782, 0.02093020073211555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010650369845106335, 0.050717301416780575, 0.06136867407865102, 0.0, 0.16406841835808414, -0.038956266538184035, -0.34614071680728536, 0.10055150960646979, 0.3647844988623467, 0.13248495233601743, -0.12695161824906995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27721416859960457, -0.07245200105546167, -0.20461072642143427, 0.2520628119436626, -0.194346142651256, 0.01733683935874627, 0.12367244731842914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19969962679047468, 0.015265358598590295, -0.013188334641529539]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000932460772157, 0.2154911957901415, 0.5254075520960675, 0.0, 0.0015154044261366864, -0.28641516619292723, -2.7544320930412285, -1.076174171725622, -2.2972498271597006, -0.24759982073920533, -0.9441141009023792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9651278873460428, 0.757327427091728, 1.535580448860818, -1.326672138264618, -1.628612812424153, -0.37240896197700574, 0.7903376336523634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7028278828753675, -0.5661656331890602, 0.020389486558202795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010735244429674809, 0.04313751226957778, 0.0625786314392504, 0.0, 0.14957647371958888, -0.03416775447433472, -0.33450368761273663, 0.09439284911777152, 0.35553890215822376, 0.13573714529835043, -0.13301098452185098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2846785900153182, -0.07555361536937943, -0.20057949462378213, 0.25577459268027014, -0.19517213843858824, 0.01454462399929483, 0.12128244226564817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.199621737178345, 0.019380394540359974, -0.010814283478255146]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000986504638207, 0.2173348800863795, 0.5285963538711298, 0.0, 0.008311286985787932, -0.2879703140158385, -2.770613356296178, -1.071752895513645, -2.2799188962291113, -0.24064150349451635, -0.9510100879683961, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9505529498723302, 0.7534056826233598, 1.5257378740419243, -1.3136770586139697, -1.63841007581735, -0.37184397678607, 0.7962921332243709, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7128055169800916, -0.5650064298475672, 0.019945411914984862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010808773209972387, 0.036873685924759945, 0.06377603550124566, 0.0, 0.13591765119302487, -0.031102956458224976, -0.32362526509899225, 0.08842552423953609, 0.3466186186117867, 0.13916634489377944, -0.13791974132033838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2914987494742535, -0.07843488936736323, -0.19685149637787305, 0.25990159301296684, -0.19594526786394395, 0.011299703818714464, 0.11908999144014908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19955268209448396, 0.023184066829859785, -0.008881492864358671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001040952281578, 0.21892164502751066, 0.5318443998538492, 0.0, 0.014455434372994066, -0.2894449297458632, -2.7863038589103057, -1.0676217341506595, -2.263014026217533, -0.23346849295648808, -0.9581014231716674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9356598942300804, 0.7493518268839664, 1.5160721145437042, -1.3004642700198759, -1.6482428027961602, -0.37145864779806914, 0.8021471910765554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7227798395497232, -0.5636600458570635, 0.019578016659266558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010889528674247463, 0.03173529882262352, 0.0649609196543887, 0.0, 0.12288294774412264, -0.029492314600493903, -0.313810052282559, 0.08262322725971165, 0.33809740023156404, 0.14346021076056528, -0.14182670406542525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2978611128449939, -0.08107711478786886, -0.19331518996440414, 0.2642557718818771, -0.19665453957620216, 0.007706579760017614, 0.11710115704369055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19948645139263124, 0.026927679810074084, -0.007347905114366092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001095818476272, 0.2202943968225748, 0.535150869996002, 0.0, 0.019976112404964497, -0.2908868408754237, -2.801560742506763, -1.0637723948338313, -2.246514853532375, -0.2260387914595803, -0.9653442577370467, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9204627132754218, 0.7451771967137655, 1.5065767335510407, -1.2870279213106035, -1.6581079764407811, -0.3712661111733493, 0.8079130441774274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7327508384249672, -0.5621229025816208, 0.01927182718937029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010973238938801623, 0.027455035901282798, 0.06612940284305621, 0.0, 0.11041356063940856, -0.028838222591209578, -0.3051376719291418, 0.07698678633656415, 0.3299834537031666, 0.1485940299381555, -0.14485669130758602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3039436190931732, -0.08349260340401757, -0.189907619853269, 0.26872697418544794, -0.19730347289241743, 0.003850732494397405, 0.11531706201743988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19941997750488044, 0.030742865508854446, -0.0061237893979253916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20011511096299092, 0.2214825190671099, 0.5385151065100857, 0.0, 0.02490084713840034, -0.2923229338625861, -2.8164412711336357, -1.060196351782816, -2.2304025030501005, -0.21832156697497618, -0.9726993825050722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9049681306376484, 0.740891755553815, 1.4972467377444765, -1.2733648666517141, -1.6680033011218867, -0.3712761292836445, 0.8135997040895893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7427184266565153, -0.560388285861029, 0.019015717754810958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011058230727444141, 0.023762444890702263, 0.06728473028167319, 0.0, 0.09849469466871684, -0.028721859743248285, -0.2976105725374558, 0.07152086102030841, 0.32224700964548914, 0.15434448969208248, -0.14710249536050946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30989165275546887, -0.08570882319900835, -0.1865999161312844, 0.27326109317778985, -0.19790649362210908, -0.00020036220590430396, 0.11373319824323874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935176463096194, 0.03469233441183588, -0.0051221886911865955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012068354139295, 0.22250349531401678, 0.5419369045324964, 0.0, 0.029256928531896972, -0.29376602433815924, -2.8310013768663658, -1.0568847414431133, -2.2146607151661373, -0.21029745116627052, -0.9801307890007165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8891775148909307, 0.7365037811966567, 1.4880774850525833, -1.2594727666522887, -1.677927543943993, -0.37149579637202673, 0.8192166918784729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.752682486082162, -0.5584484377725315, 0.018802084615086322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011145156804087516, 0.020419524938137586, 0.06843596044821347, 0.0, 0.08712162786993259, -0.02886180951146266, -0.2912021146546042, 0.06623220679405235, 0.3148357576792621, 0.1604823161741131, -0.14862812991288768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3158123149343549, -0.08775948714316552, -0.18338505383786374, 0.2778419999885099, -0.19848485644212302, -0.00439334176764448, 0.112339755777672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19928118851293328, 0.0387969617699493, -0.004272662794492707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20012628164617755, 0.22332134060079772, 0.54541662471814, 0.0, 0.03317120156856523, -0.29518464960895535, -2.8451380890300952, -1.053961604220274, -2.1992726208632316, -0.20265878664500153, -0.9876002580722529, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8730997429735209, 0.7319946575093498, 1.4790548783712623, -1.2453195416574887, -1.687887002196704, -0.37191213155652425, 0.8247616904031708, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7626439397110358, -0.556356609092534, 0.018669902169850008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001119620956917603, 0.01635690573561878, 0.06959440371287186, 0.0, 0.07828546073336504, -0.02837250541592201, -0.282734243274592, 0.05846274445678641, 0.30776188605811694, 0.15277329042537996, -0.14938938143072922, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32155543834819605, -0.0901824737461377, -0.18045213362641968, 0.28306449989600013, -0.1991891650542251, -0.00832670368995064, 0.11089997049395796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19922907257747532, 0.04183657359994846, -0.002643648904726283]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013192442139177, 0.2239482275425103, 0.5489548371269524, 0.0, 0.0366715792278375, -0.296586524353173, -2.8588493933976524, -1.0514203929343469, -2.184236114366281, -0.1954379262848652, -0.9950902730344263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8567527786674105, 0.7273588576734159, 1.4701719485389229, -1.230888881533351, -1.6978848911636142, -0.37251543196268055, 0.8302341701041117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7726029312808944, -0.5541258337645512, 0.018610119682379557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001128555042845191, 0.0125377388342514, 0.07076424817624641, 0.0, 0.07000755318544544, -0.028037494884353635, -0.27422608735114595, 0.050824225718544155, 0.3007301299390082, 0.14441720720272663, -0.1498002992434688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.32693928612220846, -0.09271599671867779, -0.17765859664678813, 0.28861320248275546, -0.1999577793382039, -0.012066008123126602, 0.1094495940188172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917983139717088, 0.044615506559656834, -0.0011956497494090225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20013761457522716, 0.22440734591479483, 0.5525510066268541, 0.0, 0.03975911638397082, -0.29798216934315713, -2.8721656295211786, -1.0492191300271183, -2.1695526216527776, -0.18848173123026996, -1.0025971718647806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8401509814292484, 0.7225974376254728, 1.461426296142665, -1.2161747018287186, -1.7079221563356972, -0.3732971774069232, 0.8356348772421495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7825592728935553, -0.5517519790258053, 0.018604268532772555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011380307670761093, 0.009182367445690917, 0.07192338999803456, 0.0, 0.06175074312266636, -0.027912899799682093, -0.2663247224705193, 0.044025258144572164, 0.29366985427007, 0.13912390109190506, -0.15013797660708325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3320359447632418, -0.09522840095886133, -0.17491304792515783, 0.2942835940926487, -0.20074530344166105, -0.01563490888485266, 0.1080141427607551, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19912683225321814, 0.04747709477491714, -0.00011702299214006178]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014335289543783, 0.22472031035488813, 0.5562052394000923, 0.0, 0.042430718224349184, -0.2993775663249582, -2.885124494559544, -1.0473129015067846, -2.155222804147192, -0.1816201348745458, -1.01012474190697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8233031935612874, 0.7177142448998596, 1.4528175204778178, -1.2011759013625687, -1.7179983908228533, -0.374249479327445, 0.8409652330108597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925126832685195, -0.5492244957458804, 0.018635373875526565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011476640421320383, 0.006259288801865879, 0.07308465546476407, 0.0, 0.05343203680756739, -0.027907939636021756, -0.25917730076730283, 0.03812457040667647, 0.28659635011170964, 0.13723192711448282, -0.1505514008437909, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.33695575735921823, -0.09766385451226353, -0.17217551329694306, 0.2999760093229975, -0.2015246897431223, -0.019046038410436672, 0.10660711537420353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906820749928394, 0.05054966559849752, 0.0006221068550801514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20014914122512492, 0.22490281905863652, 0.5599181172915517, 0.0, 0.044685009011025914, -0.3007746371064331, -2.897763192892381, -1.0456630527405861, -2.1412454289020606, -0.1747151974114972, -1.0176787139885983, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8062133777782159, 0.7127138428914443, 1.4443454795666644, -1.1858927542576552, -1.7281125254817933, -0.37536492761112034, 0.8462267964200866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8024628663707979, -0.5465312346100106, 0.018690277971370874]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011576659374156097, 0.0036501740749680742, 0.0742575578291891, 0.0, 0.04508581573353464, -0.027941415629497295, -0.25277396665674096, 0.03299697532397076, 0.2795475049026293, 0.13809874926097254, -0.15107944163256468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3417963156614319, -0.100008040168305, -0.1694408182230674, 0.30566294209827055, -0.20228269317880074, -0.022308965673506504, 0.10523126818453868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1990036620455675, 0.05386522271739528, 0.0010980819168861728]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20015498241295324, 0.22496358788852341, 0.5636906952949815, 0.0, 0.046523124895129254, -0.30217304171259973, -2.910116870810712, -1.0442383548647112, -2.127617660175425, -0.16766711338600437, -1.025262800625812, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7888816327849963, 0.7076004604520697, 1.4360093419839672, -1.170324783273599, -1.7382632426248827, -0.3766364801543263, 0.8514208330493006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8124095464110179, -0.5436605129536562, 0.018759558823811803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011682375656639517, 0.0012153765977381483, 0.0754515600685947, 0.0, 0.036762317682066795, -0.027968092123332625, -0.2470735583666168, 0.028493957517499034, 0.2725553745327172, 0.1409616805098563, -0.15168173274427474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3466348998643898, -0.10226764878749364, -0.16672275165394146, 0.31135941968112435, -0.20301434286178807, -0.02543105086411955, 0.10388073258428018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19893360080440123, 0.05741443312708689, 0.0013856170488185833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001608631206162, 0.22486724977568132, 0.5675244651508963, 0.0, 0.04804091382447449, -0.3035412422848025, -2.922052328864245, -1.043124700167149, -2.114336383673618, -0.16144541042735452, -1.0328762966158225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7713251667984461, 0.7023538524834112, 1.4278003950431948, -1.1544406355268644, -1.7484541924423087, -0.3780359169281584, 0.8565366409104427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8223535527855577, -0.5406644830067112, 0.018874481121896925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011761415325926333, -0.0019267622568418198, 0.0766753971182944, 0.0, 0.030355778586904754, -0.02736401144405591, -0.23870916107066367, 0.022273093951243095, 0.2656255300361335, 0.1244340591729968, -0.15226991980021082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35112931973100436, -0.10493215937317057, -0.16417893881545068, 0.3176829549346932, -0.20381899634852044, -0.02798873547664122, 0.1023161572228418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19888012749079415, 0.05992059893890097, 0.0022984459617024834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20016679470852397, 0.22461810660336734, 0.5714204886721297, 0.0, 0.0492515606625755, -0.3048795567549562, -2.9335321144560953, -1.0423074447214344, -2.10140738073954, -0.15596642624339424, -1.0405372644415392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7535642511419999, 0.6969653494000717, 1.4197151124779401, -1.1382226627253809, -1.7586848946400433, -0.37953926699620993, 0.8615644584658677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8322950464256667, -0.5375590699744391, 0.019029445546714298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011863175815503065, -0.0049828634462796215, 0.0779204704246687, 0.0, 0.024212936762020215, -0.026766289403073663, -0.229595711837008, 0.01634510891429119, 0.25858005868156314, 0.1095796836792056, -0.15321935651433463, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3552183131289241, -0.10777006166679028, -0.16170565130509318, 0.3243594560296713, -0.2046140439546916, -0.030067001361030556, 0.10055635110850149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1988298728021799, 0.06210826064544102, 0.003099288496347424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200172776239212, 0.2242322692592346, 0.5753793197616183, 0.0, 0.050143828812840734, -0.3061910582581071, -2.944550534505061, -1.041743376056535, -2.0888357341121013, -0.15093367718695333, -1.048277236264781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7356141941268067, 0.691432512186373, 1.4117532741877563, -1.121661763852356, -1.7689514159459603, -0.3811251082443771, 0.86649506189296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8422339086677469, -0.5343440199178914, 0.019210896739374525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001196306137608304, -0.007716746882654741, 0.07917662178977203, 0.0, 0.0178453630053046, -0.026230030063017495, -0.2203684009793198, 0.011281373297985921, 0.25143293254877075, 0.1006549811288182, -0.15479943646483557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3590011403038624, -0.11065674427397341, -0.15923676580367516, 0.3312179774604951, -0.2053304261183416, -0.031716824963344104, 0.09861206854184656, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19877724484160614, 0.06430100113095442, 0.003629023853204522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017880771966834, 0.2237276625238269, 0.5794013303291399, 0.0, 0.050699909006210096, -0.30747661967759615, -2.9551116517246165, -1.0413867886406278, -2.0766216597974223, -0.14608404137141487, -1.0561326296271798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7174848001385788, 0.6857562710597147, 1.4039161304800842, -1.10475315105645, -1.7792470152797084, -0.3827741958966008, 0.871319355442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8521699154814953, -0.5310119017509993, 0.01940522188486421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012062960912663622, -0.01009213470815384, 0.08044021135043324, 0.0, 0.011121603867387315, -0.025711228389780374, -0.21122234439110926, 0.007131748318146876, 0.2442814862935846, 0.09699271631076936, -0.1571078672479778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36258787976455753, -0.11352482253316624, -0.1567428741534436, 0.33817225591812267, -0.20591198667496285, -0.032981753044473566, 0.0964858709840395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.198720136274969, 0.06664236333784118, 0.0038865029097937334]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001848920125801, 0.22311939837896405, 0.5834870489289138, 0.0, 0.05090078540002527, -0.308735882796434, -2.9652229966883774, -1.0411980034684942, -2.064759670416598, -0.14123323192581774, -1.0641371565315465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6991809830148032, 0.679939291147258, 1.3962051220839664, -1.087493451223696, -1.7895626538601601, -0.3844693487373193, 0.8760279613648302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8621028082079024, -0.5275522348262791, 0.01960080649115936]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012168585823553865, -0.012165282897256904, 0.08171437199547749, 0.0, 0.004017527876303342, -0.025185262376756567, -0.2022268992752162, 0.0037757034426703215, 0.23723978761649236, 0.09701618891194237, -0.16009053808733326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3660763424755128, -0.1163395982491342, -0.15422016792235796, 0.34519399665507955, -0.2063127716090326, -0.03390305681437007, 0.09417211845336478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19865785452814178, 0.06919333849440365, 0.003911692125903012]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001910339768254, 0.22241740746155528, 0.5876373692829787, 0.0, 0.05072825256032961, -0.3099686862518699, -2.9748947407521658, -1.0411450762759276, -2.0532395768694993, -0.13626393879654164, -1.0723170910833948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6807032804433021, 0.6739849745819401, 1.388621114169803, -1.0698788282800074, -1.7998873562412572, -0.3861952801931571, 0.8806108106665858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8720323358314703, -0.5239535080029184, 0.019788621026410307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012283928490566007, -0.014039818348175664, 0.083006407081299, 0.0, -0.0034506567939130836, -0.024656069108718866, -0.19343488127577046, 0.0010585438513315741, 0.2304018709419729, 0.09938586258552179, -0.1635986910369645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3695540514300244, -0.1190863313063596, -0.15168015828326817, 0.3522924588737728, -0.20649404762193996, -0.03451862911675506, 0.09165698603511138, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19859055247135768, 0.07197453646721513, 0.0037562907050189094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001972276229123, 0.22160015992593438, 0.5918536565550914, 0.0, 0.05023534327615232, -0.31115485912438157, -2.98399731890119, -1.0412776896283897, -2.0420522122641835, -0.1323673535576393, -1.08069297108184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6620730424338469, 0.6678791574614724, 1.3811606617335281, -1.0518815424837384, -1.8102108812872644, -0.3879171685167433, 0.8850471905233438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8819592391097035, -0.5202568933142251, 0.019987756381997294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012387292173853077, -0.016344950712418115, 0.08432574544225284, 0.0, -0.00985818568354585, -0.023723457450233045, -0.1820515629804796, -0.0026522670492431072, 0.22374729210631697, 0.07793170477804703, -0.16751759996890506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3726047601891036, -0.12211634240935253, -0.1492090487254995, 0.35994571592537883, -0.2064705009201449, -0.034437766471724654, 0.08872759713516082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853806556466372, 0.07393229377386722, 0.0039827071117397314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20020347439010194, 0.22066886640840974, 0.5961368789821828, 0.0, 0.04942137616753238, -0.3122911282120764, -2.9924717451619225, -1.0415807058060549, -2.0311924115217646, -0.12926459359144046, -1.0893046900564256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6433087343387187, 0.6616151695062485, 1.3738233634988397, -1.0334828954614335, -1.820518215348053, -0.3896034935502784, 0.8893152917455368, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918837518366295, -0.5164777926262232, 0.020196315181244682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001249353437924127, -0.018625870350492735, 0.0856644485418279, 0.0, -0.0162793421723988, -0.0227253817538959, -0.1694885252146481, -0.0060603235533009635, 0.21719601484837767, 0.06205519932397649, -0.17223437949171228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3752861619025646, -0.12527975910447817, -0.1467459646937689, 0.36797294044609824, -0.20614668121577498, -0.03372650067070167, 0.08536202444386097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984902545385202, 0.07558201376003792, 0.004171175984947794]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002097713156489, 0.21963330701260128, 0.6004876430588264, 0.0, 0.04826735161790908, -0.31337521052871675, -3.0002854311434213, -1.042017856951844, -2.020651124882025, -0.12654774583476963, -1.0982068765058308, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6244231401634923, 0.6551909860127477, 1.3666107181270413, -1.014669781954262, -1.830789814952071, -0.3912255494765068, 0.8933920015145673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9018058862955415, -0.5126188329621287, 0.020406874864572447]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001259385109389794, -0.020711187916169344, 0.08701528153287227, 0.0, -0.023080490992466042, -0.021681646332807118, -0.1562737196299728, -0.008743022915782392, 0.21082573279478972, 0.054336955133416694, -0.17804372898810442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37771188350452867, -0.12848366987001567, -0.14425290743596728, 0.3762622701434281, -0.2054319920803594, -0.032441118524568074, 0.08153419538060984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19844268917823923, 0.07717919328188974, 0.004211193666555281]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021612092282184, 0.21850629281013784, 0.6049063830180879, 0.0, 0.04674694556987107, -0.3144054031470295, -3.0074185370116227, -1.0425507553929605, -2.010411408134718, -0.12394384477934386, -1.1074574531963899, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6054236679376318, 0.6486078022609617, 1.3595250401006225, -0.9954321389298569, -1.8410018235275876, -0.3927577856739413, 0.897252692534199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9117255410177183, -0.5086754720012359, 0.020610626904816205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001269921434586169, -0.022540284049268652, 0.08837479918522834, 0.0, -0.030408120960760072, -0.02060385236625595, -0.1426621173640283, -0.01065796882233028, 0.20479433494613986, 0.052078021108515345, -0.18501153381118132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.37998944451720995, -0.1316636750357197, -0.1417135605283744, 0.38475286048810226, -0.20424017151033333, -0.030644723948690555, 0.07721382039263426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19839309444353564, 0.07886721921785816, 0.004075040804875125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022253027785625, 0.2172997061063792, 0.6093940275144712, 0.0, 0.044831410138811985, -0.31538213075779564, -3.0138605032598287, -1.0431464819052012, -2.0004478758145035, -0.12130496351048073, -1.1171087473807155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5863125474238096, 0.6418689300364602, 1.3525686390384142, -0.975760852223192, -1.8511263198677277, -0.3941779859496728, 0.9008708398699348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9216425579681401, -0.5046390286167527, 0.020799215252272733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012818710068790215, -0.024131734075172735, 0.08975288992766754, 0.0, -0.03831070862118175, -0.01953455221532188, -0.12883932496411699, -0.011914530244816071, 0.19927064640429257, 0.05277762537726262, -0.1930258836865146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38222241027644466, -0.13477744449003068, -0.13912802124416684, 0.39342573413329984, -0.20248992680280403, -0.02840400551462917, 0.07236294671471433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19834033900843503, 0.08072886768966328, 0.0037717669491305742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20022900860672177, 0.21602149077378158, 0.6139508566643666, 0.0, 0.04249304529260065, -0.3163082802897171, -3.019609641149978, -1.0437794882828788, -1.9907280811770776, -0.11855834742913957, -1.127203397503628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56708689339683, 0.6349787981933329, 1.3457432785905576, -0.9556459545254953, -1.8611315315344155, -0.39546708486206655, 0.9042174428273831, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9315567687691604, -0.5004987690426352, 0.020966024033625068]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012956657731027664, -0.02556430665195258, 0.09113658299790565, 0.0, -0.04676729692422672, -0.01852299063842921, -0.11498275780298244, -0.012660127553552256, 0.1943958927485175, 0.054932321626823176, -0.20189300245824846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.38451308053959093, -0.13780263686254624, -0.136507208957131, 0.4022979539539349, -0.20010423333375432, -0.02578197824787499, 0.06693205914896853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982842160204063, 0.08280519148234991, 0.003336175627046675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20023567613729168, 0.21468232598148812, 0.618579669380404, 0.0, 0.039716685832498946, -0.3170317589450412, -3.0246594038591277, -1.0443415770723183, -1.9812217011084206, -0.11567135386636834, -1.13777905015814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477513703633965, 0.6279428756470102, 1.3390496574407549, -0.9350758302929199, -1.8709811549442146, -0.39660843413451846, 0.9072602766909373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9414681136338643, -0.49624739219259395, 0.02109857982582755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013335061139804465, -0.02678329584586907, 0.09257625432074831, 0.0, -0.05552718920203407, -0.014469573106482808, -0.1009952541829951, -0.011241775788790789, 0.19012760137314005, 0.05773987125542451, -0.21151305309023985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3867104606686719, -0.14071845092645366, -0.13387242299605406, 0.4114024846515084, -0.1969924681959818, -0.022826985449038478, 0.06085667727108461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1982268972940784, 0.08502753700082558, 0.0026511158440496816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024248448796664, 0.2132817010339462, 0.6232850539165122, 0.0, 0.03648736491123274, -0.3176151113242534, -3.029022659188296, -1.0448138848933215, -1.9718877847713319, -0.11262628356749618, -1.1488617258468545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.52829997285123, 0.6207655905849384, 1.332488202871619, -0.914035823072634, -1.8806351577949825, -0.39758655139198784, 0.909962810616463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.951376543075006, -0.49187641030852547, 0.02119267081108958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013616701349902424, -0.028012498950838564, 0.0941076907221639, 0.0, -0.06458641842532403, -0.011667047584244146, -0.08726510658336331, -0.009446156420062756, 0.1866783267417718, 0.060901405977443104, -0.2216535137742917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3890279502433304, -0.1435457012414359, -0.1312290913827172, 0.42080014440571706, -0.19308005701535966, -0.01956234514938717, 0.054050678510513796, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19816858882283422, 0.08741963768137005, 0.0018818197052405962]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20024942643988033, 0.21179744237757436, 0.6280614356300516, 0.0, 0.032837414321974116, -0.31812578977269435, -3.0326111904443955, -1.0452508930410527, -1.9626876112700173, -0.11087403638981642, -1.1604767590735159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5087462976732324, 0.6134391523867183, 1.3260590187239967, -0.8924938010822095, -1.8900486175493625, -0.3983666197484187, 0.9122756140155615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9612828171656946, -0.48741756737242403, 0.021263334940033223]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001388390382738015, -0.029685173127436876, 0.09552763427078588, 0.0, -0.07299901178517247, -0.010213568968818868, -0.07177062512199014, -0.008740162954621399, 0.18400347002629233, 0.035044943553595116, -0.23230066453322595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.391073503559951, -0.14652876396440218, -0.1285836829524449, 0.430840439808488, -0.1882691950876016, -0.015601367128617337, 0.04625606798196829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1981254818137743, 0.0891768587220289, 0.0014132825788728686]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025648617165462, 0.2102159997234052, 0.6329105085744566, 0.0, 0.02877294974059154, -0.31860398466958934, -3.0353794732601376, -1.0456722544572943, -1.9535790164030598, -0.10975106669980453, -1.1726841966576451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48909731099497733, 0.6059579119762081, 1.3197643797852852, -0.8704192973769448, -1.8991693651637631, -0.39891412960312955, 0.9141417636527343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711873739518471, -0.4828893418700921, 0.0213193368087825]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001411946354858873, -0.03162885308338303, 0.09698145888810075, 0.0, -0.08128929162765157, -0.009563897937899444, -0.05536565631484504, -0.008427228324830742, 0.18217189733915135, 0.022459393800237974, -0.24414875168258673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39297973356510235, -0.1496248082102037, -0.12589277877422897, 0.44149007410529506, -0.1824149522880104, -0.01095019709421708, 0.03732299274345578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19809113572304787, 0.0905645100466391, 0.0011200373749855554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20026365067228066, 0.20853153423470647, 0.6378348053398177, 0.0, 0.024287414359991967, -0.31906383544072553, -3.03730358821359, -1.0460803808476857, -1.944506846300838, -0.10880336925481057, -1.1855679286607015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46935386567918885, 0.5983182674664688, 1.3136084475674703, -0.8477824018146772, -1.9079370164244762, -0.3991966785218747, 0.9154962070713135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9810904491676253, -0.47830120746567945, 0.021365983100818976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014329001252086628, -0.0336893097739748, 0.09848593530722288, 0.0, -0.08971070761199146, -0.009197015422723371, -0.03848229906904507, -0.008162527807830557, 0.18144340204443837, 0.018953948899879114, -0.2576746400611291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39486890631576926, -0.1527928901947863, -0.12311864435629659, 0.4527379112453502, -0.17535302521426147, -0.005650978374902695, 0.02708886837158525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19806150431556513, 0.09176268808825254, 0.0009329258407294982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002709181633583, 0.2067445984866543, 0.6432883074780156, 0.0, 0.019368020415770022, -0.319506030596099, -3.0383767612417256, -1.0464716606443134, -1.93539817392384, -0.10785793321986444, -1.1992183447754208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.449511737566043, 0.5905186190172917, 1.30759712755751, -0.8245528155742337, -1.9162819395303767, -0.39918565990323196, 0.9162647015301013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9909921334418351, -0.4736560022976525, 0.021405717349798476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014534982155259296, -0.035738714961043055, 0.1090700427639566, 0.0, -0.0983878788844389, -0.008843903107469055, -0.021463460562710514, -0.007825595932554615, 0.1821734475399597, 0.018908720698922653, -0.2730083222943843, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39684256226291714, -0.15599296898354148, -0.1202264001992059, 0.46459172480887045, -0.1668984621180081, 0.0002203723728545822, 0.015369889175756525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19803368548419537, 0.09290410336053989, 0.000794684979589968]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20027829438051795, 0.20485868510348465, 0.6490013560727583, 0.0, 0.014002434650858962, -0.31992610835046786, -3.0386077281967667, -1.0468412358708508, -1.9261612032181843, -0.10686461645591573, -1.2137239690189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295630481332781, 0.5825587072681266, 1.3017382359732208, -0.8006983855868464, -1.9241240546061331, -0.39885668361580096, 0.9163618604901093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0008924345494923, -0.4689530184259971, 0.02143932756822293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001475243431933699, -0.037718267663393076, 0.11426097189485505, 0.0, -0.10731171529822119, -0.008401555087377478, -0.0046193391008222465, -0.007391504530747066, 0.18473941411311273, 0.01986633527897399, -0.2901124848695834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.39897378865529753, -0.15919823498330188, -0.11717783168578469, 0.4770885997477463, -0.15684230151512948, 0.006579525748620504, 0.0019431792001582751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980060221531453, 0.09405967743310696, 0.0006722043684891009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028578925979554, 0.20287743274338085, 0.6547406686796089, 0.0, 0.008185018820865536, -0.32031794640898287, -3.0380197116706626, -1.0471838245626715, -1.9166848868198592, -0.10581108299932915, -1.2291713152384198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.409497880984442, 0.5744384300934184, 1.2960420336682963, -0.7761829962429637, -1.9313712603623479, -0.39818884409194577, 0.9156880981674309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0107913532621287, -0.46419123734401335, 0.021467110255929775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00014989758555187285, -0.03962504720207571, 0.11478625213701081, 0.0, -0.11634831659986852, -0.007836761170300528, 0.011760330522081603, -0.0068517738364139965, 0.18952632796650123, 0.02107066913173159, -0.30894692439039756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4013033429767219, -0.16240554349416467, -0.11392404609848922, 0.49030778687765375, -0.1449441151242955, 0.013356790477103832, -0.01347524645356626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19797837425272766, 0.09523562163967537, 0.0005556537541368603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20029341668299114, 0.20080310284452807, 0.6604121090446456, 0.0, 0.001921849586408484, -0.3206748265522026, -3.036649950845352, -1.0474931959378289, -1.9068372060650318, -0.10469342341170036, -1.2456491252742798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38930633750726457, 0.5661566921582276, 1.2905223641067847, -0.750964653980663, -1.9379170515353874, -0.3971633693842987, 0.9141253637504341, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0206889396240197, -0.45937220777499244, 0.021489539567299338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015254846391213545, -0.04148659797705568, 0.11342880730073404, 0.0, -0.12526338468914103, -0.007137602864394741, 0.027395216506216978, -0.006187427503146391, 0.1969536150965476, 0.022353191752575823, -0.32955620071719854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.403830869543549, -0.16563475870381658, -0.11039339123023295, 0.5043668452460132, -0.13091582346079012, 0.020509494152941406, -0.03125468833993677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979517272378216, 0.09638059138041875, 0.00044858622739128284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030119568854826, 0.19863638606599057, 0.6660139722038477, 0.0, -0.0047654859416252715, -0.32098958444084497, -3.034549899605448, -1.047761372718335, -1.8964610837443059, -0.10350850752967147, -1.2632545889497222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3689808614367368, 0.5577104480698207, 1.2851985271167368, -0.7249939125996567, -1.9436369605967867, -0.39576205076792975, 0.9115313297721367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305853548399064, -0.45450238080270544, 0.021507407707782908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015558011114232356, -0.04333433557074981, 0.1120372631840425, 0.0, -0.1337467105606751, -0.006295157772847987, 0.04200102479807478, -0.005363535610125525, 0.207522446414517, 0.023698317640577764, -0.3521092735088453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40650952141055535, -0.16892488176813872, -0.10647673980095607, 0.5194148276201257, -0.11439818122798806, 0.028026372327378497, -0.05188067956594836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792830431773525, 0.09739653944573959, 0.0003573628096714333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20030914634140978, 0.19637390500117713, 0.6715828451201916, 0.0, -0.011823845857501004, -0.32125109674842384, -3.0317232352621573, -1.047993758889174, -1.8853759253989026, -0.10350850752923797, -1.282109695006647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34853531759768974, 0.5490903893140774, 1.2800996783217704, -0.6982100150772024, -1.9483808813828611, -0.3939543090524812, 0.9077272656514751, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0404812611623253, -0.44961272326613566, 0.021525033954934155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001590130572305638, -0.045249621296268805, 0.11137745832687744, 0.0, -0.14116719831751465, -0.005230246151577747, 0.056533286865820584, -0.004647723416777062, 0.22170316690806577, 8.670054257864379e-12, -0.37710212113849784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4089108767809417, -0.17240117511486672, -0.10197697589932689, 0.535677950449087, -0.09487841572149006, 0.036154834308971096, -0.07608128241323243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19791812644837758, 0.09779315073139577, 0.00035252494302495706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003172693409572, 0.1940175527107981, 0.6771603689056768, 0.0, -0.019193679667741763, -0.321440476638921, -3.028179268613157, -1.0481732072969074, -1.8733471366727263, -0.10350850752836022, -1.3024202699248018, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3279913270141919, 0.5402847239915176, 1.2752683565321803, -0.670544663390444, -1.9519661143688292, -0.39170631156022995, 0.9024892898828979, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0503774344917505, -0.4447394511672975, 0.021544256271463894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016245999094805286, -0.047127045807580724, 0.11155047570970374, 0.0, -0.1473966762048152, -0.0037875978099430434, 0.07087933298000587, -0.003588968154669996, 0.24057577452352463, 1.7555029717154477e-11, -0.40621149836309306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4108798116699565, -0.17611330645119624, -0.09662643579180089, 0.5533070337351663, -0.07170465971936085, 0.04495994984502532, -0.10475951537154438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19792346658850413, 0.09746544197676281, 0.000384446330594774]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032562408611035, 0.19157898268789894, 0.6827789936632113, 0.0, -0.02680877064690194, -0.32154935222513786, -3.0239496911498267, -1.048269333871253, -1.8600634801830365, -0.10350850752892245, -1.3244520270897273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3073749799692585, 0.5312801892863821, 1.2707653820007925, -0.641920890359514, -1.9541671935741474, -0.38898616714406864, 0.8955337475218497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0602746926488202, -0.43992003567794874, 0.02156267750140531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016709490306319699, -0.04877140045798318, 0.11237249515069075, 0.0, -0.15230181958320357, -0.002177511724336902, 0.0845915492666035, -0.0019225314869087012, 0.2656731297937968, -1.1244587338957728e-11, -0.440635143298511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41232694089866834, -0.18009069410271097, -0.09005949062775538, 0.5724754606185991, -0.04402158410636586, 0.05440288832322622, -0.13911084722096373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979451631413971, 0.09638830978697575, 0.0003684245988282738]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003343827899983, 0.18908234189505516, 0.6884591475134899, 0.0, -0.03458886264762535, -0.32156845280526186, -3.019089507224257, -1.0482170064255085, -1.8451117116401439, -0.10350850752801133, -1.348545726744807, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.28671800434849704, 0.5220618657484017, 1.2666775150992649, -0.6122492040576393, -1.9547005956772974, -0.38576786993113416, 0.886494070350839, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0701739237493035, -0.4351940617873942, 0.02157207271245176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017517407775899616, -0.04993281585687589, 0.11360307700557186, 0.0, -0.15560184001446814, -0.0003820116024801435, 0.09720367851139555, 0.0010465489148875277, 0.29903537085785037, 1.8222420301728088e-11, -0.48187399310159584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4131395124152298, -0.18436647075960821, -0.08175733803055242, 0.5934337260374951, -0.010668042062998706, 0.06436594425868974, -0.18079354342021137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19798462200966607, 0.09451947781108981, 0.00018790422092902821]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003437113012565, 0.1865590655037719, 0.6942110743842566, 0.0, -0.042433366863801565, -0.32148710723549906, -3.013687044176947, -1.0479506258393319, -1.8279278250508226, -0.10350850752730906, -1.3751539477281702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26605257839378216, 0.5126101957533383, 1.263130067889564, -0.5814169572975708, -1.953201116026987, -0.38203307191891245, 0.8748821920655593, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0800761664844183, -0.43060595297904586, 0.021563618093416753]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018657022516393627, -0.05046552782566498, 0.11503853741533392, 0.0, -0.15689008432352433, 0.0016269113952556665, 0.10804926094620285, 0.00532761172353181, 0.34367773178642597, 1.4045463697372213e-11, -0.5321644196672647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41330851909429756, -0.1890333999012687, -0.07094894419401514, 0.6166449352013684, 0.02998959300620538, 0.07469596024443391, -0.23223756570559562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19804485470229513, 0.09176217616696702, -0.00016909238070013938]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20035384746092152, 0.18404512675042728, 0.7000380490622289, 0.0, -0.050212851054079896, -0.32129764731835564, -3.007872020375405, -1.047408573474381, -1.807714696520507, -0.1035085075265131, -1.4049158957652377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24540734864367067, 0.5028965248793075, 1.260308356335637, -0.5492699698748068, -1.949181545315102, -0.3777738292535714, 0.8600228144996451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899826588460824, -0.42620844655981927, 0.021530459334271956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020272319330068492, -0.050278775066892704, 0.11653949355944743, 0.0, -0.1555896838055666, 0.003789198342868636, 0.11630047603084057, 0.01084104729901766, 0.4042625706063127, 1.5919110619624917e-11, -0.5952389607413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.41290459500222965, -0.19427341748061752, -0.0564342310785417, 0.6429397484552792, 0.08039141423770374, 0.08518485330682168, -0.2971875513182835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19812984723328245, 0.08795012838453235, -0.0006631751828959446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036843163460358, 0.18136281953048786, 0.7059390781648229, 0.0, -0.057767388905325394, -0.3210710738639323, -3.0019894450633307, -1.0466631557182662, -1.7833826261393904, -0.10350850752649103, -1.4386498684378064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22607875701511615, 0.49392618538752037, 1.2587569083891101, -0.5184133404197366, -1.941897647938553, -0.3738639731587597, 0.8417880744913834, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0998962708048692, -0.4221692529637803, 0.021686362584224045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002916834736410404, -0.053646144398788474, 0.1180205820518809, 0.0, -0.1510907570249099, 0.0045314690884670624, 0.1176515062414791, 0.014908355122296033, 0.4866414076223328, 4.4136456503999646e-13, -0.6746794534513738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3865718325710906, -0.17940678983574165, -0.03102895893053481, 0.6171325891014039, 0.1456779475309793, 0.07819712189623458, -0.36469480016523564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19827223917573664, 0.08078387192078006, 0.0031180649990417805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2003942537113021, 0.17828529615059197, 0.7119086970749711, 0.0, -0.06481104577349599, -0.32095649077276867, -2.9965751754981027, -1.0458472146225162, -1.753576222358894, -0.10350850752557518, -1.476720268237994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21045717232158523, 0.4874910167006223, 1.2591597974561297, -0.492597068932329, -1.930827428581285, -0.371992393713558, 0.821011277691062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1098211641847406, -0.4187433454099081, 0.02231639502794631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000516441533970284, -0.061550467597917866, 0.11939237820296275, 0.0, -0.14087313736341175, 0.0022916618232726514, 0.10828539130455896, 0.016318821914997908, 0.5961280756099278, 1.8317036250482457e-11, -0.7614079960037541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.31243169387061864, -0.12870337373796226, 0.008057781340389522, 0.5163254297481521, 0.22140438714536217, 0.03743158890403379, -0.4155359360064289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1984978675974289, 0.06851815107744402, 0.012600648874445338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004388397255267, 0.17485617009380533, 0.7179373658089209, 0.0, -0.0708799625458358, -0.32108736955233547, -2.9921991868446067, -1.0449728458633074, -1.7183656050601326, -0.103508507551078, -1.5186732699592207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20058607313259408, 0.48488016496026076, 1.261770084558291, -0.47557115538422545, -1.9164565911539984, -0.3734251779064008, 0.7994134183993886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1197616468296943, -0.41613950387568394, 0.023478168149860274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008917202844920643, -0.06858252113573299, 0.12057337467899516, 0.0, -0.12137833544679619, -0.002617575591335923, 0.08751977306991583, 0.01748737518417392, 0.70421234597523, -5.100565746783541e-10, -0.8390600344245331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19742198377982317, -0.052217034807230445, 0.052205742043229766, 0.34051827096207177, 0.2874167485457316, -0.028655683856854998, -0.43195718583346787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19880965289907265, 0.0520768306844828, 0.023235462438279234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2005152505839828, 0.1713391455780551, 0.7240261343656306, 0.0, -0.0757735884958979, -0.3213355926797959, -2.9889814816028712, -1.0440263392981617, -1.6783008240333939, -0.10350850760301146, -1.5640162619985774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19755116875234574, 0.48665761041572353, 1.2661729829388388, -0.4710855997270218, -1.9005937735528882, -0.3787027586782937, 0.7798707452587533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.129720437439687, -0.4144030404743032, 0.02505428898970948]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015282171691219392, -0.07034049031500482, 0.12177537113419343, 0.0, -0.09787251900124191, -0.004964462549208628, 0.0643541048347083, 0.018930131302915862, 0.8012956205347723, -1.0386692511734449e-09, -0.9068598407871321, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06069808760496673, 0.03554890910925572, 0.08805796761095572, 0.08971111314407304, 0.31725635202220503, -0.10555161543785882, -0.3908534628127065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19917581219985286, 0.034729268027614696, 0.03152241679698409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20065601839622627, 0.16807247951426837, 0.7301320595769725, 0.0, -0.07969648408535791, -0.32176962153628585, -2.986607289663825, -1.0431390960024967, -1.6342489992114075, -0.10350850760306361, -1.6122408329025861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20067328395522496, 0.492400892843251, 1.2716015314676967, -0.47859763667929617, -1.8855827822470475, -0.3876223444709693, 0.7649963838140723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1396650036073466, -0.41338405076823215, 0.026870077922475817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0028153562448687964, -0.06533332127573466, 0.12211850422683904, 0.0, -0.07845791178920039, -0.008680577129799173, 0.04748383878092355, 0.017744865913298997, 0.881036496439728, -1.042922814899149e-12, -0.9644914180801775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062442304057584455, 0.11486564855054912, 0.10857097057715762, -0.1502407390454879, 0.30021982611681386, -0.1783917158535125, -0.29748722889361945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19889132335319332, 0.02037979412142081, 0.036315778655326744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20096542306793036, 0.1654449932387038, 0.7362508424313801, 0.0, -0.08304710453424663, -0.32573663391034274, -2.9837188757965825, -1.0443762733868391, -1.5870075393538325, -0.10521373332923009, -1.662240832902595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2086725093691195, 0.5012186466235822, 1.2773543946865247, -0.496107667472857, -1.874211870670797, -0.3994081790168006, 0.7573401079606881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1494812901559333, -0.4128914605340995, 0.02866861537375455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006188093434081931, -0.0525497255112915, 0.1223756570881518, 0.0, -0.06701240897777443, -0.07934024748113738, 0.05776827734485358, -0.024743547686851254, 0.9448291971514986, -0.034104514523329695, -1.0000000000001805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998450827789035, 0.17635507560662322, 0.1150572643765603, -0.35020061587121726, 0.22741823152500568, -0.2357166909166251, -0.15312551706768568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1963257309717322, 0.009851804682653769, 0.03597074902557463]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20152838728931086, 0.16369481209325562, 0.7423906816198869, 0.0, -0.08691864583703286, -0.3314701379428469, -2.9768146445403336, -1.0486542064114133, -1.5393105615783342, -0.11197817370281932, -1.712240832902578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22038123413262947, 0.5120842470988328, 1.282798670935164, -0.5219493598008356, -1.870009977014743, -0.4126385789809851, 0.7601173661938881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158737285299586, -0.41276466205298745, 0.030274916064017]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011259284427610077, -0.035003622908963465, 0.12279678377013534, 0.0, -0.07743082605572461, -0.11467008065008287, 0.13808462512497643, -0.08555866049148067, 0.9539395555099669, -0.13528880747178448, -0.999999999999657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2341744952701998, 0.21731200950501292, 0.1088855249727857, -0.5168338465595709, 0.08403787312108424, -0.2646079992836903, 0.05554516466400122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18511990287305707, 0.0025359696222403425, 0.03212601380524895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20202627967430978, 0.16284106308747984, 0.7485249734313544, 0.0, -0.09344210826657097, -0.33808688780499263, -2.962144595895054, -1.0563212869545757, -1.4949080658849068, -0.1275518286405913, -1.7622408329025676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2350154259370006, 0.5242289585463547, 1.287687448692728, -0.5546227136632432, -1.873673089113286, -0.42613294628406545, 0.7728950815705997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1674067985535097, -0.41296480272338026, 0.031647632194646884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009957847699978529, -0.017074980115515438, 0.12268583622935114, 0.0, -0.1304692485907622, -0.1323349972429145, 0.29340097290509703, -0.15334161086325052, 0.8880499138684388, -0.31147309875544, -0.9999999999997944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.29268383608742216, 0.24289422895043714, 0.09777555515128335, -0.6534670772481537, -0.0732622419708612, -0.2698873460616072, 0.25555430753423225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17339026507847224, -0.004002813407856775, 0.027454322612597743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.202398800107997, 0.16280683147053426, 0.7545672663418745, 0.0, -0.10236052291981554, -0.34514526068085766, -2.938669555357371, -1.066806922522258, -1.4566519388420978, -0.15099873731396388, -1.8122408329025614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2521359232549917, 0.5371313790297202, 1.2922238548942178, -0.5927613967532037, -1.8839800229080845, -0.4391346299700987, 0.794086424033654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1756525480679787, -0.413549951262761, 0.03278605831622804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007450408673744192, -0.0006846323389115214, 0.12084585821040356, 0.0, -0.17836829306489152, -0.141167457517301, 0.4695008107536621, -0.2097127113536453, 0.7651225408561788, -0.4689381734674513, -0.9999999999998763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3424099463598216, 0.2580484096673115, 0.090728124029795, -0.76277366179921, -0.20613867589596885, -0.26003367372066566, 0.42382684926108727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16491499028938097, -0.01170297078761519, 0.022768522431623063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2027163628310531, 0.163548418785463, 0.7604249409633889, 0.0, -0.1129019331978828, -0.34889525657054227, -2.9078895229271913, -1.0783023625548778, -1.4236392592615992, -0.1812568968502859, -1.862240832902567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27156293012603155, 0.5504404420941427, 1.2967143864739177, -0.6352723432251367, -1.8997476245278966, -0.4511342511228243, 0.8224317087991058, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.18355943573368, -0.4145957872726459, 0.03365033610337059]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006351254461121899, 0.014831746298575024, 0.11715349243028593, 0.0, -0.21082820556134538, -0.07499991779359372, 0.6156006486035991, -0.2299088006523955, 0.6602535916099723, -0.6051631907264403, -1.000000000000111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3885401374207975, 0.26618126128844893, 0.08981063159399902, -0.85021892943866, -0.31535203239624304, -0.23999242305451118, 0.5669056953090346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15813775331402652, -0.020916720197697428, 0.01728555574285116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20300062721202383, 0.16503843169782795, 0.7660373673432823, 0.0, -0.12443766154595379, -0.35264525165413685, -2.8712654969834506, -1.0900256812328397, -1.3939445447531358, -0.217290875746959, -1.9122408329024576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29321619565331164, 0.563902471783936, 1.3017963568395874, -0.6812811004027302, -1.920152501583522, -0.46209018873095564, 0.856740237231522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1912604617573923, -0.41613681364612143, 0.0342114464647145]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005685287619414848, 0.029800258247298695, 0.11224852759786824, 0.0, -0.23071456696141968, -0.07499990167189127, 0.7324805188748166, -0.23446637355923902, 0.5938942901692699, -0.7206795779334619, -0.9999999999978096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4330653105456018, 0.2692405937958666, 0.10163940731339415, -0.92017514355187, -0.4080975411125062, -0.21911875216262716, 0.6861705686483266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1540205204742444, -0.030820527469511003, 0.01122220722687825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20327350143028525, 0.16728785758489248, 0.7713944842449668, 0.0, -0.1366453821212773, -0.35264524971890543, -2.829966276228405, -1.1011813700863278, -1.3659979985495936, -0.25811805886428807, -1.9622408329024688, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.317005942110701, 0.5772663034002397, 1.3082663081475974, -0.7300881061447986, -1.9449740073709518, -0.4723040399021917, 0.8960526609708361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1988628223791276, -0.4181387944267183, 0.034438861496440466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005457484365228559, 0.04498851774129044, 0.10714233803369108, 0.0, -0.24415441150647035, 3.8704628849139944e-08, 0.8259844151009157, -0.2231137770697607, 0.5589309240708441, -0.8165436623465813, -1.000000000000223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47579492914778665, 0.26727663232607307, 0.12939902616019983, -0.976140114841369, -0.49643011574859736, -0.2042770234247212, 0.786248474786281, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1520472124347034, -0.040039615611937036, 0.004548300634519246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354427407946665, 0.17029590589764237, 0.7765242390469841, 0.0, -0.14957609567993307, -0.3526452497225634, -2.784926899624365, -1.111502092915575, -1.3387330147559335, -0.30277980535815, -2.012240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3425978958829109, 0.59021135720085, 1.3168912697811177, -0.7800881312000915, -1.9743114642801527, -0.4823756353417002, 0.939502599962036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2064712450597492, -0.42048907395168095, 0.0343385347184016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005415452983628351, 0.06016096625499762, 0.10259509604034556, 0.0, -0.25861427117311553, -7.315934072253455e-11, 0.900787532080797, -0.20641445658494453, 0.5452996758732007, -0.8932349298772394, -0.9999999999999883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5118390754441977, 0.258901076012207, 0.17249923267040806, -1.0000005011058573, -0.5867491381840184, -0.20143190879016956, 0.8689987798239975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15216845361243223, -0.047005590499253035, -0.0020065355607773996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20380902679416726, 0.1740250608263596, 0.7814815414939414, 0.0, -0.16345409175240433, -0.35264524972256756, -2.7368953983411313, -1.1210488685706324, -1.3114909002989157, -0.3505092025532365, -2.062240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3694491359183932, 0.6024375144364038, 1.3280363297310942, -0.8300881562554033, -2.008190975646627, -0.49297056126018424, 0.9862625511421699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2141691199585547, -0.4230301045584226, 0.033953799488170976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005295054294012406, 0.07458309857434448, 0.09914604893914625, 0.0, -0.277559921449425, -8.306185477170416e-14, 0.960630025664667, -0.19093551310114656, 0.544842289140358, -0.954587943901729, -0.9999999999999948, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5370248007096454, 0.2445231447110752, 0.22290119899952948, -1.0000005011062378, -0.6775902273294845, -0.2118985183696804, 0.9351990236026778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15395749797610853, -0.05082061213483312, -0.007694704604612444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20405302516662302, 0.17839110823571697, 0.7863344254845989, 0.0, -0.17851430003789928, -0.35264524972255495, -2.686895373285901, -1.1300227185258729, -1.2838256251509144, -0.40050922760850854, -2.112240832902468, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3969237492142522, 0.613741097894437, 1.3415486574536832, -0.8800881813106121, -2.0459772709518442, -0.504647076992953, 1.0355802259860223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2220102602948362, -0.4255933560538981, 0.03335268787598558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004879967449115027, 0.0873209481871476, 0.09705767981314739, 0.0, -0.30120416570989883, 2.525265043987572e-13, 1.000000501104607, -0.17947699910481119, 0.5533055029600262, -1.0000005011054416, -0.9999999999999959, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5494922659171806, 0.22607166916066412, 0.2702465544517814, -1.0000005011041742, -0.7557259061043429, -0.23353031465537516, 0.9863534968770462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15682280672562757, -0.05126502990950946, -0.012022232243707826]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20427427775571064, 0.1832657630480131, 0.7911560606975594, 0.0, -0.19402046241882806, -0.3526452497225476, -2.6369255548772657, -1.1381357395602882, -1.2541818029209706, -0.4505092526637864, -2.1622408329024654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4241780894055525, 0.6240109137311005, 1.3565984597849061, -0.9300882063658712, -2.086394358193773, -0.5175612797107543, 1.085580225986022, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2299439964350036, -0.4280393053467843, 0.03261250819647751]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004425051781752245, 0.09749309624592228, 0.09643270425921166, 0.0, -0.3101232476185755, 1.46698788079243e-13, 0.9993963681727096, -0.16226042068830895, 0.5928764445988757, -1.0000005011055564, -0.9999999999999505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5450868038260062, 0.2053963167332707, 0.3009960466244557, -1.0000005011051827, -0.8083417448385756, -0.2582840543560268, 0.9999999999999947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15867472280334796, -0.04891898585772456, -0.014803593590161389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20448925460959733, 0.1884861482941713, 0.7960013837556438, 0.0, -0.20812797112921447, -0.3526452497225536, -2.590735943115225, -1.1442111287049983, -1.2195158208931738, -0.5005092777190392, -2.2122408329024843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4501567220181025, 0.6334540335899963, 1.3712930643842167, -0.9782469378031894, -2.1265963620534154, -0.531072591019149, 1.1355802259860202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2377756105301416, -0.43028076956376143, 0.03180917214483589]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004299537077733934, 0.10440770492316372, 0.09690646116168819, 0.0, -0.28215017420772837, -1.204229784694197e-13, 0.923792235240814, -0.12150778289419997, 0.6933196405559353, -1.0000005011050557, -1.000000000000377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5195726522509989, 0.1888623971779163, 0.29389209198621125, -0.9631746287463633, -0.8040400771928422, -0.2702262261678953, 0.9999999999999597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1566322819027592, -0.04482928433954309, -0.016066721032832413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2047468885177489, 0.19387014210656023, 0.8008866381240283, 0.0, -0.21961803998109392, -0.3521226426517718, -2.5514919148248616, -1.1465010588890092, -1.1798068664050003, -0.5505093027742914, -2.262240832902491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4737450900696767, 0.642079354452608, 1.3843459861892113, -1.0220309843042243, -2.1630376093293977, -0.5443202336407252, 1.1818302260191775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2452004234030019, -0.4322623985728623, 0.031009374273467866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005152678163031458, 0.10767987624777886, 0.09770508736768965, 0.0, -0.2298013770375888, 0.010452141415636393, 0.784880565807272, -0.04579860368021922, 0.794179089763471, -1.0000005011050457, -1.0000000000001337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.47176736103148464, 0.17250641725223376, 0.2610584360998941, -0.8756809300207011, -0.7288249455196422, -0.2649528524315232, 0.9250000006631481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14849625745720518, -0.03963258018201765, -0.015995957427360454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2051287495455325, 0.19923065914216656, 0.8057737414679297, 0.0, -0.2281785742138778, -0.35022616837644915, -2.519391471608246, -1.1433405956760947, -1.136039702814632, -0.6005093278295216, -2.3122408329025026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4940033565817461, 0.6497248585809339, 1.3951808982628564, -1.059285479802085, -2.192812112797505, -0.5564281233814546, 1.2207959277732934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2519001603691544, -0.4339526108995303, 0.030265197010617452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007637220555672521, 0.10721034071212654, 0.09774206687802872, 0.0, -0.1712106846556775, 0.03792948550645252, 0.6420088643323169, 0.06320926425829188, 0.8753432718073637, -1.0000005011046043, -1.0000000000002376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4051653302413882, 0.15291008256651703, 0.21669824147290176, -0.7450899099572149, -0.5954900693621484, -0.24215779481458866, 0.7793140350823167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13399473932305103, -0.03380424653335981, -0.014883545257008256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20576022076715375, 0.2043888656870428, 0.8105783890627817, 0.0, -0.2337123229928388, -0.3464879381815168, -2.4940922874295155, -1.1337999009427524, -1.0890259719424475, -0.650509352884751, -2.362240832902516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510514236160238, 0.6564071831994994, 1.403620965527082, -1.0890059379932011, -2.214526068245795, -0.5667107378922177, 1.2507736607049844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2576710963515167, -0.4353477493425074, 0.029610162330812134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012629424432424752, 0.10316413089752449, 0.09609295189704037, 0.0, -0.11067497557922014, 0.07476460389864714, 0.5059836835746102, 0.19081389466684653, 0.9402746174436897, -1.0000005011045867, -1.0000000000002702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33021759156983965, 0.133646492371311, 0.16880134528450907, -0.5944091638223233, -0.43427910896580035, -0.20565229021526063, 0.5995546586338187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11541871964724648, -0.027902768859541856, -0.013100693596106397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064101730111816, 0.20918969614030278, 0.8151985088088208, 0.0, -0.23619468757488218, -0.34091006903492105, -2.475337384198103, -1.1177464421455081, -1.0394149872447274, -0.7005093779400104, -2.412240832902519, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.523403301297924, 0.6622822239167705, 1.4098182069669167, -1.1113813433797564, -2.2283755764191837, -0.5748417513451253, 1.2719013258029221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2624608795377155, -0.43646862893810046, 0.029057378771169932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880557524, 0.09601660906519982, 0.09240239492078313, 0.0, -0.04964729164086727, 0.11155738293191456, 0.375098064628254, 0.3210691759448877, 0.9922196939544017, -1.0000005011051882, -1.0000000000000613, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2577813027537198, 0.11750081434542253, 0.1239448287966965, -0.44750810773110444, -0.27699016346777455, -0.16262026905815133, 0.42255330195875485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.095795663723975, -0.022417591911861316, -0.011055671192844046]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2070601252552261, 0.2135221305357053, 0.8195134890305069, 0.0, -0.23592775110245523, -0.33388518964591246, -2.462551220837017, -1.0959194558390715, -0.9894149872447394, -0.7505094029952885, -2.4622408329025243, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5333287265246551, 0.667481948193073, 1.4142498397471182, -1.1277963513126714, -2.2360476984196853, -0.5810006042943882, 1.2859313215966783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.266386030912219, -0.4373574993376022, 0.028596672850609083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880889928, 0.08664868790805016, 0.08629960443372142, 0.0, 0.005338729448539366, 0.1404975877801714, 0.25572326722171174, 0.4365397261287322, 0.9999999999997586, -1.0000005011055593, -1.0000000000001035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19850850453462252, 0.10399448552605098, 0.08863265560402797, -0.32830015865830164, -0.1534424400100285, -0.12317705898525709, 0.2805999158751256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07850302749007283, -0.017777407990034997, -0.009214118411216964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20771007749924222, 0.2173234455155467, 0.823412480102414, 0.0, -0.2331721748620815, -0.3259143561449327, -2.4553099141551606, -1.0691483838741687, -0.9394149872447404, -0.8005094280505596, -2.512240832902523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5410462930877361, 0.6720870992422457, 1.4174490504828554, -1.1398783046788483, -2.23955831534367, -0.5855875325806078, 1.2949642850495815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2696122536938677, -0.43805918705077557, 0.028207867985896987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880322287, 0.07602629959682783, 0.0779798214381413, 0.0, 0.05511152480747473, 0.1594166700195956, 0.14482613363713087, 0.5354214392980579, 0.9999999999999802, -1.0000005011054218, -0.9999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15435133126162043, 0.09210302098345298, 0.0639842147147435, -0.2416390673235393, -0.07021233847969158, -0.09173856572439221, 0.18065926905806198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0645244556329731, -0.014033754263467138, -0.007776097294241945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20836002974325324, 0.220580738424814, 0.8268497555052778, 0.0, -0.22776557192265945, -0.3174532650407923, -2.453736299899618, -1.0373651970028064, -0.8894149872447474, -0.8505094531076175, -2.562240832903147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5471275253317054, 0.6760967766719892, 1.419812030834297, -1.1488903227386842, -2.2406049125982195, -0.5889740129652162, 1.3007316657284402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2722569064454363, -0.43861191622931434, 0.02786773997931919]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880220122, 0.06514585818534588, 0.06874550805727751, 0.0, 0.10813205878844129, 0.1692218220828084, 0.03147228511085087, 0.6356637374272478, 0.9999999999998577, -1.0000005011411581, -1.0000000000124751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12162464487938615, 0.08019354859486817, 0.04725960702883106, -0.18024036119671732, -0.020931945090991222, -0.067729607692168, 0.1153476135771768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0528930550313747, -0.011054583570775578, -0.006802560131555889]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20890236731276418, 0.22331947192858484, 0.8299126941352141, 0.0, -0.21963384384261464, -0.3087547466632327, -2.457943386608462, -1.0008838400568223, -0.8394149872448201, -0.9005094781628663, -2.6122408329031273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519614181536695, 0.6795011419163419, 1.4215954927811791, -1.1557017087656305, -2.2403813722918278, -0.5914575442271724, 1.3044574108583427, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2744018531044412, -0.43904510173632294, 0.027557092385001702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010846751390218888, 0.05477467007541689, 0.06125877259872422, 0.0, 0.16263456160089598, 0.17397036755119216, -0.08414173417687226, 0.7296271389196829, 0.9999999999985463, -1.0000005011049757, -0.9999999999996081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0966778564392827, 0.06808730488705383, 0.035669238937643385, -0.13622772053892793, 0.004470806127835566, -0.04967062523912445, 0.07451490259804805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04289893318009702, -0.008663710140172066, -0.006212951886349732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924014300176616, 0.22558907526272806, 0.832516028451838, 0.0, -0.2088784119570595, -0.29988190631457157, -2.4679101480898793, -0.9600673236121545, -0.7894149872448852, -0.9505095032181211, -2.6622408329031124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558093246584372, 0.6822883123648255, 1.4229550903934498, -1.1609092407972317, -2.239690744526241, -0.5932717611957165, 1.3069797006688277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2761077168336417, -0.4393805271434575, 0.027263123491609406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006755513780039767, 0.04539206668286434, 0.0520666863324798, 0.0, 0.2151086377111026, 0.17745680697322283, -0.19933522962834466, 0.8163303288933546, 0.9999999999986986, -1.0000005011050965, -0.9999999999997062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07695813009535564, 0.05574340896967034, 0.027191952245415554, -0.10415064063202173, 0.01381255531173049, -0.03628433937087952, 0.050445796209702576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03411727458400836, -0.006708508142691235, -0.00587937786784593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932616161286308, 0.22744569050308344, 0.834826254295132, 0.0, -0.19579154426530776, -0.2908321419076912, -2.483469466430795, -0.9154141104565975, -0.739414987245167, -1.000509528273315, -2.712240832902818, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5588604330257323, 0.6844420565639199, 1.4239877225131137, -1.164969402369256, -2.239103536428652, -0.5946108692553929, 1.3089117387084355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2774277204317501, -0.4396341865431943, 0.02698265280572664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017203722219384116, 0.037132304807107774, 0.04620451686587979, 0.0, 0.2617373538350347, 0.18099528813760773, -0.3111863668183114, 0.8930642631111416, 0.9999999999943651, -1.0000005011038793, -0.9999999999941117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06102216734590005, 0.04307488398188946, 0.020652642393276476, -0.08120323144048687, 0.011744161951782052, -0.0267821611935287, 0.03864076079215309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026400071962168384, -0.005073187994736585, -0.005609413717655272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20933056938417735, 0.228938372466004, 0.8366688095526873, 0.0, -0.18217453223378702, -0.2814297402669101, -2.500887728282853, -0.870306111972243, -0.6931649872445551, -1.0491367343047637, -2.7584908329056668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5612536679267874, 0.6860483734709207, 1.4247430436927009, -1.168155308410831, -2.2387880875171633, -0.595590809248792, 1.3105357742296277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.278425135211993, -0.4398232632180623, 0.02672449963672147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.815542628558227e-05, 0.029853639258411103, 0.03685110515110657, 0.0, 0.2723402406304148, 0.18804803281562182, -0.3483652370411696, 0.9021599696870902, 0.9250000000122373, -0.9725441206289748, -0.9250000000569817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.047864698021103345, 0.032126338140017016, 0.01510642359174525, -0.06371812083149866, 0.006308978229771619, -0.0195987998679837, 0.032480710423844435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01994829560486069, -0.003781533497360421, -0.005163063380103397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932884115003778, 0.23011316550761649, 0.8381225057841533, 0.0, -0.1693528861440909, -0.27255979656795276, -2.518771328661458, -0.8284933281084138, -0.654414987213272, -1.0926411213852207, -2.7972408329494938, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631048045192583, 0.687252723211333, 1.4252317019514358, -1.1706501793212163, -2.2387012797308765, -0.5962762215751217, 1.3119750197448723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2791678862882272, -0.4399629161625189, 0.02649902814853944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.456468279174673e-05, 0.023495860832250186, 0.029073924629319937, 0.0, 0.2564329217939224, 0.17739887397914625, -0.35767200757209533, 0.836255677276582, 0.7750000006256631, -0.8700877416091413, -0.7750000008765425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0370227318494159, 0.024086994808245304, 0.009773165174699198, -0.04989741820770852, 0.001736155725733773, -0.013708246526593065, 0.0287849103048912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014855021524681263, -0.002793058889132289, -0.004509429763640606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932788289126003, 0.23101798821627914, 0.8391026888525631, 0.0, -0.15818501666305668, -0.26483319096932273, -2.5359587088692606, -0.7937257558710759, -0.6250680896836437, -1.1277424437604398, -2.8260974817958933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564512246192544, 0.6882110000970189, 1.4254194277410992, -1.172594032649529, -2.2387410078804804, -0.5966909778580843, 1.3133183993931452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2797159619590375, -0.4400654543891233, 0.026310697312253172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9165175554961214e-05, 0.018096454173253205, 0.0196036613681976, 0.0, 0.22335738962068408, 0.15453211197260083, -0.34374760415605077, 0.6953514447467598, 0.5869379505925651, -0.7020264475043795, -0.5771329769279895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02814883346571545, 0.01916553771371786, 0.0037545157932705603, -0.0388770665662527, -0.0007945629920774432, -0.008295125659251692, 0.02686759296545663, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010961513416206263, -0.002050764532088299, -0.003766616725725312]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209326967977962, 0.23170153162576393, 0.8397180196333647, 0.0, -0.14905358832275853, -0.25852071302748747, -2.5515493738647765, -0.7668782370757354, -0.6040801048930344, -1.1540211237438165, -2.8459557199745085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5655600193084604, 0.6890612677378614, 1.4252544891234067, -1.1741005473302502, -2.2388086006669075, -0.5968383061702716, 1.3146469020890874, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2801180324457406, -0.44014044847222306, 0.0261579683581745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.829826596068004e-05, 0.013670868189695779, 0.01230661561603071, 0.0, 0.1826285668059628, 0.12624955883670494, -0.31181329991032136, 0.5369503759068073, 0.4197596958121855, -0.5255735996675329, -0.397164763572303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02095546231832748, 0.01700535281684921, -0.003298772353851691, -0.030130293614425267, -0.001351855728544265, -0.002946566243744073, 0.02657005391884625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008041409734061587, -0.001499881661994671, -0.003054579081573399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093259380204269, 0.23220977394247713, 0.8400854275917896, 0.0, -0.14197612515217423, -0.2536482214865198, -2.564986775067951, -0.7473180611300209, -0.5895743811466219, -1.1724845390217244, -2.858801959448876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663198497966578, 0.6899025586887599, 1.424707731640309, -1.1752628476276366, -2.2388339068055143, -0.5967248652769541, 1.3160195454508985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2804118817113503, -0.440195155718598, 0.02603609857431136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0599150701613132e-05, 0.010164846334263896, 0.007348159168498353, 0.0, 0.14154926341168605, 0.09744983081935366, -0.2687480240634872, 0.39120351891429056, 0.29011447492825215, -0.36926830555815804, -0.2569247894873526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015196609763948796, 0.016825819017970946, -0.010935149661955473, -0.023246005947725922, -0.0005061227721400406, 0.0022688178663480153, 0.027452867236222957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005876985312195564, -0.0010941449274996567, -0.002437395677262807]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932478082939882, 0.23258303632233118, 0.8403182736213654, 0.0, -0.13673976621698192, -0.25009048605629397, -2.5760634691920976, -0.7338035035911181, -0.5797348308047431, -1.1846861181123198, -2.8666674562661716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5668496073376568, 0.690808718640863, 1.423754695329556, -1.176157114405769, -2.2387707525162717, -0.5963535131611295, 1.3174903452101003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2806261112024597, -0.4402349952513054, 0.02593967049718884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.314382056186457e-05, 0.007465247597081032, 0.004656920591515499, 0.0, 0.10472717870384635, 0.07115470860451609, -0.22153388248293018, 0.2702911507780543, 0.19679100683757533, -0.24403158181190557, -0.1573099363459114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010595150819977833, 0.018123199042062353, -0.019060726215059675, -0.017885335562650054, 0.001263085784849995, 0.007427042316493482, 0.02941599518403489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004284589822188753, -0.0007967906541475968, -0.00192856154245041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932339724114024, 0.2328547249447787, 0.8404844977878413, 0.0, -0.13302175330080057, -0.2476419798401231, -2.5848497946527678, -0.7249578381638652, -0.5731054595349542, -1.1922294288601571, -2.8712263686173403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5671915980120815, 0.6918542953571599, 1.4223367074189475, -1.1768459124727995, -2.2385826009709686, -0.5957045777303653, 1.3191371386595554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2807820429389665, -0.440263974177527, 0.025863793622816735]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.76717651716686e-05, 0.0054337724489508295, 0.003324483329518648, 0.0, 0.0743602583236267, 0.048970124323417547, -0.17572650921339994, 0.17691330854505882, 0.13258742539577828, -0.1508662149567478, -0.09117824702337414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006839813488494819, 0.020911534325937276, -0.028359758212169114, -0.013775961340610206, 0.0037630309060581193, 0.012978708615283687, 0.03293586898910326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003118634730133735, -0.000579578524432414, -0.001517537487442093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20932160909258068, 0.2330513790842077, 0.840695975766972, 0.0, -0.1304781107382692, -0.24608019902554626, -2.5915906810501066, -0.7195101586413297, -0.5686273915797048, -1.1965227031409893, -2.873712065986655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5673716881041702, 0.6931383151733975, 1.420324885976035, -1.1773812592468422, -2.2382285951112917, -0.5947182660780783, 1.321087474954143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2808954222641762, -0.44028503700835714, 0.025804395699238862]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.576297119099514e-05, 0.003933082788579588, 0.004229559582612759, 0.0, 0.05087285125062718, 0.031235616291536917, -0.1348177279467748, 0.1089535904507085, 0.08956135910498746, -0.08586548561664105, -0.04971394738629807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003601801841772482, 0.02568039632475126, -0.0402364288582501, -0.01070693548085521, 0.007080117193534543, 0.019726233045739956, 0.03900672589175434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022675865041934746, -0.000421256616602761, -0.0011879584715574895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931920301568352, 0.2331934293386948, 0.8408585872212334, 0.0, -0.12879737342821995, -0.245203650165338, -2.5966091754426435, -0.7164018528654865, -0.5655782245461377, -1.198687194199383, -2.8749662449540203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.56739952898861, 0.6947976467255678, 1.417501623225868, -1.1778071478137369, -2.2376551247952263, -0.5932859412217962, 1.3235316849239758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.280977805635369, -0.4403003384623748, 0.025758135598587646]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.812153794340694e-05, 0.0028410050897417867, 0.0032522290852278627, 0.0, 0.03361474620098516, 0.017530977204165292, -0.10036988785073828, 0.0621661155168642, 0.06098334067134223, -0.04328982116787521, -0.02508357934730481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005568176887978771, 0.033186631043404066, -0.056465255003339654, -0.008517771337891071, 0.011469406321307846, 0.02864649712564206, 0.04888419939665492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016476674238530644, -0.0003060290803538771, -0.0009252020130243051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931618104453162, 0.23329626311703922, 0.8409724071782145, 0.0, -0.12772312341066705, -0.24481395712687198, -2.6002446659971485, -0.7148146095129365, -0.5634795661829842, -1.199550618643628, -2.875531087473784, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5672778537988058, 0.6969542188524047, 1.4136642286778873, -1.1781593437099984, -2.2368185258139257, -0.5913055409781842, 1.3266454613493943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810376429208725, -0.44031145120516274, 0.02572219668437234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0439423038208124e-05, 0.002056675566888427, 0.002276399139622121, 0.0, 0.021485000351057923, 0.007793860769319941, -0.07270981109009911, 0.03174486705099942, 0.041973167263069225, -0.01726848888489693, -0.011296850395268064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024335037960834314, 0.04313144253673796, -0.07674789095961343, -0.007043917925231801, 0.016731979626013978, 0.03960800487223917, 0.06227552850837193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011967457100707489, -0.00022225485575790908, -0.0007187782843061262]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093132596300379, 0.2333713576137685, 0.8411024824889938, 0.0, -0.12705684411839407, -0.2447149090405895, -2.602818979415272, -0.7141544056546724, -0.5620128669998177, -1.199683608494942, -2.8757399307150244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5670300950976542, 0.6995436439667067, 1.4089507589655348, -1.1784599753817526, -2.2357609555553686, -0.5888537791612296, 1.3303470237452841, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2810810937432404, -0.4403195204187482, 0.0256940742681744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.842828987430867e-05, 0.0015018899345859969, 0.0026015062155844244, 0.0, 0.013325585845459686, 0.00198096172564936, -0.0514862683624715, 0.013204077165283132, 0.029333983663330492, -0.002659797026282086, -0.004176864824815902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004955174023030489, 0.05178850228603931, -0.09426939424704964, -0.0060126334350839375, 0.021151405171141162, 0.04903523633909185, 0.07403124791779794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008690164473574144, -0.00016138427170990318, -0.0005624483239587907]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20931107145574457, 0.23342725960843494, 0.8412299048084414, 0.0, -0.1266536488275151, -0.24475560750623362, -2.6046089182401073, -0.71401434648281, -0.56096890190329, -1.1994554876513186, -2.875785908046203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5667027024736216, 0.7023252529122656, 1.4038254173463194, -1.1787187226710483, -2.234602608355407, -0.5861785294179096, 1.334307758548752, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811126383451363, -0.44032537855362475, 0.02567146062408601]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3763485867001316e-05, 0.001118039893328548, 0.002548446388953234, 0.0, 0.008063905817579597, -0.0008139693128823918, -0.035798776496701455, 0.002801183437245544, 0.020879301930553273, 0.004562416872467299, -0.0009195466235717882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006547852480650781, 0.05563217891117837, -0.10250683238430679, -0.005174945785914244, 0.023166943999231908, 0.053504994866400785, 0.07921469606935587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006308920379176483, -0.00011716269753029164, -0.0004522728817677998]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093095357777038, 0.23347030733254687, 0.8413333933949931, 0.0, -0.12641317592168402, -0.2448425633689893, -2.6058359713905936, -0.7141318406218842, -0.5602121250904676, -1.1990895838369133, -2.8757726831399966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5663405076834858, 0.7050641520890193, 1.398739313522182, -1.1789408532348258, -2.23345759570976, -0.5835200154982266, 1.3382051322199189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281135535361113, -0.44032963089928073, 0.02565226245036766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0713560815450024e-05, 0.0008609544822384934, 0.002069771731034684, 0.0, 0.00480945811662164, -0.001739117255113497, -0.024541063009727, -0.0023498827814825117, 0.015135536256447077, 0.007318076288105374, 0.0002644981241333316, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007243895802718277, 0.0547779835350745, -0.10172207648274745, -0.004442611275548488, 0.022900252912939713, 0.05317027839365999, 0.07794747342334042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00045794031953013753, -8.504691312025128e-05, -0.0003839634743670364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093083863401872, 0.23350509051701604, 0.8413646252815028, 0.0, -0.12626914210007656, -0.2449286003817336, -2.606668321483937, -0.7143485456589677, -0.5596551025701284, -1.1987097357395833, -2.875750105900365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.565974677304888, 0.7076153731996925, 1.393973547800686, -1.1791313171364814, -2.2323958449919328, -0.5810281181019368, 1.3418399661678189, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811521534988537, -0.4403327173759992, 0.025634732928234014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2988750332211854e-05, 0.0006956636893833827, 0.0006246377301939144, 0.0, 0.0028806764321491277, -0.001720740254886341, -0.016647001866865102, -0.004334100741669422, 0.011140450406784304, 0.007596961946602426, 0.0004515447926331461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007316607571954944, 0.051024422213464565, -0.09531531442991814, -0.0038092780331124413, 0.021235014356552527, 0.049837947925796156, 0.07269667895799907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000332362754814236, -6.172953436950594e-05, -0.0003505904426728646]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093074345213319, 0.23353476076684745, 0.8413867836530399, 0.0, -0.12617978319897336, -0.2449968772106131, -2.6072287718098015, -0.714577054554873, -0.559240923775451, -1.1983759739779265, -2.8757378530791198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5656226078371608, 0.7099212289243557, 1.3896443520739996, -1.1792953816447265, -2.2314451351174696, -0.5787651709376522, 1.345133091682759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811642136478232, -0.4403349575490008, 0.02561761009628726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9036377105635495e-05, 0.0005934049966281783, 0.000443167430740441, 0.0, 0.0017871780220643492, -0.0013655365775899187, -0.011209006517291896, -0.0045701779181072716, 0.008283575893547793, 0.006675235233133516, 0.00024505642489917266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007041389354544094, 0.0461171144932648, -0.08658391453372918, -0.003281290164901044, 0.01901419748926482, 0.045258943285691154, 0.06586251029880365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002412029793911311, -4.480346003190916e-05, -0.0003424566389351333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930656804015205, 0.23356129882315158, 0.8413701620718517, 0.0, -0.12612001251429453, -0.24504422559840863, -2.607604653229138, -0.7147753717799153, -0.5589313399745239, -1.1981100556589004, -2.8757403173484275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5652913274534491, 0.7119836069201142, 1.385754835100013, -1.1794382729338133, -2.2306047665306026, -0.5767333927952603, 1.3480873651022844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281172965508997, -0.440336583464336, 0.025600174956988263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7329623597052658e-05, 0.0005307611260826335, -0.00033243162376509416, 0.0, 0.0011954136935767837, -0.0009469677559102456, -0.007517628386735238, -0.003966344500848236, 0.006191676018541968, 0.005318366380524382, -4.928538615713067e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006625607674232605, 0.04124755991517044, -0.077790339479733, -0.0028578257817353727, 0.01680737173734279, 0.040635562847839264, 0.059085468390505325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017503722347327722, -3.2518306703991607e-05, -0.00034870278597991196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930571697289413, 0.23358578927657528, 0.8413301762265463, 0.0, -0.1260756570374459, -0.24507464315984007, -2.6078564227091303, -0.7149285725174833, -0.5586999459037346, -1.1979128602868756, -2.8757551078398103, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5649807970422012, 0.7138384212270887, 1.3822426312907556, -1.1795648525660125, -2.229858153091005, -0.5749001873910619, 1.3507527457911412, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811793163762348, -0.4403377635721811, 0.02558220222703967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.702134515844646e-05, 0.0004898090684743421, -0.000799716906108358, 0.0, 0.0008871095369727812, -0.0006083512286286783, -0.0050353895998431234, -0.0030640147513591332, 0.004627881415787143, 0.003943907440495759, -0.0002958098276514625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006210608224958936, 0.03709628613948982, -0.07024407618514973, -0.0025315926439827795, 0.014932268791951654, 0.036664108083967424, 0.05330761377713449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001270173447574517, -2.360215690101155e-05, -0.00035945459897185014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093048289687132, 0.23360869936906162, 0.8412687929570802, 0.0, -0.12603921694238535, -0.24509250940629626, -2.6080254533918, -0.7150364279503766, -0.5585275030750284, -1.197775332567186, -2.8757778356522703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5646863279103231, 0.7155384116720686, 1.3790120388227531, -1.1796795240936315, -2.229181352658341, -0.5732152525497688, 1.3532028827256402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811839248259298, -0.44033862013547376, 0.02556383189244487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7760083618687023e-05, 0.0004582018497266741, -0.0012276653893209275, 0.0, 0.0007288019012108107, -0.00035732492912375895, -0.0033806136533930773, -0.0021571086578656457, 0.00344885657412393, 0.002750554393789047, -0.00045455624919883757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005889382637561511, 0.03399980889959524, -0.06461184936005213, -0.002293430552380959, 0.013536008653279674, 0.033698696825861935, 0.04900273868997617, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.216899389749787e-05, -1.713126585362548e-05, -0.0003674066918959724]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2093038618960449, 0.23363013314251516, 0.8412021612596656, 0.0, -0.12600711441060672, -0.24510213748602921, -2.6081395104400515, -0.7151055316030717, -0.5583997009662818, -1.1976850765639133, -2.8758042432433197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5644002197876236, 0.7171431776920782, 1.3759527757440497, -1.1797862949051272, -2.228548011012204, -0.571620595983273, 1.3555215766006095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811872688471595, -0.44033924188535506, 0.02554541065054421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9341453365596536e-05, 0.00042867546907065216, -0.0013326339482925987, 0.0, 0.0006420506355724892, -0.00019256159465898116, -0.0022811409650317937, -0.00138207305390175, 0.0025560421749317797, 0.0018051200654563017, -0.0005281518209890811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005722162453991348, 0.03209532040019296, -0.06118526157406873, -0.002135416229915026, 0.01266683292273626, 0.03189313132991613, 0.04637387749938665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.688042459223199e-05, -1.243499762654782e-05, -0.0003684248380132118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930277955712914, 0.23365003479002197, 0.841142355991144, 0.0, -0.12597786919762735, -0.2451067040304369, -2.608217050437533, -0.7151446630045013, -0.5583056253473476, -1.1976298647099906, -2.875831082964572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.564112916098539, 0.718713631945134, 1.3729505868607748, -1.1798888818872901, -2.227932048589906, -0.5700562098209019, 1.3577952065121577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811896953317157, -0.44033969321508903, 0.025527345973332755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1646778315541915e-05, 0.0003980329501363525, -0.0011961053704323751, 0.0, 0.0005849042595874469, -9.133088815418519e-05, -0.0015507999496303946, -0.0007826280285938342, 0.001881512378682125, 0.0011042370784556759, -0.0005367944250410268, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005746073781690693, 0.03140908506111582, -0.06004377766550069, -0.002051739643259896, 0.012319248445959628, 0.03128772324742158, 0.04547259823096527, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.852969112507101e-05, -9.026594679226684e-06, -0.0003612935442291047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930155521577734, 0.23366833009605906, 0.841094961488964, 0.0, -0.12595099681958702, -0.24510830575426978, -2.608270244854492, -0.7151623127094201, -0.5582368711318413, -1.1975992576938694, -2.8758562656040474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5638140257817605, 0.7203079847006745, 1.369895085563649, -1.1799907533268417, -2.227309439495549, -0.5684642412888999, 1.360107104727664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281191456016363, -0.440340020855898, 0.02550999675993775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4486827036107972e-05, 0.0003659061207415492, -0.0009478900435981089, 0.0, 0.0005374475608064811, -3.203447665762285e-05, -0.0010638883391749958, -0.0003529940983749414, 0.0013750843101261174, 0.0006121403224216934, -0.0005036527895113157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0059778063355689585, 0.03188705511080903, -0.061110025942516716, -0.0020374287910290695, 0.012452181887139795, 0.03183937064003895, 0.046237964310127326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.521369294633575e-05, -6.552816180006944e-06, -0.0003469842679000255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20930018081720683, 0.23368500968621683, 0.8410609628302775, 0.0, -0.125926388040214, -0.24510836130916702, -2.6083070567133824, -0.7151655660674753, -0.5581869933210988, -1.1975851125906631, -2.875878686583119, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.563493591706401, 0.7219767244682881, 1.3666896025534783, -1.18009501357608, -2.226660223367573, -0.5667941725697253, 1.3625303249008929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811927335841258, -0.44034025872312105, 0.025493606580810426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7487971409974618e-05, 0.00033359180315545664, -0.0006799731737292077, 0.0, 0.0004921755874602552, -1.1110979447739581e-06, -0.0007362371778133676, -6.506716110269497e-05, 0.0009975562148499739, 0.0002829020641273661, -0.0004484195814282261, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006408681507189875, 0.033374795352271634, -0.06410966020341216, -0.002085204984763627, 0.012984322559509329, 0.033401374383493235, 0.04846440346457676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5551355253924737e-05, -4.757344460149128e-06, -0.00032780358254653704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929867884331144, 0.2337001652461733, 0.8410398000736337, 0.0, -0.1259039816055719, -0.24510771241587442, -2.608332691702937, -0.7151597804444204, -0.5581510785125475, -1.1975814871566215, -2.875897971265622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5631438560880656, 0.7237552448328658, 1.3632656213457324, -1.180204082582403, -2.225971326545408, -0.5650103653121799, 1.365116883684307, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281193660600752, -0.4403404314317798, 0.025478275340491713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0039477908181726e-05, 0.00030311119912921383, -0.00042325513287815654, 0.0, 0.0004481286928418511, 1.2977865851722881e-05, -0.0005126997910942445, 0.00011571246109806768, 0.0007182961710260918, 7.250868083288599e-05, -0.0003856936500588376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006994712366707671, 0.03557040729155468, -0.0684796241549184, -0.002181380126459792, 0.013777936443305007, 0.03567614515090822, 0.051731175668285306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8540332523773255e-05, -3.4541731755088937e-06, -0.00030662480637424854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092971066962968, 0.23371399345663038, 0.8410315183894932, 0.0, -0.12588360240755486, -0.24510639356105499, -2.6083506489147124, -0.7151486795474746, -0.5581253344249605, -1.1975842653907938, -2.875914255468676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5627612462555937, 0.7256557504430601, 1.3595986979929144, -1.180319265356326, -2.225239514424052, -0.5631003451914094, 1.3678858125913502, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811943332514166, -0.44034055684806567, 0.025463959270514265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.144294029240099e-05, 0.000276564209141811, -0.0001656336828101733, 0.0, 0.00040758396034068956, 2.6377096388984554e-05, -0.00035914423550959505, 0.00022201793891585123, 0.0005148817517415824, -5.55646834436625e-05, -0.0003256840610755665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007652196649439385, 0.03801011220388612, -0.07333846705635926, -0.0023036554784603078, 0.014636242427122956, 0.03820040241540994, 0.055378578140861626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3453013296197203e-05, -2.508325717375635e-06, -0.000286321399548956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929554240381656, 0.23372677844954556, 0.8410309175430131, 0.0, -0.12586495439624742, -0.24510451324511714, -2.608363229770946, -0.715134626654381, -0.5581069586289285, -1.1975907620666153, -2.875927934791054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5623475532949853, 0.7276636348005215, 1.355715874881219, -1.1804404942998248, -2.2244724050053057, -0.5610786053208363, 1.3708175312484436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811948213291113, -0.4403406479415184, 0.025450491256586823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.128584960460454e-05, 0.0002556998583034697, -1.2016929603494417e-05, 0.0, 0.00037296022614867746, 3.7606318756892435e-05, -0.0002516171246731703, 0.00028105786187182383, 0.00036751592064140806, -0.00012993351642981148, -0.00027358644755902454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008273859212166279, 0.040157687149229564, -0.07765646223390661, -0.002424578869977944, 0.015342188374920577, 0.040434797411462116, 0.05863437314186746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.7615538926286e-06, -1.8218690544552197e-06, -0.00026936027854881727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209294053398125, 0.23373885868698788, 0.8410335748135789, 0.0, -0.12584763873052435, -0.24510210272088584, -2.6083719747967073, -0.7151189612611795, -0.558093895091273, -1.197599327374643, -2.8759395243000445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.561909294418856, 0.7297428023174414, 1.3516858663276905, -1.1805665121830295, -2.2236858833252864, -0.5589813906049087, 1.3738611251068245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195175474863, -0.4403407141278588, 0.025437617055845567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9780113831033408e-05, 0.00024160474884648138, 5.314541131553214e-05, 0.0, 0.00034631331446133593, 4.821048462616556e-05, -0.00017490051522889565, 0.00031330786403151347, 0.0002612707531080156, -0.00017130616055594606, -0.00023179017981265172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008765177522586246, 0.041583350338396, -0.080600171070569, -0.0025203576640966487, 0.01573043360038643, 0.04194429431855181, 0.060871877167615614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.082915030469657e-06, -1.3237268083657956e-06, -0.0002574840148251435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929267402278356, 0.23375058401338336, 0.8410368464974026, 0.0, -0.1258312071972287, -0.24509912738008263, -2.608377934289759, -0.7151023257509268, -0.5580846474444042, -1.1976090235471704, -2.8759495580003933, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5614554637779701, 0.7318480731070073, 1.3475954379145076, -1.180695442257408, -2.222898841005886, -0.5568542851154894, 1.3769520004783893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281195432432936, -0.4403407622430411, 0.0254250422090177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7587506829197594e-05, 0.00023450652790980332, 6.543367647447401e-05, 0.0, 0.0003286306659130794, 5.9506816063916064e-05, -0.00011918986102826232, 0.0003327102050529317, 0.00018495293737567448, -0.00019392345054728718, -0.00020067400697726577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009076612817717112, 0.04210541579131824, -0.08180856826365653, -0.0025786014875700805, 0.015740846388008323, 0.04254210978838492, 0.06181750743129771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.139161459139613e-06, -9.623036454801814e-07, -0.0002514969365572958]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929140492578405, 0.23376226979364867, 0.8410366838434314, 0.0, -0.1258152304891205, -0.24509561131307556, -2.6083818247290775, -0.7150849474311873, -0.5580781479145169, -1.1976193739597198, -2.875958516984219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5609949280913906, 0.7339380409830827, 1.3435246690204103, -1.180825424830752, -2.22212797938815, -0.5547392558008276, 1.380030415191857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811956188667661, -0.44034079724974484, 0.025412482780436875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.538193999048871e-05, 0.00023371560530605358, -3.2530794247178512e-06, 0.0, 0.0003195341621644069, 7.032134014142217e-05, -7.78087863706458e-05, 0.0003475663947893592, 0.00012999059774529547, -0.00020700825098755003, -0.0001791796765088974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009210713731589496, 0.04179935752150859, -0.08141537788194497, -0.002599651466876533, 0.015417232354719007, 0.042300586293236575, 0.06156829426935478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7286766039075745e-06, -7.001340752734186e-07, -0.0002511885716165004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20929022605121414, 0.23377415724123438, 0.8410354043712006, 0.0, -0.12579936807991787, -0.245091880159618, -2.6083840897483874, -0.7150668577609607, -0.55807369540577, -1.197630180755887, -2.8759667720472466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5605345511860355, 0.7359832897091294, 1.3395309574510912, -1.1809550542929945, -2.2213846728043958, -0.552666304106167, 1.3830534858866987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811957541294259, -0.44034082274968717, 0.025399710587983983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3577491398254557e-05, 0.000237748951714319, -2.5589444615739494e-05, 0.0, 0.0003172481840523629, 7.462306915097544e-05, -4.5300386200787526e-05, 0.00036179340453244813, 8.905017493845235e-05, -0.00021613592333979306, -0.0001651012605533446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009207538107104077, 0.040904974520935396, -0.07987423138638482, -0.002592589244853728, 0.01486613167508669, 0.04145903389321194, 0.06046141389683468, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7052531964609267e-06, -5.099988465446153e-07, -0.00025544384905784367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092891087142332, 0.2337863889700238, 0.8410360082603573, 0.0, -0.12578335826999573, -0.24508741702397602, -2.6083851827022246, -0.715048050955997, -0.5580706532528865, -1.1976413418152407, -2.8759746453116835, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5600783519138955, 0.7379690563802977, 1.3356436247608887, -1.1810835571516842, -2.2206741594981336, -0.5506506833394155, 1.3859992698826669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811958522663727, -0.4403408413557531, 0.025386583483815072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2346739618580776e-05, 0.0002446345757885683, 1.207778313352136e-05, 0.0, 0.0003201961984425355, 8.926271283950733e-05, -2.18590767437206e-05, 0.0003761360992743255, 6.084305766997865e-05, -0.00022322118707697718, -0.00015746528873960834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009123985442799153, 0.03971533342336723, -0.07774665380405146, -0.002570057173793344, 0.014210266125241882, 0.04031241533503041, 0.058915679919361294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9627389349568807e-06, -3.721213176678822e-07, -0.0002625420833782228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928802517115022, 0.23379900514934923, 0.8410349328638245, 0.0, -0.125767081482586, -0.24508231676848866, -2.6083853909718746, -0.7150285610661412, -0.5580686155401812, -1.1976528125791381, -2.8759823294466824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5596274722157201, 0.7398939844199924, 1.3318660572606382, -1.1812107802490412, -2.219996308616668, -0.5486940638167193, 1.3888652079976598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959234561143, -0.4403408549627982, 0.025373054806792944]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1670861659835338e-05, 0.00025232358650895104, -2.1507930657501184e-05, 0.0, 0.00032553574819482414, 0.00010200510974724494, -4.1653930017752455e-06, 0.0003897977971152688, 4.075425410771976e-05, -0.0002294152779486388, -0.0001536826999770408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00901759396351018, 0.038498560793894, -0.07555135000501167, -0.002544461947141193, 0.013557017629314352, 0.03913239045392443, 0.05731876229985881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4237948324154929e-06, -2.721409020453415e-07, -0.00027057354044257597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928695084797927, 0.2338119584573455, 0.8410321159752371, 0.0, -0.12575052771739645, -0.2450766126830368, -2.6083849522399776, -0.7150084945107471, -0.558067272264523, -1.1976645422434569, -2.875989934475641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5591806119876536, 0.7417669828489495, 1.3281815578917626, -1.181337083108363, -2.219347098584525, -0.5467876350123405, 1.3916637907816496, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811959750864783, -0.4403408649438677, 0.025359163293032172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.148646341928201e-05, 0.00025906615992544573, -5.6337771747108655e-05, 0.0, 0.00033107530379099525, 0.00011408170903712871, 8.774637939968811e-06, 0.0004013311078828809, 2.6865513162621074e-05, -0.00023459328637668916, -0.0001521005791680687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00893720456133019, 0.03745996857914207, -0.07368998737751273, -0.002526057186434127, 0.012984200642861312, 0.038128576087575396, 0.05597165567979601, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.032607281879432e-06, -1.9962139030758776e-07, -0.000277830275215461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928586632714155, 0.23382514213019298, 0.8410281279171928, 0.0, -0.1257337701212526, -0.245070380155813, -2.608384056205543, -0.7149880199197897, -0.5580663940860073, -1.1976764629807153, -2.875997503976249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5587346767482065, 0.7436035660074914, 1.3245602911608023, -1.1814631941859728, -2.218720221675862, -0.5449157679568635, 1.3944173987513842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196012518856, -0.4403408722934107, 0.02534500869895688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.169041675451192e-05, 0.0002636734569495852, -7.976116088462764e-05, 0.0, 0.000335151922876737, 0.00012465054447576959, 1.7920688690471714e-05, 0.0004094918191487047, 1.756357031465416e-05, -0.000238414745170206, -0.0001513900121642371, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008918704788940066, 0.036731663170838695, -0.07242533461920501, -0.0025222215521966854, 0.012537538173262038, 0.03743734110954007, 0.05507215939469092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.486475535157642e-07, -1.4699085936223667e-07, -0.0002830918815058249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928475816571282, 0.23383842289331924, 0.8410237772334282, 0.0, -0.12571693075540719, -0.24506380536438543, -2.6083828393500443, -0.7149673371095181, -0.5580658266392596, -1.1976884972615673, -2.876005033477747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5582855023094606, 0.7454223285409701, 1.320966063736913, -1.1815900579661462, -2.2181085407857957, -0.5430595762208513, 1.397153250655472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960396432749, -0.4403408777315123, 0.025330721100861507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2163228574663497e-05, 0.00026561526252498984, -8.701367529104261e-05, 0.0, 0.00033678731690860153, 0.00013149582855127422, 2.4337109971788726e-05, 0.0004136562054321969, 1.134893495327528e-05, -0.00024068561703942797, -0.00015059002995320076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008983488774919038, 0.03637525066957294, -0.07188454847778691, -0.002537275603468942, 0.012233617801327062, 0.03712383472024385, 0.05471703808175564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.424883800536471e-07, -1.0876203281328585e-07, -0.00028575196190749576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928361962021858, 0.233851671975343, 0.8410200329115725, 0.0, -0.12570014481308564, -0.24505718307812926, -2.608381384654628, -0.714946639975147, -0.5580654824178932, -1.19770057133443, -2.87601249037681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5578285987012843, 0.7472417640137283, 1.317362530804653, -1.1817186799421848, -2.217505315958886, -0.5412001596216567, 1.3998987606241629, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960592890377, -0.4403408817798127, 0.025316430660225216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2770909884935263e-05, 0.00026498164047559765, -7.488643711521706e-05, 0.0, 0.0003357188464307567, 0.00013244572512316, 2.909390832013645e-05, 0.0004139426874227912, 6.884427328987225e-06, -0.0002414814572513849, -0.00014913798126398273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00913807216352482, 0.036388709455163676, -0.07207065864519666, -0.0025724395207737606, 0.012064496538201786, 0.037188331983892126, 0.054910199373815416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9291525549217034e-07, -8.096600676193637e-08, -0.0002858088127258603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928245108894183, 0.23386478804542368, 0.8410174650185066, 0.0, -0.125683527186835, -0.24505075403237622, -2.6083797446478076, -0.7149260860247941, -0.55806531127179, -1.1977126232930966, -2.876019838179076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.557359873636548, 0.7490775025074466, 1.31371866460612, -1.181849972036363, -2.216905181731572, -0.5393214456994128, 1.402677423283606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960735113084, -0.4403408848165188, 0.025302244240532755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3370625534722936e-05, 0.0002623214016136919, -5.135786131682776e-05, 0.0, 0.000332352525012723, 0.00012858091506071477, 3.280013641051642e-05, 0.0004110790070570588, 3.4229220628398828e-06, -0.000241039173333795, -0.0001469560453180969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00937450129472489, 0.03671476987436629, -0.07287732397065966, -0.0026258418835635637, 0.01200268454627503, 0.03757427844487955, 0.05557325318886109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.844454131390296e-07, -6.07341217716913e-08, -0.0002837283938491854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928125975254663, 0.2338777108130339, 0.8410158630732162, 0.0, -0.1256671439747314, -0.24504447219903447, -2.608377986471098, -0.7149057769458779, -0.5580652503388998, -1.1977246030067663, -2.876027063526532, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5568762726491504, 0.7509401348519842, 1.3100131355736913, -1.181984612037136, -2.2163048343526506, -0.5374124503813171, 1.4055054932543025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196083799387, -0.44034088711628594, 0.02528823051558007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3826727904008558e-05, 0.0002584553522042788, -3.203890580907234e-05, 0.0, 0.000327664242072245, 0.00012563666683489575, 3.516353418872416e-05, 0.0004061815783248623, 1.2186578059567068e-06, -0.0002395942733952444, -0.00014450694912265818, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009672019747952372, 0.03725264689075036, -0.07411058064857856, -0.002692800015456993, 0.012006947578431529, 0.0381799063619132, 0.056561399413934295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0576157060140677e-07, -4.5995343059355314e-08, -0.0002802744990537038]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20928005822107565, 0.23389042542853103, 0.8410148861598132, 0.0, -0.1256510139598323, -0.24503832647630847, -2.608376152939475, -0.7148857485231586, -0.5580652620672273, -1.1977364858353845, -2.8760341665429783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5563762310020239, 0.7528339407988729, 1.3062369547787211, -1.182122942229882, -2.2157033441213, -0.535468624793998, 1.4083899574042051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960912332747, -0.4403408888790849, 0.02527441387595175]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.4030629419687853e-05, 0.0002542923099423783, -1.953826805875379e-05, 0.0, 0.00032260029798148945, 0.00012291445452000235, 3.667063245698228e-05, 0.00040056845438629304, -2.3456654998743283e-07, -0.0002376565723656537, -0.00014206032892117383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010000832942529793, 0.037876118937773505, -0.07552361589940103, -0.002766603854918861, 0.012029804627013495, 0.038876511746381424, 0.057689282998053766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.486777525501345e-07, -3.525597893159262e-08, -0.00027633279256637983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927886130024168, 0.2339029581009885, 0.8410143843772253, 0.0, -0.12563511083264114, -0.2450323182141585, -2.6083742664359377, -0.7148659747237618, -0.5580653290243688, -1.1977482722593595, -2.876041161779588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5558598237937736, 0.7547568426705952, 1.3023937086428552, -1.182264935247827, -2.21510201780957, -0.5334919482142477, 1.4113283165359392, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960965966573, -0.4403408902509209, 0.025260777130170713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.393841667927272e-05, 0.0002506534491489933, -1.0035651758644546e-05, 0.0, 0.0003180625438231048, 0.00012016524299924724, 3.773007074423181e-05, 0.0003954759879352741, -1.339142829504216e-06, -0.0002357284794985124, -0.00013990473219042374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010328144165007061, 0.038458037434445515, -0.07686492271731701, -0.0028398603588998673, 0.012026526234592393, 0.039533531595005764, 0.05876718263468003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0726765329846376e-07, -2.7436719599043683e-08, -0.00027273491562077913]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092776824624636, 0.23391536552185, 0.8410144391534922, 0.0, -0.12561937333641351, -0.24502644928800751, -2.608372332749249, -0.714846381459219, -0.5580654492593156, -1.197759983980225, -2.8760480752640456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5553285643804892, 0.7567016476649344, 1.2984972245575668, -1.182410240711934, -2.2145038309831597, -0.5314896916689004, 1.4143103114192785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961004586885, -0.440340891338681, 0.025247270725072626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3576755561743843e-05, 0.0002481484172302796, 1.0955253381353154e-06, 0.0, 0.00031474992455246607, 0.00011737852301981131, 3.8673733772419264e-05, 0.0003918652908572367, -2.4046989356143726e-06, -0.00023423441731272078, -0.00013826968915586324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010625188265690203, 0.03889609988678383, -0.07792968170576704, -0.002906109282138934, 0.011963736528207015, 0.040045130906946655, 0.05963989766678648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.724062164925631e-08, -2.175520169768459e-08, -0.00027012810196172857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927653107197078, 0.23392772070120912, 0.84101540580586, 0.0, -0.12560372148059526, -0.2450207360536313, -2.608370340249683, -0.7148268663770398, -0.5580656368309801, -1.1977716584644167, -2.8760549373458373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5547849118132201, 0.7586582290391126, 1.2945673283683066, -1.1825582987058603, -2.2139125863543287, -0.5294722015989911, 1.417321104001079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961032334704, -0.44034089222072975, 0.02523382607193861]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3027809855934757e-05, 0.0002471035871828815, 1.9333047355637315e-05, 0.0, 0.0003130371163650664, 0.00011426468752416804, 3.984999132486252e-05, 0.00039030164358217097, -3.751433291583298e-06, -0.00023348968383076396, -0.00013724163583012978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010873051345381439, 0.03913162748356494, -0.07859792378520314, -0.0029611598785264674, 0.011824892576616503, 0.04034980139818535, 0.06021585163600526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.5495637686507746e-08, -1.764097494381458e-08, -0.00026889306268031713]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927541131276883, 0.23394009802358995, 0.8410185932189661, 0.0, -0.12558808170539637, -0.24501536003159705, -2.6083682275172504, -0.7148073196989726, -0.5580659552445796, -1.1977833488101328, -2.8760617628774376, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5542316414209236, 0.7606159964722238, 1.2906249655285476, -1.182708483457291, -2.21333203892798, -0.5274503660158455, 1.4203449570214883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196105224699, -0.4403408929544426, 0.025220370236506463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2395184038915284e-05, 0.00024754644761651673, 6.374826212170298e-05, 0.0, 0.0003127955039780514, 0.00010752044068553737, 4.225464864792489e-05, 0.0003909335613460387, -6.368271990569878e-06, -0.00023380691432252473, -0.00013651063200414507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011065407845928948, 0.039155348662223484, -0.07884725679517919, -0.0030036950286129248, 0.011610948526976715, 0.04043671166291232, 0.06047706040818713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.982457199812676e-08, -1.4674257741168563e-08, -0.0002691167086428905]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092743215783537, 0.23395255998394907, 0.8410230051473843, 0.0, -0.1255723470215273, -0.24500948683706794, -2.6083661263330646, -0.7147876519622324, -0.5580662673833868, -1.1977950636282821, -2.8760686341751702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5536712534113452, 0.7625660031818171, 1.2866879830377118, -1.182860236787746, -2.2127652088517054, -0.5254334347642385, 1.4233684315272994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066363056, -0.4403408935819532, 0.025206839486613532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1794688302532136e-05, 0.0002492392071820842, 8.823856836351996e-05, 0.0, 0.00031469367738097055, 0.00011746389058215508, 4.202368371624377e-05, 0.0003933547348035006, -6.242776145484021e-06, -0.00023429636298597504, -0.000137425954647393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011207760191569353, 0.03900013419186768, -0.0787396498167154, -0.0030350666091020382, 0.011336601525492554, 0.04033862503213897, 0.06046949011622329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.823213433133761e-08, -1.2550211904220164e-08, -0.0002706149978586365]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927325796914456, 0.23396514844578484, 0.8410271275585507, 0.0, -0.1255564580338701, -0.24500311691316207, -2.6083640599432076, -0.7147677981657665, -0.5580665472338727, -1.1978068265208242, -2.876075583750252, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.553105546653773, 0.7645022849839103, 1.2827683981542415, -1.1830131612272698, -2.2122139963352003, -0.5234276176635633, 1.426382469184317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119610762088, -0.44034089413375943, 0.025193188723775455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1272184183163444e-05, 0.00025176923671551226, 8.244822332876133e-05, 0.0, 0.0003177797531437408, 0.00012739847811768642, 4.132779714126504e-05, 0.0003970759293174542, -5.597009716998422e-06, -0.00023525785083845817, -0.00013899150163114093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011314135151442745, 0.03872563604186414, -0.07839169766940694, -0.0030584887904729547, 0.011024250330098417, 0.04011634201350546, 0.06028075314034978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9691486868662377e-08, -1.1036124096475251e-08, -0.00027301525676155737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927221430519952, 0.23397788059636185, 0.8410270716064849, 0.0, -0.12554039099261471, -0.24499642276078032, -2.608362020589197, -0.7147477276260098, -0.5580668007004707, -1.197818655240422, -2.8760826201722662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5525354056982379, 0.7664223422694074, 1.278871353095892, -1.1831670647227828, -2.2116791073875484, -0.5214355596259588, 1.4293832066465353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961082891086, -0.4403408946317607, 0.025179396447075814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0873278901138924e-05, 0.00025464301154047255, -1.119041316239696e-06, 0.0, 0.0003213408251079206, 0.00013388304763496832, 4.0787080209078265e-05, 0.0004014107951335775, -5.069331957641143e-06, -0.00023657439195773594, -0.00014072844028634236, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011402819110700887, 0.03840114570994267, -0.07794090116698955, -0.003078069910258842, 0.010697778953041907, 0.03984116075209075, 0.06001474924436734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3364573338846698e-08, -9.96002479206681e-09, -0.00027584553399285095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927118397610842, 0.23399075006007178, 0.8410239311303209, 0.0, -0.1255241513808587, -0.24498956199327032, -2.608359996228923, -0.7147274444229025, -0.5580670386222834, -1.1978305548826256, -2.8760897378995463, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5519607905134508, 0.7683268961315398, 1.2749955209541877, -1.1833219600052314, -2.2111602189092636, -0.5194565663562908, 1.4323716913338567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087239965, -0.44034089509134106, 0.025165464592248835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0606581822150228e-05, 0.00025738927419882105, -6.280952327926157e-05, 0.0, 0.00032479223511994534, 0.00013721535019996331, 4.048720548120468e-05, 0.0004056640621466314, -4.758436254420416e-06, -0.0002379928440712219, -0.00014235454560254028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011492303695741828, 0.0380910772426483, -0.07751664283408612, -0.0030979056489716097, 0.010377769565691192, 0.03957986539335971, 0.05976969374642933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.697758470711222e-09, -9.191606961494153e-09, -0.0002786370965395946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20927016114082483, 0.23400373210759065, 0.8410194512123002, 0.0, -0.12550776676360897, -0.24498264241683182, -2.6083579783408393, -0.7147069809039911, -0.558067269018674, -1.1978425179494117, -2.8760969224402344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5513808833672721, 0.770219150729859, 1.2711345184463556, -1.1834780299146201, -2.210656286818563, -0.5174873471763168, 1.4353528300773581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961089872947, -0.4403408955231401, 0.025151414134471806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0456705671853165e-05, 0.0002596409503772192, -8.959836041594101e-05, 0.0, 0.00032769234499486994, 0.00013839152876997973, 4.035776167439639e-05, 0.0004092703782273909, -4.607927813112079e-06, -0.00023926133572264456, -0.0001436908137622857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011598142923575108, 0.037845091966384706, -0.0772200501566399, -0.0031213981877756675, 0.010078641814011902, 0.03938438359947973, 0.05962277487002981, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.265964787306103e-09, -8.635980485045285e-09, -0.0002810091555406154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092691414881666, 0.23401679135898465, 0.8410150085045758, 0.0, -0.12549127854671643, -0.24497574505774763, -2.608355960179742, -0.7146863868814608, -0.5580674989080651, -1.1978545284643507, -2.8761041534961382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5507943371419204, 0.7721037991406221, 1.2672788624344777, -1.1836355715101474, -2.2101659072623985, -0.5155230332547469, 1.4383339177750694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091267843, -0.4403408959343855, 0.02513727793862914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0393053164340324e-05, 0.00026118502787984593, -8.885415448636424e-05, 0.0, 0.00032976433785099205, 0.00013794718168371885, 4.036322194714469e-05, 0.0004118804506054077, -4.597787821579858e-06, -0.00024021029877926975, -0.0001446211180774292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011730924507034505, 0.037692968215261316, -0.07711312023755544, -0.003150831910545682, 0.009807591123291796, 0.0392862784313995, 0.059621753954225365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7897920090490064e-09, -8.224908377818695e-09, -0.00028272391685331427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926812261786906, 0.23402988986582984, 0.8410113546364125, 0.0, -0.1254747319744555, -0.24496891110737837, -2.6083539390949957, -0.7146657179611566, -0.5580677317620203, -1.1978665659441785, -2.8761114100393854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5501995705682504, 0.7739859735345267, 1.2634180710725733, -1.1837949304919402, -2.209687661112676, -0.5135582639844605, 1.441323046386029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091769961, -0.44034089633000717, 0.025123092917831803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.037740595119924e-05, 0.00026197013690362075, -7.307736326522295e-05, 0.0, 0.0003309314452189297, 0.00013667900738548018, 4.042169492600479e-05, 0.000413378406083312, -4.657079103848079e-06, -0.00024074959655829772, -0.00014513086494717239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011895331473398937, 0.037643487878091735, -0.07721582723808787, -0.0031871796358551034, 0.009564922994449472, 0.039295385405728384, 0.05978257221919284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0042353279090035e-09, -7.91243332768826e-09, -0.00028370041594671626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209267104140628, 0.2340429943556656, 0.8410087467675743, 0.0, -0.12545816787715466, -0.24496215978482463, -2.6083519141469704, -0.7146450246015063, -0.5580679696948085, -1.1978786103348296, -2.8761186733775808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5495950616600683, 0.7758702989590087, 1.2595425870350851, -1.1839564366614876, -2.2092203933095136, -0.5115881754110759, 1.4443276391989144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091630049, -0.44034089671341636, 0.025108892724971923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0369544821449065e-05, 0.00026208979671518603, -5.215737676477587e-05, 0.0, 0.0003312819460165331, 0.0001350264510744388, 4.049896050569199e-05, 0.00041386719300691855, -4.75865576519643e-06, -0.00024088781302224356, -0.00014526676390855757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012090178163641576, 0.0376865084896394, -0.07750968074976214, -0.0032301233909471402, 0.009345356063242948, 0.039401771467691124, 0.060091856257709055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7982296091932287e-10, -7.668184058429974e-09, -0.00028400385719756733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926608744319491, 0.2340560813647748, 0.84100714592006, 0.0, -0.12544161653442082, -0.244955497567562, -2.6083498843726542, -0.7146243440160265, -0.558068214967887, -1.1978906458593799, -2.8761259294668036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5489795953441095, 0.7777601731303376, 1.2556452680292212, -1.1841203496511143, -2.2087633966761158, -0.50960916074856, 1.447353305741198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961091030892, -0.4403408970870755, 0.025094702314994995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0333948661378775e-05, 0.00026174018218340985, -3.20169502866619e-05, 0.0, 0.0003310268546768269, 0.00013324434525306686, 4.059548631981508e-05, 0.0004136117095959833, -4.905461569446624e-06, -0.000240710491007444, -0.0001451217844593823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012309326319177109, 0.03779748342657835, -0.07794638011728017, -0.003278259792533467, 0.009139932667958336, 0.03958029325031823, 0.06051333084567211, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1983133136278932e-09, -7.473183279607074e-09, -0.00028380819953853617]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926507518548892, 0.23406913975715812, 0.8410063972109484, 0.0, -0.1254250943916626, -0.24494892316027456, -2.608347847602481, -0.7146036957909659, -0.5580684709624298, -1.197902663376985, -2.8761331701051116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5483524295994947, 0.7796573562743375, 1.2517222633995697, -1.1842868227479875, -2.208316486536265, -0.5076193119658289, 1.450403158759081, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961090106299, -0.4403408974528865, 0.025080534974728976]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.024515411962932e-05, 0.00026116784766674965, -1.4974182231708038e-05, 0.0, 0.0003304428551644765, 0.00013148814574851165, 4.073540347224048e-05, 0.0004129645012103608, -5.11989085565838e-06, -0.00024035035209954281, -0.00014481276615678032, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012543314892294048, 0.03794366287999797, -0.07846009259303048, -0.0033294619374617247, 0.008938202797012384, 0.039796975654622084, 0.06099706035765974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8491878388867557e-09, -7.316219767631447e-09, -0.00028334680532038955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092640706247312, 0.23408217066001355, 0.8410063526322429, 0.0, -0.12540860373294258, -0.2449424304491214, -2.60834579975472, -0.7145830813160546, -0.5580687427240117, -1.1979146611692344, -2.876140392932268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5477133581084443, 0.7815619052704538, 1.2477731946150523, -1.184455889736394, -2.207879969820352, -0.5056185028546967, 1.4534776604086994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961088954982, -0.44034089781242836, 0.025066391894913224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.009121515419239e-05, 0.000260618057108365, -8.915741105720763e-07, 0.0, 0.00032981317440052325, 0.00012985422306327325, 4.095695521190876e-05, 0.0004122894982256085, -5.435231639094996e-06, -0.00023995584498924465, -0.00014445654312312013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012781429821006966, 0.03809097992232506, -0.07898137569034647, -0.0033813397681313325, 0.008730334318258284, 0.0400161822226447, 0.06149003299236816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3026331635870013e-09, -7.190836763878865e-09, -0.00028286159631504327]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926307691308385, 0.23409518526677917, 0.8410069402647227, 0.0, -0.1253921349031404, -0.24493601079447763, -2.6083437344912714, -0.7145624864817306, -0.5580690372130511, -1.1979266443344707, -2.8761476003795403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5470626671276048, 0.7834724248618756, 1.2438006829971782, -1.184627475277609, -2.207454529886821, -0.5036081384235395, 1.4565749690388725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961087651023, -0.44034089816707767, 0.025052263927612763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.987423294722793e-05, 0.0002602921353122936, 1.1752649594739351e-05, 0.0, 0.00032937659604336363, 0.00012839309287525946, 4.1305268976469446e-05, 0.0004118966864805311, -5.889780787719116e-06, -0.00023966330472836243, -0.00014414894544540635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013013819616792176, 0.03821039182843783, -0.07945023235748334, -0.0034317108242994452, 0.008508798670629213, 0.04020728862314311, 0.061946172603460165, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.6079186586223684e-09, -7.0929858090402915e-09, -0.0002825593460092203]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926209653450153, 0.23410820123521298, 0.8410082143246913, 0.0, -0.1253756709732818, -0.24492966907772523, -2.6083416402413238, -0.7145418865534288, -0.5580693663526989, -1.1979386237684981, -2.8761547968083865, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5464010059180497, 0.7853865487005857, 1.2398093933607142, -1.1848014244146543, -2.207041062165461, -0.5015906591196544, 1.4596916611728852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961086252894, -0.44034089851804437, 0.025038134870181875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9607571646466996e-05, 0.0002603193686763777, 2.5481199373799305e-05, 0.0, 0.00032927859717196993, 0.0001268343350481614, 4.188499894923267e-05, 0.00041199856603673615, -6.582792954605186e-06, -0.00023958868055025964, -0.0001439285769249745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013233224191099789, 0.038282476774199756, -0.0798257927292779, -0.003478982740907496, 0.008269354427197501, 0.04034958607770108, 0.06233384268025381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7962567570105424e-09, -7.0193344667182365e-09, -0.00028258114861774437]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926113099265617, 0.234121238526162, 0.8410105984550883, 0.0, -0.1253591947926548, -0.24492346106987012, -2.6083394906020354, -0.7145212518834684, -0.5580697569854639, -1.1979506160215903, -2.8761619827878184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5457292068060542, 0.7873015241020881, 1.2358048465440552, -1.184977542987103, -2.206640501330332, -0.49956893056404467, 1.4628236370430239, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961084815775, -0.4403408988663479, 0.025023985465707808]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.931083690758048e-05, 0.0002607458189806041, 4.768260794038333e-05, 0.0, 0.00032952361254006915, 0.00012416015710208913, 4.2992785767106124e-05, 0.0004126933992083718, -7.812655299679258e-06, -0.0002398450618418897, -0.0001437195886432252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01343598223991072, 0.03829950803004944, -0.08009093633318079, -0.0035223714489752, 0.008011216702579899, 0.0404345711121948, 0.06263951740277536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8742398780104438e-09, -6.966071248459883e-09, -0.0002829880894813476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20926018097379936, 0.23413431550550415, 0.8410167207029203, 0.0, -0.12534271040293332, -0.2449177927150775, -2.608337171986235, -0.7145005514573702, -0.5580703255885383, -1.1979626566472965, -2.876169126106767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5450480973304483, 0.7892147697485378, 1.2317922688863037, -1.1851556392368676, -2.206253675763402, -0.4975456560147912, 1.4659670042325852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961083432173, -0.4403408992127139, 0.025009797299432257]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9000377136226644e-05, 0.0002615395868425685, 0.00012244495664020678, 0.0, 0.00032968779442995655, 0.00011336709585256783, 4.637231600443822e-05, 0.00041400852196258844, -1.1372061487813333e-05, -0.00024081251412407916, -0.00014286637897059832, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013622189512117975, 0.03826491292899262, -0.08025155315503234, -0.003561924995294374, 0.007736511338602989, 0.040465490985068735, 0.06286734379122626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7672025351042834e-09, -6.927319278877532e-09, -0.0002837633255110353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925924473431196, 0.23414744577279814, 0.8410295052634726, 0.0, -0.12532615413129616, -0.24491146594222257, -2.6083348858091493, -0.7144797706276045, -0.5580708638242928, -1.1979747109666614, -2.876176309298787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5443583420276428, 0.7911243028203149, 1.2277756938930156, -1.1853355594288222, -2.205881215621574, -0.49552292125638464, 1.4691187756999138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961081996834, -0.4403408995579558, 0.024995556101940583]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.872478974795834e-05, 0.0002626053458798795, 0.0002556912110465393, 0.0, 0.0003311254327433029, 0.00012653545709845852, 4.5723541721021796e-05, 0.0004156165953142211, -1.0764715090429236e-05, -0.00024108638729753126, -0.00014366384040922283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013795106056110737, 0.038190661435542575, -0.08033149986576091, -0.0035984038390933335, 0.007449202836556653, 0.04045469516813203, 0.06303542934656964, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.870679197150595e-09, -6.904837927637466e-09, -0.00028482394983349996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209258321812838, 0.23416063671814646, 0.8410437398870134, 0.0, -0.12530950693366413, -0.2449045021895959, -2.6083326703868854, -0.7144588979179173, -0.5580713315230594, -1.1979867766771146, -2.876183551344064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5436603401302411, 0.7930289777705635, 1.2237574461151752, -1.1855172087541164, -2.205523515013933, -0.4935019358093305, 1.4722772729752847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196108047214, -0.4403408999025876, 0.02498125341052859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8458429479456307e-05, 0.00026381890696620686, 0.00028469247081648613, 0.0, 0.00033294395264052857, 0.0001392750525336554, 4.430844527807723e-05, 0.0004174541937448723, -9.353975332314504e-06, -0.00024131420906434384, -0.00014484090553941895, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013960037948034177, 0.03809349900497107, -0.08036495555680431, -0.003632986505881571, 0.007154012152821098, 0.04041970894108255, 0.06316994550741814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.0493887787539148e-09, -6.892636135295253e-09, -0.00028605382823986507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925741079071422, 0.23417388915558981, 0.8410558513561877, 0.0, -0.1252927688848866, -0.24489716620190444, -2.608330514922322, -0.7144379299689384, -0.5580717393380537, -1.1979988583162735, -2.876190849474161, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5429541857656108, 0.7949285340699397, 1.219738015378438, -1.1857005597806267, -2.20518074960298, -0.49148297443279904, 1.4754422337730737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961078852034, -0.44034090024685824, 0.02496688719657855]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.822044247553129e-05, 0.00026504874886679614, 0.00024222938348463573, 0.0, 0.00033476097555076287, 0.00014671975382885406, 4.3109291263184026e-05, 0.00041935897957802475, -8.15629988416167e-06, -0.00024163278317604285, -0.00014596260194143167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014123087292605495, 0.0379911259875245, -0.08038861473474176, -0.003667020530205452, 0.006855308219058671, 0.04037922753062938, 0.06329921595578203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.240211931340805e-09, -6.8854117509447195e-09, -0.0002873242790007967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925651016993824, 0.2341871982181353, 0.841064560189934, 0.0, -0.12527594904818817, -0.244889683732324, -2.6083283999322955, -0.7144168718483338, -0.5580721071402739, -1.1980109586672534, -2.8761981945080244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5422396885604397, 0.796823478601238, 1.2157162776406405, -1.1858856473286126, -2.204852931173053, -0.48946549449193955, 1.4786146509471971, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961077143157, -0.440340900590808, 0.024952461212057558]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8012415519644415e-05, 0.0002661812509097066, 0.00017417667492830742, 0.0, 0.0003363967339687805, 0.00014964939160868815, 4.22998005336657e-05, 0.0004211624120919971, -7.356044404709993e-06, -0.00024200701959800386, -0.00014690067726872157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014289944103422625, 0.03789889062596692, -0.08043475475595119, -0.003701750959717785, 0.006556368598541364, 0.04034959881719022, 0.06344834348246732, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.417755392511266e-09, -6.878994897202412e-09, -0.0002885196904198138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925561871488957, 0.2342005551099568, 0.8410618129676085, 0.0, -0.12525905888066197, -0.24488214897121363, -2.6083263175041984, -0.7143957352424114, -0.5580724431370468, -1.1980230752117988, -2.876205579243565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5415164409760148, 0.7987148547729442, 1.2116899592973498, -1.1860725531242928, -2.204539981107109, -0.4874483756147806, 1.4817964206867469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196107529577, -0.4403409009345591, 0.024937983419938786]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7829100973510103e-05, 0.00026713783642982983, -5.494444651112204e-05, 0.0, 0.00033780335052389384, 0.00015069522220727264, 4.1648561942064236e-05, 0.00042273211844828475, -6.719935459193817e-06, -0.00024233089091155212, -0.0001476947108070534, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0144649516884974, 0.03782752343412516, -0.08052636686581613, -0.0037381159136050312, 0.006259001318883878, 0.04034237754317851, 0.063635394790993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.6947749940585474e-09, -6.875021760779324e-09, -0.00028955584237541106]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925473569686348, 0.23421394931927147, 0.8410514001986437, 0.0, -0.1252421128803267, -0.24487463982329583, -2.6083242575075474, -0.714374534897885, -0.5580727580383967, -1.1980352043068812, -2.876212994467474, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5407839134953499, 0.8006039588567667, 1.207656221940558, -1.186261384604039, -2.2042418051162214, -0.48543021847138557, 1.484989893729473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961073308133, -0.4403409012779771, 0.024923463887919817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.766036052164086e-05, 0.0002678841862932682, -0.0002082553792966759, 0.0, 0.0003389200067054922, 0.00015018295835598537, 4.119993302519067e-05, 0.00042400689052663815, -6.298026998768619e-06, -0.00024258190164787988, -0.00014830447818341125, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014650549613298546, 0.037782081676448954, -0.08067474713583679, -0.0037766295949263422, 0.005963519817753503, 0.04036314286790055, 0.06386946085452182, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.975271951200736e-09, -6.868360176661031e-09, -0.00029039064037935573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092538608537945, 0.23422737072300479, 0.8410381966315522, 0.0, -0.12522512498451718, -0.24486719520491726, -2.6083222122520726, -0.7143532856264078, -0.558073060175217, -1.1980473414524133, -2.8762204318291222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5400415571601024, 0.802492060683494, 1.203612248263087, -1.1864522523033614, -2.203958355577257, -0.48340964194609903, 1.4881974215808351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961071196258, -0.4403409016208386, 0.024908912697799563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7496861379995055e-05, 0.0002684280746661161, -0.00026407134182844635, 0.0, 0.0003397579161902799, 0.00014889236757115187, 4.0905109493422496e-05, 0.0004249854295460771, -6.042736403583455e-06, -0.00024274291064534188, -0.00014874723296733107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014847126704950253, 0.03776203653454571, -0.08087947354941886, -0.0038173539864452552, 0.005668990779289269, 0.04041153050573016, 0.06415055702724443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.223748727891442e-09, -6.857230398915573e-09, -0.0002910238024050965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092529944076841, 0.23424081134161082, 0.8410256342076418, 0.0, -0.1252081083032503, -0.24485987423481367, -2.6083201681803243, -0.7143319993473054, -0.5580733639668903, -1.19805948425245, -2.876227881748336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5392888952123503, 0.8043801749776589, 1.199555730702428, -1.1866452498983047, -2.203689672700999, -0.4813855291015325, 1.4914209744135996, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961069010158, -0.44034090196284364, 0.024894338130268572]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.73289222079557e-05, 0.0002688123721204562, -0.00025124847820875187, 0.0, 0.0003403336253374409, 0.0001464194020714956, 4.088143496894334e-05, 0.00042572558204703276, -6.075833466954572e-06, -0.00024285600073301045, -0.00014899838427806628, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015053238955041206, 0.037762285883297685, -0.08113035121317991, -0.00385995189886731, 0.005373657525156167, 0.0404822568913309, 0.06447105665528777, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.372200407588851e-09, -6.840101178064515e-09, -0.00029149135061983824]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925213689002095, 0.2342542662563984, 0.8410156966170897, 0.0, -0.12519107192954645, -0.24485269584579836, -2.6083181143208978, -0.7143106838121357, -0.5580736811329241, -1.1980716312967383, -2.8762353371275893, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5385255891694956, 0.8062689141714454, 1.1954851943908478, -1.1868404398340329, -2.2034359013919644, -0.47935718789178705, 1.4946618848676878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961066785933, -0.44034090230379175, 0.024879745639150908]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.715035326296363e-05, 0.00026909829575125156, -0.00019875181104035377, 0.0, 0.0003407274740771001, 0.00014356778030618733, 4.1077188530469014e-05, 0.0004263107033934446, -6.343320675583013e-06, -0.000242940885769391, -0.00014910758505718826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015266120857095179, 0.03777478387572981, -0.08141072623160639, -0.0039037987145622843, 0.00507542618069157, 0.04056682419490884, 0.06481820908176425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.448451342577258e-09, -6.818962556157126e-09, -0.0002918498223532651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925128903715878, 0.23426773395518843, 0.8410091822802671, 0.0, -0.1251740209093694, -0.24484566153708204, -2.608316039956505, -0.7142893418370708, -0.5580740230314425, -1.1980837830640352, -2.8762427927565875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5377514715302819, 0.8081584355938903, 1.191400123617303, -1.1870378465048221, -2.203197285560948, -0.47732441194759734, 1.4979207434700035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961064552824, -0.44034090264356734, 0.024865137375008096]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6957057243526444e-05, 0.00026935397580074723, -0.0001302867364530094, 0.0, 0.00034102040354084764, 0.00014068617432632294, 4.1487287853933165e-05, 0.00042683950129745, -6.8379703677965584e-06, -0.00024303534593528628, -0.0001491125799654512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015482352784273262, 0.037790428448899266, -0.08170141547089317, -0.003948133415784107, 0.004772316620325626, 0.04065551888379408, 0.06517717204631435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.4662181708756e-09, -6.795512158578875e-09, -0.00029216528285619614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20925045163771558, 0.23428121600255097, 0.841006182580274, 0.0, -0.1251569578582527, -0.2448387886481049, -2.6083139287135433, -0.7142679714400227, -0.5580744067173158, -1.198095943175205, -2.8762502430157117, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5369665434085289, 0.8100484778689586, 1.1873008984865836, -1.1872374571208901, -2.202974145462632, -0.47528744564920095, 1.5011974420998633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961062340045, -0.44034090298211515, 0.02485051238883319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.674798886404033e-05, 0.00026964094725063224, -5.999399986235081e-05, 0.0, 0.0003412610223343902, 0.0001374577795425186, 4.2224859239858586e-05, 0.0004274079409619088, -7.673717465437287e-06, -0.00024320222339622167, -0.00014900518248552445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015698562435060924, 0.03780084550136615, -0.08198450261439016, -0.003992212321361882, 0.00446280196632445, 0.04073932596792761, 0.06553397259719447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.425557552529118e-09, -6.770956109758903e-09, -0.000292499723498149]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092496254561651, 0.23429471621174008, 0.8410070818992268, 0.0, -0.12513988917033175, -0.24483220114101195, -2.6083117354932526, -0.7142465662167454, -0.5580748787203342, -1.1981081230145345, -2.876257672920959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5361709421772896, 0.8119384662083703, 1.1831885815751473, -1.1874392290545575, -2.2027668457589105, -0.47324687428874174, 1.5044913358973206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961060191408, -0.4403409033193899, 0.024835867359076832]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6523631009647197e-05, 0.00027000418378232623, 1.7986379055652413e-05, 0.0, 0.00034137375841914824, 0.0001317501418588057, 4.38644058126588e-05, 0.000428104465546681, -9.440060369282882e-06, -0.00024359678659280064, -0.00014859810494164313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01591202462478672, 0.03779976678823284, -0.082246338228728, -0.004035438673345594, 0.004145994074430361, 0.04081142720918442, 0.06587787594914715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.2972752186325556e-09, -6.745495156767535e-09, -0.0002929005951271798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924881037954635, 0.23430823941628123, 0.8410104805760512, 0.0, -0.12512278443502178, -0.24482522520652472, -2.6083095683298225, -0.7142251228420964, -0.5580753276019556, -1.1981203016818394, -2.876265125001612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5353648890732149, 0.8138276562638193, 1.1790646163154206, -1.1876431018294107, -2.2025757636634418, -0.47120347108002103, 1.507801477500176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961058005932, -0.4403409036557102, 0.02482119775785553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6301532375350888e-05, 0.00027046409082271354, 6.797353648898557e-05, 0.0, 0.00034209470619956105, 0.00013951868974477018, 4.334326859974839e-05, 0.0004288674929802702, -8.977632425557614e-06, -0.00024357334609904135, -0.00014904161305743515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016121062081492537, 0.037783801108978735, -0.08247930519453568, -0.004077455497066453, 0.0038216419093723523, 0.04086806417441358, 0.0662028320571086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.370951473633228e-09, -6.7264061167353235e-09, -0.00029339202442599564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924800703709684, 0.23432179057086786, 0.8410220134799768, 0.0, -0.1251056348788504, -0.24481791065265449, -2.608307439769383, -0.7142036343470946, -0.5580757402627518, -1.1981324793969663, -2.876272606590669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5345486301753641, 0.815715283537283, 1.174930509137666, -1.187849009680018, -2.202401260338183, -0.46915803691662905, 1.511126864406344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961055784995, -0.44034090399110765, 0.024806498730338414]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6066848990084677e-05, 0.000271023091732647, 0.0002306580785137615, 0.0, 0.0003429911234276098, 0.00014629107740476386, 4.2571208786319135e-05, 0.00042976990003583957, -8.253215924271817e-06, -0.00024355430253760203, -0.00014963178114351563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01632517795701424, 0.037752545469273785, -0.08268214355509021, -0.00411815701214592, 0.003490066505177751, 0.040908683267839405, 0.06650773812336223, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.441875061750068e-09, -6.707948679834676e-09, -0.0002939805503423458]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924721542543817, 0.23433537370842256, 0.8410361863605892, 0.0, -0.12508843718601376, -0.24481039522159975, -2.608305342609468, -0.7141820942853051, -0.5580761239398435, -1.1981446603147465, -2.8762801172878922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5337223806981956, 0.8176006922550547, 1.1707875488863044, -1.1880568938312568, -2.202243664018041, -0.46711126031023903, 1.5144666613670423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961053527348, -0.4403409043256543, 0.024791766155124875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5832233173576852e-05, 0.0002716627510938502, 0.00028345761224643766, 0.0, 0.0003439538567329903, 0.0001503086210947443, 4.194319830212943e-05, 0.000430801235789004, -7.673541835312326e-06, -0.00024361835560364367, -0.00015021394446600118, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01652498954337114, 0.037708174355435345, -0.08285920502723475, -0.004157683024774714, 0.0031519264028380908, 0.040935532127800434, 0.06679593921396432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.515292675017828e-09, -6.690933603425866e-09, -0.00029465150427082805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924643533830425, 0.2343489912932732, 0.8410488218063917, 0.0, -0.12507119063353525, -0.2448027929086804, -2.6083032659665797, -0.7141604982942021, -0.558076489693346, -1.1981568485621175, -2.8762876545351124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5328862835321865, 0.8194834221540722, 1.1666366132028636, -1.1882667114267673, -2.2021032639672424, -0.4650636217414324, 1.5178203558558363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961051233105, -0.4403409046594021, 0.024776997345098726]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5601742678380886e-05, 0.0002723516970125972, 0.0002527089160520015, 0.0, 0.00034493104957015075, 0.00015204625838715168, 4.153285776985821e-05, 0.000431919822058675, -7.315070048949514e-06, -0.0002437649474163956, -0.00015074494440707218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0167219433201824, 0.03765459798034946, -0.08301871366881823, -0.004196351910210223, 0.002808001015978366, 0.04095277137613264, 0.06707388977588098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.588484374229094e-09, -6.674955954323654e-09, -0.0002953762005229549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924566647408677, 0.2343626439628206, 0.8410582188776666, 0.0, -0.12505389614320422, -0.2447951709450306, -2.6083012010642563, -0.7141388447389879, -0.5580768464749206, -1.198169046739875, -2.876295215589466, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5320403872014193, 0.8213632450124095, 1.1624780814579907, -1.1884784401226691, -2.2019803143826557, -0.46301535181210113, 1.5211878305426285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196104890307, -0.4403409049923652, 0.02476219137471044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5377284349828743e-05, 0.0002730533909486646, 0.00018794142549695913, 0.0, 0.0003458898066202609, 0.00015243927299610655, 4.129804646886761e-05, 0.0004330711042844184, -7.135631492355292e-06, -0.0002439635551490929, -0.00015122108707033406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016917926615343505, 0.03759645716674715, -0.08317063489745692, -0.004234573918034956, 0.002458991691729575, 0.04096539858662546, 0.0673494937358462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.660066937348196e-09, -6.659262154159706e-09, -0.00029611940776575553]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924490848327904, 0.23437633061949292, 0.8410560835309228, 0.0, -0.12503655431277882, -0.24478752010214577, -2.6082991495782464, -0.7141171348764142, -0.5580771925424345, -1.1981812541074885, -2.8763028006481965, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5311846441002754, 0.8232401533797046, 1.1583118511849793, -1.1886920782222765, -2.201875045276336, -0.4609664411809146, 1.524569354157154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961046486924, -0.44034090532473663, 0.024747349055800713]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.515981615443592e-05, 0.0002737331334461661, -4.2706934877010327e-05, 0.0, 0.0003468366085082563, 0.0001530168576964341, 4.102972019804011e-05, 0.0004341972514756301, -6.921350278078256e-06, -0.0002441473522719288, -0.0001517011746054956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017114862022878714, 0.037538167345899924, -0.08332460546022809, -0.004272761992147246, 0.0021053821263965393, 0.04097821262373043, 0.0676304722905131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.8322945298618424e-09, -6.647428706090912e-09, -0.00029684637819448666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924416111709013, 0.23439004885222628, 0.8410461448202162, 0.0, -0.12501916851060207, -0.24477986099661353, -2.608297108373726, -0.7140953718715477, -0.5580775311962143, -1.1981934700527117, -2.8763104073626153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5303189263193195, 0.8251143119355534, 1.1541374375979159, -1.1889076410571624, -2.2017876764519566, -0.458916691640201, 1.527965505878348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961043974682, -0.44034090565650524, 0.024732472576478384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.494732377830591e-05, 0.00027436465466719494, -0.0001987742141298727, 0.0, 0.00034771604353479976, 0.00015318211064475697, 4.082409040750608e-05, 0.0004352600973289408, -6.773075596842037e-06, -0.0002443189044638289, -0.0001521342883787291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017314355619117806, 0.03748317111697732, -0.0834882717412666, -0.004311256697716052, 0.0017473764875824422, 0.0409949908142728, 0.06792303442387358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.024482560456021e-09, -6.6353721321817925e-09, -0.0002975295864465577]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092434241898101, 0.23440379548519505, 0.8410332845986868, 0.0, -0.12500174317378177, -0.24477220846572847, -2.608295074172032, -0.7140735601679984, -0.5580778659557126, -1.1982056933796754, -2.876318032849949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5294430534430056, 0.8269859865684598, 1.1499541243889762, -1.189125154817421, -2.2017184311773126, -0.45686579217268836, 1.5313770578414172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961041372786, -0.4403409059875701, 0.024717564985329347]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4738545600715052e-05, 0.0002749326593754455, -0.0002572044305889292, 0.0, 0.00034850673640610146, 0.0001530506177013048, 4.068403387558512e-05, 0.0004362340709858327, -6.695189967279231e-06, -0.00024446653927346663, -0.00015250974666713418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01751745752627855, 0.037433492658127586, -0.08366626417879379, -0.004350275205172314, 0.0013849054928832506, 0.04101798935025297, 0.0682310392613842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.20379147070437e-09, -6.6212970787305426e-09, -0.0002981518229807454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924269768571976, 0.23441756723256021, 0.8410211936055637, 0.0, -0.12498428656625127, -0.24476466142210812, -2.6082930282445553, -0.7140517040554214, -0.5580782163099339, -1.1982179260165966, -2.876325668360499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5285568258487621, 0.8288554673713606, 1.1457611312938534, -1.1893446493034172, -2.2016675466270863, -0.4548134026388708, 1.5348048426790608, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196103873076, -0.44034090631767464, 0.024702629546660564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4530081806884725e-05, 0.0002754349473032083, -0.00024181986246085216, 0.0, 0.0003491321506098486, 0.00015094087240714833, 4.091854953169874e-05, 0.00043712225154075634, -7.007084426564443e-06, -0.0002446527384237837, -0.00015271021099671814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017724551884869048, 0.03738961605801727, -0.08385986190245388, -0.004389889719921877, 0.0010176910045214236, 0.041047790676350795, 0.06855569675287329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.284054276865303e-09, -6.602091496072119e-09, -0.00029870877337561573]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924198163869062, 0.2344313611202062, 0.8410122464977837, 0.0, -0.12496680663473403, -0.2447572764006, -2.608290952109812, -0.7140298075149323, -0.5580786015168077, -1.1982301698893667, -2.8763333053410314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5276600565197247, 0.8307230000548407, 1.141557766052324, -1.1895661509740727, -2.2016352798132326, -0.45275922901337, 1.5382496319416816, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961036089454, -0.44034090664660797, 0.024687669311053716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4320940582745845e-05, 0.00027587775291998173, -0.0001789421555994827, 0.0, 0.000349598630344771, 0.00014770043016274956, 4.152269486684434e-05, 0.0004379308097814693, -7.704137474671007e-06, -0.0002448774554009283, -0.00015273961065152483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.017935386580748176, 0.03735065366960045, -0.08406730483058789, -0.004430033413108865, 0.0006453362770783385, 0.04108347251001572, 0.0688957852524162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.282608769722518e-09, -6.578666193878617e-09, -0.00029920471213696226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20924127625602892, 0.2344451748886894, 0.8410079530709207, 0.0, -0.12494931498664277, -0.244750168298184, -2.6082888080760194, -0.7140078729634463, -0.5580790606308612, -1.1982424314263758, -2.8763409284529082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5267525963935548, 0.8325887363924743, 1.1373435371498235, -1.1897896775209689, -2.2016219084821045, -0.4507030786006588, 1.5417120444288943, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961033496475, -0.4403409069741575, 0.02467268668987216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4107653234047511e-05, 0.00027627536966383934, -8.58685372608118e-05, 0.0, 0.00034983296182516905, 0.00014216204832000084, 4.288067585132707e-05, 0.0004386910297200211, -9.182281072144481e-06, -0.0002452307401810137, -0.0001524622375366768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018149202523398262, 0.0373147267526732, -0.08428457805000901, -0.004470530937921876, 0.00026742662256651394, 0.04112300825422484, 0.06924824974425506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.1859567260439755e-09, -6.5509905493119906e-09, -0.00029965242363114023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092405814221847, 0.23445900711925993, 0.8410076193949413, 0.0, -0.12493180308159409, -0.24474297271213807, -2.6082866415957042, -0.7139859042924999, -0.5580795469753796, -1.1982546995110912, -2.876348553631648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5258343494031532, 0.8344527092342277, 1.1331182132852262, -1.1900152349403026, -2.2016277287256725, -0.44864488862339164, 1.5451924969752042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961030939942, -0.440340907300321, 0.024657683298567584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3896676884206326e-05, 0.0002766446114107791, -6.67351958730456e-06, 0.0, 0.0003502381009738575, 0.0001439117209183849, 4.3329606299553536e-05, 0.00043937341892728914, -9.726890369524963e-06, -0.000245361694308613, -0.0001525035747982607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01836493980803164, 0.037279456835067414, -0.08450647729194553, -0.004511148386673094, -0.00011640487135941536, 0.04116379954534321, 0.06960905092619887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.113067642888294e-09, -6.523269362194304e-09, -0.0003000678260915194]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923989737066429, 0.23447285729849482, 0.8410173949544465, 0.0, -0.12491426032710078, -0.2447354537589122, -2.608284502251769, -0.71396390406394, -0.5580800095622412, -1.198266962763555, -2.8763561988785353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5249052765248465, 0.8363148320871545, 1.1288818293044027, -1.1902428166137695, -2.201653048920596, -0.4465847280576006, 1.5486911968215638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961028376508, -0.44034090762510103, 0.024642659859163866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3681030408542761e-05, 0.00027700358469752445, 0.00019551119010394067, 0.0, 0.0003508550898663204, 0.00015037906451729831, 4.27868787103912e-05, 0.00044000457119782273, -9.251737232382818e-06, -0.00024526504927672977, -0.00015290493773938857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018581457566134493, 0.03724245705853732, -0.08472767961646975, -0.004551633469339973, -0.0005064038984640953, 0.041203211315821324, 0.06997399692719035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.126869319532842e-09, -6.495600528856092e-09, -0.0003004687880743624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092392244501384, 0.234486725664656, 0.8410311200160856, 0.0, -0.12489668545552522, -0.24472768583321533, -2.6082823951474987, -0.7139418722212836, -0.5580804432043482, -1.1982792199698034, -2.8763638661337536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5239653889266263, 0.8381749203751567, 1.1246346429876275, -1.1904724048381408, -2.201698183225296, -0.4445227753775335, 1.5522081740767828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961025786713, -0.4403409079485101, 0.024627616319695567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3458410517791e-05, 0.0002773673232235325, 0.00027450123278138414, 0.0, 0.0003514974315111833, 0.00015535851393738803, 4.214208540367673e-05, 0.00044063685312759504, -8.672842140828888e-06, -0.0002451441249686973, -0.00015334510436367145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018797751964405293, 0.037201765760044934, -0.08494372633550343, -0.004591764487425716, -0.0009026860940070896, 0.041239053601341294, 0.07033954510438059, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.179590171708666e-09, -6.4681820872776385e-09, -0.00030087078936595537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092385628245801, 0.23450061290819943, 0.841043974989202, 0.0, -0.12487907955192709, -0.24471978613250056, -2.6082803126668055, -0.7139198076214038, -0.5580808557941545, -1.1982914729840688, -2.87637155287179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5230147331040501, 0.840032726778139, 1.1203770586254933, -1.1907039742031829, -2.201763446439512, -0.44245928030608556, 1.555743342117177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961023164102, -0.4403409082705559, 0.024612552136522255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3232511166461702e-05, 0.0002777448708686309, 0.0002570994623296304, 0.0, 0.0003521180719626334, 0.00015799401429511677, 4.164961386793083e-05, 0.0004412919975958298, -8.251796124645198e-06, -0.0002450602853071114, -0.00015373476072257683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01901311645152213, 0.0371561280596449, -0.08515168724268607, -0.004631387300841511, -0.0013052642843153798, 0.04126990142895847, 0.07070336080788225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.245223065171383e-09, -6.440916079248447e-09, -0.000301283663466211]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923791258923294, 0.23451451984754135, 0.841053839335408, 0.0, -0.124861443738691, -0.24471183909284877, -2.6082782461560727, -0.7138977088744598, -0.5580812562752453, -1.198303724005304, -2.876379256266048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5220533722188224, 0.8418879814421235, 1.1161095379235029, -1.1909374956665297, -2.201849150615711, -0.4403945196928669, 1.5592965689997291, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196102050767, -0.44034090859124075, 0.024597466590461522]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3004706942721193e-05, 0.0002781387868381211, 0.00019728692411996905, 0.0, 0.00035271626472192926, 0.00015894079303583724, 4.1330214656937515e-05, 0.00044197493888114875, -8.009621817293962e-06, -0.0002450204247059355, -0.00015406788515755283, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019227217704553823, 0.03710509327968975, -0.0853504140398068, -0.004670429266939552, -0.0017140835239768332, 0.041295212264373216, 0.0710645376510457, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.312866158655143e-09, -6.413697667347336e-09, -0.0003017109212146423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923727385304727, 0.2345284471820798, 0.8410522138073605, 0.0, -0.12484378254230989, -0.24470398536804427, -2.6082761725991963, -0.7138755742604499, -0.5580816683877518, -1.1983159783207948, -2.876386968121842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5210813675425818, 0.8437404292008875, 1.111832515911148, -1.191172940537945, -2.2019556038910966, -0.4383287562399933, 1.56286774570927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961017818023, -0.44034090891060784, 0.024582359033059612]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2774723713286888e-05, 0.00027854669076925285, -3.251056095003856e-05, 0.0, 0.00035322392762227256, 0.00015707449608995283, 4.147113752742501e-05, 0.0004426922801981734, -8.242250128389216e-06, -0.0002450863098167964, -0.00015423711587763197, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01944009352481135, 0.03704895517528012, -0.08554044024709782, -0.004708897428303273, -0.002129065507710266, 0.04131526905747279, 0.07142353419081342, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.379290814927804e-09, -6.3873414308310886e-09, -0.000302151148038187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092366466504449, 0.2345423951962035, 0.8410434472930469, 0.0, -0.12482610237027067, -0.2446963384501182, -2.6082740628509478, -0.7138534024818921, -0.5580821222057958, -1.1983282422944421, -2.8763946777497114, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5200987630336469, 0.8455898577733169, 1.107546335549563, -1.1914102836995266, -2.2020831116149004, -0.4362622067468347, 1.566456840158064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961015123277, -0.44034090922857455, 0.024567229195095627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2544052047728873e-05, 0.0002789602824744588, -0.00017533028627138354, 0.0, 0.00035360344078455975, 0.000152938358521538, 4.2194964967829366e-05, 0.0004434355711551118, -9.0763608804408e-06, -0.000245279472945569, -0.00015419255739288778, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019652090178698466, 0.03698857144858722, -0.08572360723169974, -0.004746863231634872, -0.002550154476074551, 0.04133098986317244, 0.07178188897588188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.389492783145938e-09, -6.359334203315072e-09, -0.0003025967592796801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923603119785542, 0.23455636366143515, 0.8410353019987932, 0.0, -0.1248084242584862, -0.24468923095470801, -2.6082718269296277, -0.713831191059617, -0.5580827105398091, -1.1983405351414187, -2.876402351621198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.519105575620468, 0.8474361134617115, 1.1032512099441503, -1.1916495054977405, -2.202231978612754, -0.4341950240570607, 1.5700639289912093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961012491604, -0.4403409095449165, 0.024552077293800822]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2309051789507755e-05, 0.00027936930463274916, -0.00016290588507396475, 0.0, 0.00035356223568931217, 0.00014214990820386725, 4.471842639831812e-05, 0.00044422844550102134, -1.1766680265442813e-05, -0.00024585693952967403, -0.00015347742973165416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019863748263576935, 0.03692511376789492, -0.08590251210825339, -0.004784435964277944, -0.0029773399570713964, 0.04134365379548046, 0.07214177666290271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.26334369806623e-09, -6.326839330366228e-09, -0.00030303802589605624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092354267738185, 0.2345703517593418, 0.841037086357163, 0.0, -0.12479072675782128, -0.24468196978950849, -2.608269562166431, -0.71380894456449, -0.5580833331616019, -1.1983528350359811, -2.87641002529331, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5181017919564832, 0.8492791034645827, 1.0989472139222365, -1.1918905930169712, -2.2024025140696923, -0.4321272937656738, 1.5736892075793183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961010055812, -0.4403409098589737, 0.02453690412215113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2088480738122096e-05, 0.0002797619581327564, 3.568716739713108e-05, 0.0, 0.0003539500132983976, 0.00014522330399074646, 4.529526392674975e-05, 0.0004449299025413268, -1.2452435856533942e-05, -0.00024599789125044413, -0.0001534734422348367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020075673279695384, 0.03685980005742207, -0.08607992043827516, -0.004821750384614016, -0.003410709138764685, 0.04135460582773689, 0.07250557176218154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.871585243622658e-09, -6.281143838603349e-09, -0.0003034634329938299]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923483351000108, 0.23458435821041387, 0.8410433690732536, 0.0, -0.1247729928187537, -0.24467419120495768, -2.6082673488459154, -0.7137866672064415, -0.5580839074054937, -1.198365123797158, -2.87641772791869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5170873720815716, 0.85111878546559, 1.0946343060215737, -1.192133538432852, -2.202595032702884, -0.43005904517215826, 1.5773329717200524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961007619495, -0.4403409101713919, 0.024521710933646846]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1865276348927471e-05, 0.0002801290214417316, 0.00012565432181280977, 0.0, 0.00035467878135150756, 0.0001555716910162052, 4.4266410315425116e-05, 0.0004455471609690459, -1.1484877837322644e-05, -0.00024577522353742175, -0.0001540525076079574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020288397498231026, 0.0367936400201483, -0.0862581580132528, -0.00485890831761699, -0.003850372663837832, 0.04136497187031095, 0.07287528281468234, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.872635981013225e-09, -6.248363731130677e-09, -0.00030386377008570877]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923425164787207, 0.2345983814792764, 0.841050347506695, 0.0, -0.12475522292646406, -0.24466603816082416, -2.6082651926888545, -0.713764361211254, -0.5580844274851053, -1.1983773992061868, -2.876425460844925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5160622570306792, 0.8529551512103469, 1.09031236495632, -1.1923783374825825, -2.2028098565664673, -0.4279902694218642, 1.5809955887759293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961005111467, -0.4403409104823721, 0.02450649925825024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.163724258027144e-05, 0.0002804653772501444, 0.0001395686688296028, 0.0, 0.0003553978457929012, 0.0001630608826704875, 4.312314121554707e-05, 0.0004461199037493099, -1.0401592232705189e-05, -0.0002455081805767086, -0.00015465852470114935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02050230101784817, 0.03672731489513667, -0.08643882130507669, -0.004895980994609451, -0.004296477271664276, 0.041375515005881276, 0.073252341117538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.0160564280701034e-09, -6.219605362174422e-09, -0.0003042335079320552]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092336812073117, 0.23461241991371726, 0.8410561678621937, 0.0, -0.12473742219781848, -0.24465770728454195, -2.6082630802066746, -0.7137420285191424, -0.5580849074418099, -1.198389663027904, -2.8764332181693337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5150263785751835, 0.8547882069357311, 1.0859812336661037, -1.1926249875088784, -2.2030473162083246, -0.4259209411969448, 1.5846774624480346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811961002514438, -0.44034091079192145, 0.024491270776937437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1408811207364125e-05, 0.0002807686888172977, 0.00011640710997282274, 0.0, 0.00035601457291151454, 0.00016661752564447262, 4.224964359557917e-05, 0.0004466538422316748, -9.599134091982837e-06, -0.0002452764343438294, -0.0001551464881691109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.020717569109913524, 0.03666111450768433, -0.08662262580432678, -0.004933000525917938, -0.0047491928371491505, 0.041386564498387415, 0.07363747344210625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.194058572993528e-09, -6.190986860384029e-09, -0.00030456962625612414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092331222669531, 0.23462647193549757, 0.841052066079572, 0.0, -0.12471959924255467, -0.24464941954873765, -2.608260982624077, -0.713719670597397, -0.55808537708744, -1.1984019203027907, -2.8764409883123934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5139796698170055, 0.8566179539149585, 1.0816407643975692, -1.1928734852410094, -2.203307750057057, -0.4238510406151482, 1.5883789956931182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960999830891, -0.44034091110001405, 0.02447602713313368]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1178807172321633e-05, 0.00028104043560611415, -8.203565243488869e-05, 0.0, 0.00035645910527626145, 0.00016575471608629082, 4.195165195554541e-05, 0.00044715843490582383, -9.392912601900415e-06, -0.00024514549773298693, -0.00015540286119064626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02093417516356161, 0.03659493958454977, -0.08680938537068913, -0.004969954642621503, -0.005208676974652198, 0.04139801163593095, 0.07403066490167189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.367093402234195e-09, -6.1618522748371104e-09, -0.0003048728760751354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923257491223984, 0.23464053609047267, 0.8410419055366319, 0.0, -0.12470176364589647, -0.24464133781230815, -2.6082588665282125, -0.7136972887095854, -0.5580858710249742, -1.1984141770704049, -2.8764487579958957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5129220742543645, 0.8584443728070699, 1.077290855772315, -1.1931238248543903, -2.2035915028096063, -0.42178057102604194, 1.5921005596733184, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960997096226, -0.440340911406489, 0.024460769881989263]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0947094264936601e-05, 0.00028128309950176415, -0.0002032108588002307, 0.0, 0.00035671193316402056, 0.00016163472858988137, 4.232191728334855e-05, 0.0004476377562333042, -9.878750685222405e-06, -0.0002451353522834519, -0.00015539367005093068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021151911252818414, 0.03652837784222549, -0.08699817250508257, -0.005006792267617171, -0.005675055050982058, 0.04140939178212616, 0.07443127960400155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.469333852017078e-09, -6.129498761064716e-09, -0.00030514502288832664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923203945074248, 0.234654611139149, 0.8410329760044956, 0.0, -0.12468393783006151, -0.24463381737345521, -2.608256641870117, -0.7136748820675878, -0.5580864822372624, -1.1984264517189394, -2.876456493033111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5118535520675944, 0.86026741417937, 1.0729314763532303, -1.193375996563004, -2.2038989229339174, -0.4197095700785597, 1.59584247316251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960994386653, -0.4403409117110504, 0.024445500384940443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0709229947061336e-05, 0.0002815009735270556, -0.00017859064272867818, 0.0, 0.0003565163166989832, 0.00015040877705849477, 4.449316191303092e-05, 0.000448132839952295, -1.2224245764281534e-05, -0.00024549297069120405, -0.0001547007443032467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0213704437354033, 0.036460827446003485, -0.08718758838169695, -0.005043434172273638, -0.0061484024862227945, 0.041420018949645344, 0.07483826978383265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.41914580147142e-09, -6.091227530342086e-09, -0.00030538994097642047]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923151539108384, 0.23466869601465398, 0.8410369603092293, 0.0, -0.12466610730241652, -0.24462629384666287, -2.6082543779253315, -0.7136524549442156, -0.5580871394853086, -1.1984387281294149, -2.876464218332244, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5107740827551385, 0.8620869957374822, 1.0685626721506054, -1.1936299866938658, -2.2042303620937327, -0.41763811324967404, 1.5996049968703707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960991865436, -0.44034091201287073, 0.024430219834777226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0481193173066671e-05, 0.0002816975100991661, 7.968609467351684e-05, 0.0, 0.00035661055289996446, 0.00015047053584673302, 4.5278895708661466e-05, 0.0004485424674445845, -1.3144960923647588e-05, -0.0002455282095096486, -0.00015450598266201668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02158938624911852, 0.03639163116224268, -0.08737608405249829, -0.005079802617235855, -0.006628783196301097, 0.04142913657771301, 0.07525047415721449, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.042432717502845e-09, -6.0364069223755525e-09, -0.0003056110032643384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923100283255752, 0.23468278982685334, 0.8410444950602779, 0.0, -0.12464825226265315, -0.24461829692062967, -2.6082521656327224, -0.713630011550289, -0.5580877491526708, -1.198450985861604, -2.8764719670998957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5096836649634202, 0.8639030045311199, 1.0641845631582998, -1.1938857771391707, -2.2045861721409685, -0.4155663116254859, 1.603388334133879, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960989332096, -0.44034091231267136, 0.024414929235849793]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0251170526505469e-05, 0.00028187624398724346, 0.0001506950209727834, 0.0, 0.00035710079526729164, 0.00015993852066417723, 4.4245852182918864e-05, 0.0004488678785303976, -1.219334724283644e-05, -0.00024515464378050837, -0.0001549753530299669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021808355834365044, 0.03632017587275478, -0.08756217984611223, -0.005115808906095752, -0.007116200944715079, 0.041436032483762424, 0.07566674527016634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.066679126741525e-09, -5.996012086212419e-09, -0.00030581197854868307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923050216204658, 0.23469689186915452, 0.8410516616188889, 0.0, -0.12463037171473912, -0.24460994079275783, -2.6082500133720026, -0.7136075531239947, -0.5580883027034881, -1.1984632225123395, -2.8764797420544017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5085823128939614, 0.8657153051896176, 1.0597973256827151, -1.194143346163699, -2.2049667038536658, -0.4134943030747915, 1.6071926446615838, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196098671681, -0.44034091261067837, 0.024399629399881436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0013410218914426e-05, 0.00028204084602383465, 0.00014333117222068478, 0.0, 0.00035761095828053827, 0.00016712255743682876, 4.304521440058582e-05, 0.0004491685258869663, -1.1071016345658088e-05, -0.0002447330147117217, -0.00015549909012203795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022027041389176896, 0.03624601316995274, -0.08774474951169516, -0.0051513804905646155, -0.007610634253944473, 0.041440171013887465, 0.07608621055409705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.230571128178997e-09, -5.960140387646349e-09, -0.0003059967193671177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20923001346662412, 0.23471100150640223, 0.8410570992865238, 0.0, -0.124612469576945, -0.24460141530682628, -2.6082479078840874, -0.7135850801968361, -0.5580888139089831, -1.1984754403653106, -2.876487537895516, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5074700501760492, 0.867523751218759, 1.0554011660280609, -1.1944026698833945, -2.2053723078435907, -0.4114222395388834, 1.6110180667421843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960984004842, -0.440340912906907, 0.024384321059351226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.77390844932557e-06, 0.0002821927449540467, 0.000108753352697927, 0.0, 0.00035804275588250685, 0.00017050971863127144, 4.210975830491218e-05, 0.0004494585431732285, -1.0224109900509904e-05, -0.0002443570594232101, -0.0001559168222916129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022245254358245144, 0.036168920582829035, -0.08792319309308277, -0.005186474393909225, -0.008112079798501207, 0.04144127071816173, 0.07650844161200956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.423937811173064e-09, -5.924572664479066e-09, -0.0003061668106041999]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092295368781185, 0.23472511812237018, 0.8410525567244167, 0.0, -0.12459455539927589, -0.24459298694859025, -2.608245811408167, -0.7135625925579099, -0.5580893217995248, -1.1984876469894246, -2.876495340225951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5063469036469429, 0.8693281958882545, 1.0509962948414044, -1.1946637235971365, -2.205803335645199, -0.40935027469185803, 1.6148647387961867, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960981211883, -0.440340913201293, 0.024369004918805077]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.531770112582698e-06, 0.0002823323193592111, -9.085124214319048e-05, 0.0, 0.0003582835533821116, 0.00016856716472041987, 4.192951841072784e-05, 0.00044975277852422565, -1.0157810831525628e-05, -0.0002441324822768575, -0.00015604660869718368, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02246293058212572, 0.03608889338990902, -0.08809742373312995, -0.005221074274839436, -0.008620556032167825, 0.04143929694050713, 0.07693344108004997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.585919470088617e-09, -5.8877196347280575e-09, -0.00030632281092298554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922907254402637, 0.23473924097755533, 0.8410430468096177, 0.0, -0.12457664465750391, -0.24458494204825634, -2.6082436611804063, -0.7135400894695607, -0.558089891193906, -1.1984998552367652, -2.8765031252828543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5052128977614048, 0.871128501107967, 1.0465829055964682, -1.194926482883499, -2.2062601412752496, -0.4072785536904651, 1.6187328177432267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960978396832, -0.44034091349359755, 0.024353681801970777]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.286681842308948e-06, 0.00028245710370275603, -0.00019019829597943813, 0.0, 0.00035821483543939294, 0.00016089800667815171, 4.3004555210236635e-05, 0.0004500617669834312, -1.1387887624443933e-05, -0.00024416494681227545, -0.00015570113806031218, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022680117710762223, 0.03600610439425101, -0.08826778489872511, -0.005255185727246861, -0.009136112601008644, 0.04143442002785773, 0.07736157894079969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.630101619651346e-09, -5.8460912789013415e-09, -0.00030646233668602126]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092286203029788, 0.2347533691199173, 0.8410366097666756, 0.0, -0.12455873906782257, -0.24457712016806227, -2.608241455221437, -0.7135175725101464, -0.5580905242752763, -1.1985120646248903, -2.876510891702536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5040680507202013, 0.872924542990264, 1.042161160418863, -1.1951909245602055, -2.2067430834685604, -0.40520720662076, 1.6226224919949306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960975589218, -0.4403409137837116, 0.02433835273812638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.044820950828083e-06, 0.00028256284723898446, -0.00012874085884307046, 0.0, 0.00035811179362700286, 0.00015643760388143953, 4.411917938666845e-05, 0.0004503391882867604, -1.2661627407282987e-05, -0.00024418776250376096, -0.00015532839362946262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.022896940824068145, 0.03592083764594023, -0.08843490355210347, -0.00528883353413279, -0.009658843866211879, 0.0414269413941024, 0.0777934850340786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6152266013673606e-09, -5.802281156345202e-09, -0.0003065812768879271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922817994548892, 0.23476750143913333, 0.8410317368181572, 0.0, -0.12454082133663524, -0.24456902851836237, -2.6082392747393492, -0.713495046101068, -0.5580911374821886, -1.1985242565890923, -2.87651866889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5029123732057359, 0.8747162132660619, 1.0377311860746754, -1.1954570270293148, -2.207252526997856, -0.40313634677010934, 1.6265339855381478, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960972813505, -0.4403409140713817, 0.024323018905498428]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.807149797687654e-06, 0.0002826463843210159, -9.74589703665631e-05, 0.0, 0.0003583546237463803, 0.00016183299399782965, 4.360964175396415e-05, 0.00045052818156762596, -1.2264138246990007e-05, -0.0002438392840411457, -0.00015554380207734861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02311355028930857, 0.035833405515955936, -0.0885994868837508, -0.005322049382186002, -0.010188870585910479, 0.04141719701301333, 0.07822987086434155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5514245871595604e-09, -5.753402196005454e-09, -0.000306676652559026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922775208871658, 0.23478163673089025, 0.8410269189424823, 0.0, -0.12452290749927553, -0.2445610802733366, -2.60823705671734, -0.7134725099597611, -0.5580917959042532, -1.1985364438454809, -2.876526432828552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5017458688935809, 0.876503417771528, 1.0332930775127567, -1.1957247695296482, -2.2077888417223948, -0.4010660722071327, 1.6304675538598268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196097005762, -0.44034091435659856, 0.02430768157447591]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.557135447079631e-06, 0.00028270583513837535, -9.63575134987599e-05, 0.0, 0.00035827674719448194, 0.00015896490051578013, 4.4360440186066256e-05, 0.00045072282613815867, -1.3168441291317371e-05, -0.00024374512776992012, -0.00015527871823862847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023330086243100588, 0.03574409010932276, -0.08876217123837545, -0.005354850006668302, -0.010726294490778453, 0.041405491259532884, 0.07867136643357993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.5117697080917796e-09, -5.704337183720439e-09, -0.00030674662045039944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092273364795529, 0.23479577360256368, 0.8410267217978544, 0.0, -0.12450499913756155, -0.2445531912725162, -2.6082348019596893, -0.7134499663025892, -0.5580924988772874, -1.1985486250627273, -2.876534182971404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5005685356159986, 0.8782860735546842, 1.0288469036469596, -1.1959941324338006, -2.2083524046662615, -0.3989964689225732, 1.6344234810585367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960967315432, -0.44034091463937164, 0.024292342210012866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.31218327346479e-06, 0.00028273743346835396, -3.942892555852602e-06, 0.0, 0.000358167234279383, 0.00015778001640777447, 4.50951530158411e-05, 0.0004508731434375434, -1.4059460683804483e-05, -0.00024362434492997581, -0.00015500285704769982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02354666555164614, 0.03565311566312634, -0.08892347731593916, -0.005387258083048048, -0.011271258877333048, 0.04139206569119055, 0.07911854397420086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4843783973253375e-09, -5.655461688257759e-09, -0.00030678728926084454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092269328669074, 0.2348099105758585, 0.8410328085718266, 0.0, -0.12448707681038215, -0.2445448705057502, -2.608232602889105, -0.7134274203571955, -0.5580931513025706, -1.1985607790395163, -2.876541952707773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4993803688712595, 0.880064103097541, 1.0243927211786348, -1.1962650965612587, -2.208943599389502, -0.3969276174649741, 1.6384020683100775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960964513507, -0.440340914919795, 0.02427700236992856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.072252910155402e-06, 0.00028273946589653745, 0.00012173547944455026, 0.0, 0.00035844654358794566, 0.0001664153353203612, 4.398141168845759e-05, 0.00045091890787210125, -1.3048505665113734e-05, -0.00024307953578067693, -0.00015539472737960248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023763334894781794, 0.03556059085713516, -0.08908364936649825, -0.005419282549162722, -0.011823894464809255, 0.04137702915198115, 0.07957174503081545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.6038510622082095e-09, -5.608466697218602e-09, -0.00030679680168615704]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922654166067067, 0.23482404617815011, 0.8410412273442239, 0.0, -0.12446914038951988, -0.24453622390550075, -2.608230468085501, -0.7134048745361499, -0.5580937444931828, -1.1985729027930856, -2.876549744394196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49818136574451966, 0.8818374283976583, 1.019930589651557, -1.1965376419472014, -2.2095628134221337, -0.3948595998606208, 1.6424036197278522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960961632773, -0.44034091519783325, 0.024261663614724982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.824124734902576e-06, 0.0002827120458322431, 0.0001683754479456738, 0.0, 0.0003587284172453867, 0.00017293200498848488, 4.2696072079051175e-05, 0.00045091642091311116, -1.1863812242775575e-05, -0.00024247507138728597, -0.00015583372845762609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.023980062534796138, 0.035466506002346784, -0.08924263054155514, -0.00545090771885237, -0.012384280652634735, 0.04136035208706627, 0.08003102835549275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.761465067164659e-09, -5.5607647810329235e-09, -0.00030677510407153255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922616295505392, 0.23483817896123738, 0.8410490852513846, 0.0, -0.12445119489880907, -0.24452743829899679, -2.6082283837711637, -0.7133823305847966, -0.5580942928161348, -1.198584998145203, -2.8765575520800817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4969715275917248, 0.8836059669803608, 1.0154605812500674, -1.196811747499963, -2.2102104377362424, -0.39279250428916135, 1.6464284343560336, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095867687, -0.44034091547339604, 0.024246327492719974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.574112335228865e-06, 0.0002826556617451584, 0.00015715814321276875, 0.0, 0.00035890981421632693, 0.00017571213007928167, 4.1686286744317405e-05, 0.0004508790270657108, -1.0966459037819545e-05, -0.00024190704235009058, -0.00015615371771426863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024196763055897286, 0.035370771654048096, -0.08940016802979006, -0.0054821110552363845, -0.012952486282172465, 0.04134191142918913, 0.0804962925636271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.911807805937267e-09, -5.5112561318106675e-09, -0.0003067224401001848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922579680585263, 0.23485230751964287, 0.8410551260082697, 0.0, -0.12443324572456714, -0.24451864694277212, -2.6082263344864067, -0.7133597902155533, -0.5580948123792668, -1.1985970672594228, -2.8765653691833957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49575086226104903, 0.8853696289438552, 1.0109827884664662, -1.1970873906083481, -2.2108868656457132, -0.39072642862796775, 1.65047679939993, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960955656938, -0.4403409157463759, 0.024230995521878285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.322984026012576e-06, 0.0002825711681099264, 0.00012081513770211566, 0.0, 0.00035898348483850577, 0.00017582712449362893, 4.098569513964275e-05, 0.0004508073848668016, -1.0391262641673134e-05, -0.00024138228439390562, -0.0001563420662759655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02441330661351502, 0.035273239269888054, -0.0895558556720272, -0.005512862167700783, -0.013528558189413202, 0.04132151322387183, 0.08096730087792933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.039863141520829e-09, -5.459597199002481e-09, -0.00030663941683379875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922544348864547, 0.23486643055305054, 0.8410516600789181, 0.0, -0.12441531025423512, -0.24451022400760422, -2.608224252247095, -0.7133372533672377, -0.558095373430019, -1.198609123703882, -2.876573169694533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4945193854577599, 0.8871283156303824, 1.006497328144911, -1.1973645468070087, -2.2115924913823406, -0.388661482186963, 1.6545489860475655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196095262447, -0.44034091601655695, 0.024215669123602613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.066344143356634e-06, 0.0002824606681536391, -6.931858703256564e-05, 0.0, 0.0003587094066402643, 0.00016845870335784188, 4.1644786232455846e-05, 0.00045073696631083623, -1.1221015042756142e-05, -0.00024112888918500513, -0.00015601022275316007, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02462953606578174, 0.035173733730543714, -0.08970920643110362, -0.00554312397321154, -0.014112514732550215, 0.041298928820095435, 0.0814437329527083, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0649334679944005e-09, -5.403621012739874e-09, -0.00030652796551343983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922510287796178, 0.23488054673289557, 0.8410453123797789, 0.0, -0.12439739345231203, -0.24450208979585292, -2.608222123215735, -0.7133147218632591, -0.5580959904178329, -1.198621169241677, -2.876580947616735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4932771206221174, 0.8888819200328602, 1.002004340587019, -1.1976431899810067, -2.2123277102860492, -0.38659778527636235, 1.658645250560513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196094961182, -0.44034091628382155, 0.02420034975651545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.812213673893282e-06, 0.00028232359690059553, -0.00012695398278336715, 0.0, 0.00035833603846176075, 0.00016268423502602524, 4.2580627199534485e-05, 0.00045063007957435767, -1.2339756277197146e-05, -0.00024091075590005698, -0.00015555844404097243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02484529671285001, 0.035072088049553814, -0.08985975115784277, -0.005572863479960354, -0.014704378074173489, 0.04127393821201264, 0.08192529025895022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0252987988901175e-09, -5.345292444117205e-09, -0.0003063873417432767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922477524753944, 0.23489465477246935, 0.8410452074994145, 0.0, -0.12437950954869476, -0.24449439493203598, -2.6082198931027345, -0.7132921961287746, -0.5580967194820536, -1.1986332144417962, -2.87658868200518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4920240985108147, 0.8906303281832448, 0.997503986963954, -1.1979232922787466, -2.2130929177335372, -0.38453546777582476, 1.6627658355278006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960946663445, -0.44034091654796714, 0.02418503883586631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.55260844684948e-06, 0.00028216079147531595, -2.0976072879545196e-06, 0.0, 0.0003576780723454631, 0.00015389727633898903, 4.460226001287e-05, 0.00045051468968865444, -1.4581284414749146e-05, -0.00024090400238012088, -0.00015468776889814983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025060442226055177, 0.03496816300769299, -0.0900070724612974, -0.005602045954796174, -0.015304148949760347, 0.0412463500107513, 0.08241169934575161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.896747979429786e-09, -5.282911832871913e-09, -0.0003062184129828008]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922445995118852, 0.23490875335282946, 0.8410484974848362, 0.0, -0.12436162721644259, -0.2444862530313363, -2.6082177053556697, -0.7132696829483258, -0.5580974129435289, -1.1986452270616588, -2.876596425174763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49076035572194887, 0.8923734214703991, 0.9929964432129866, -1.198204825000671, -2.213888511169073, -0.38247466647819256, 1.6669109766511037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960943694733, -0.4403409168091144, 0.024169737799255797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.305927018371171e-06, 0.00028197160720243975, 6.57997084341371e-05, 0.0, 0.00035764664504322043, 0.00016283801399335354, 4.3754941293355606e-05, 0.00045026360897635297, -1.3869229504038548e-05, -0.0002402523972538747, -0.00015486339166848937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025274855777316755, 0.03486186574308656, -0.09015087501934801, -0.005630654438487442, -0.015911868710717047, 0.04121602595264391, 0.0829028224660603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.937423846599186e-09, -5.22294577457969e-09, -0.00030602073221025353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922415758091562, 0.2349228411724104, 0.8410526983818923, 0.0, -0.12434374248924537, -0.24447768873916056, -2.60821558440803, -0.7132471849890912, -0.5580980457685073, -1.19865720078781, -2.8766041854502538, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4894859337370256, 0.8941110786251171, 0.9884818963113168, -1.1984877579817428, -2.214714887686934, -0.38041552288820757, 1.6710809034491936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960940678644, -0.4403409170672489, 0.02415444805994494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.047405458144199e-06, 0.0002817563916189022, 8.401794112132126e-05, 0.0, 0.0003576945439442653, 0.00017128584351477422, 4.241895279880636e-05, 0.0004499591846913434, -1.2656499568355628e-05, -0.00023947452302428265, -0.00015520550981206458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025488439698465194, 0.034753143094359555, -0.09029093803339643, -0.005658659621436673, -0.016527530357216394, 0.04118287179970025, 0.08339853596179836, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.03217883464038e-09, -5.1626905210071585e-09, -0.00030579478621716805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922386825645328, 0.23493691690624557, 0.8410564512649941, 0.0, -0.1243258594111105, -0.24446889925952728, -2.6082135201018084, -0.7132247038994421, -0.5580986285853954, -1.1986691367474456, -2.8766119583016656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48820087632289133, 0.8958431793631576, 0.983960534776307, -1.1987720604255176, -2.2155724461756536, -0.3783581789414705, 1.6752758485502535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960937612354, -0.4403409173222983, 0.024139171052652106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786489246427161e-06, 0.0002815146767031294, 7.505766203420739e-05, 0.0, 0.00035766156269743726, 0.00017578959266584843, 4.1286124428578224e-05, 0.0004496217929827031, -1.1656337761063967e-05, -0.00023871919271227572, -0.00015545702823389334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025701148282685583, 0.03464201476081067, -0.09042723070019727, -0.005686048875495764, -0.017151169774387676, 0.04114687893474189, 0.08389890202119733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.132577920404379e-09, -5.1009871084421215e-09, -0.00030554014585668624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092235922605165, 0.23495097923899583, 0.8410519427358509, 0.0, -0.12430799797295512, -0.24446039171558423, -2.6082114331239783, -0.7132022392024135, -0.5580992433130904, -1.1986810509852375, -2.8766197135440503, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4869052277139634, 0.8975696069788188, 0.9794325421284801, -1.1990577012557722, -2.2164615881936442, -0.37630277396989964, 1.679496053466264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960934548712, -0.4403409175740272, 0.024123908203004432]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.519918735469442e-06, 0.0002812466550050523, -9.017058286262138e-05, 0.0, 0.0003572287631076722, 0.00017015087886112826, 4.173955660569902e-05, 0.00044929394057188977, -1.2294553899290337e-05, -0.00023828475583984556, -0.00015510484769303776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.025912972178559337, 0.034528552313223757, -0.09055985295653808, -0.005712816605088591, -0.017782840359812042, 0.04110809943141729, 0.08440409832021027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.127284994485085e-09, -5.034578465706776e-09, -0.0003052569929535026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922332950507752, 0.23496502672304753, 0.841047783413629, 0.0, -0.12429016966556214, -0.24445225590891467, -2.60820928186934, -0.7131797919809006, -0.5580999330293639, -1.1986929512033815, -2.8766274348355845, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48559903131642573, 0.8992902496173529, 0.9748980930181969, -1.199344649530385, -2.2173827195828784, -0.3742494430608768, 1.6837417729196484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196093153261, -0.44034091782227236, 0.02410866107571083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.2551087796667704e-06, 0.0002809496810341711, -8.318644443892944e-05, 0.0, 0.00035656614785969763, 0.0001627161333910628, 4.3025092769582105e-05, 0.0004489444302589652, -1.3794325470608606e-05, -0.0002380043628809906, -0.000154425830679982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02612392795075296, 0.03441285277068236, -0.09068898220566399, -0.005738965492258566, -0.018422627784678763, 0.04106661818045598, 0.08491438906769068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.0322003801230195e-09, -4.964903312858732e-09, -0.0003049425458720436]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922307991070202, 0.23497905786820408, 0.8410556573019119, 0.0, -0.12427237387831729, -0.2444442940500671, -2.608207077567316, -0.7131573652116887, -0.5581006863642975, -1.1987048335720254, -2.8766351253435607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4842823300878567, 0.9010049998697255, 0.9703573543408388, -1.1996328745291291, -2.2183362506259474, -0.3721983176407974, 1.6880132741548193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960928754658, -0.44034091806592374, 0.024093431277851397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.991887509777812e-06, 0.0002806229031311392, 0.00015747776565822725, 0.0, 0.0003559157448970038, 0.00015923717695157525, 4.408604048309066e-05, 0.00044853538423953636, -1.5066698673928943e-05, -0.00023764737287945692, -0.00015381015952641166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026334024571381103, 0.0342950050474507, -0.09081477354716017, -0.005764499974883995, -0.01907062086137703, 0.041022508401587915, 0.08543002470341639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.555908666280711e-09, -4.8730279323739366e-09, -0.00030459595718869284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922284323115387, 0.23499307108162593, 0.8410620224473074, 0.0, -0.12425458744531685, -0.24443588510526554, -2.608204929517324, -0.7131349647765528, -0.5581013908433606, -1.1987166731633414, -2.8766428246415074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48295516731288507, 0.9027137532260882, 0.9658104886496258, -1.1999223453926828, -2.219322595734824, -0.37014952706588417, 1.6923108338763249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960925990926, -0.4403409183058999, 0.024078220512936645]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.7335909628940805e-06, 0.00028026426843671655, 0.00012730290790996507, 0.0, 0.00035572866000864066, 0.00016817889603117935, 4.296099983475214e-05, 0.00044800870271772164, -1.408958126273807e-05, -0.0002367918263207148, -0.00015398595893936561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02654325549943236, 0.034175067127253114, -0.09093731382426007, -0.005789417271074297, -0.019726902177531216, 0.040975811498265485, 0.08595119443011036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527463615746055e-09, -4.799523095846143e-09, -0.0003042152982949902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922261997224498, 0.2350070647912494, 0.8410577045336366, 0.0, -0.12423681243828566, -0.24442719122016499, -2.6082028373758583, -0.7131125929317202, -0.5581020469926288, -1.1987284688445206, -2.876650531726507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48161758806816896, 0.904416406601707, 0.9612576589459293, -1.2002130305739471, -2.2203421712282, -0.36810320061496893, 1.696634732660511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196092317279, -0.44034091854252083, 0.024063030469186026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.465178177833702e-06, 0.00027987419246927657, -8.635827341689408e-05, 0.0, 0.00035550014062387086, 0.00017387770201113094, 4.184282931522522e-05, 0.000447436896650261, -1.3122985361760713e-05, -0.0002359136235845094, -0.0001541416999878178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026751584894322514, 0.034053067512376585, -0.09105659407393087, -0.005813703625287087, -0.020391509867517234, 0.04092652901830437, 0.08647797568372015, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.636273932491716e-09, -4.732419414340443e-09, -0.00030380087501240055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922241016812146, 0.23502103740905048, 0.8410463694385787, 0.0, -0.12421905333043677, -0.24441836995158422, -2.608200790619741, -0.7130902517633231, -0.5581026658436722, -1.198740221602538, -2.8766582417647193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48026963952599694, 0.9061128577303539, 0.9566990298493572, -1.20050489804106, -2.221395396086243, -0.36605946817557733, 1.700985254766309, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960920279746, -0.44034091877582304, 0.024047862863995576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.1960824706491225e-06, 0.0002794523560217615, -0.0002267019011576197, 0.0, 0.00035518215697770964, 0.00017642537161540508, 4.0935122353427696e-05, 0.0004468233679431487, -1.2377020867531316e-05, -0.00023505516034913785, -0.00015420076425019393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026958970843440316, 0.03392902257293763, -0.09117258193144308, -0.005837349342256303, -0.02106449716086064, 0.04087464878783213, 0.08701044211595904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.786086760284027e-09, -4.666044771786301e-09, -0.00030335210380902497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922221440887018, 0.23503498739762702, 0.841036886455467, 0.0, -0.1242013481825966, -0.24441026653189415, -2.608198632835657, -0.7130679387372286, -0.5581034088108263, -1.1987519639596742, -2.876665895865233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4789113717793767, 0.9078030043511358, 0.9521347702517232, -1.200797914844916, -2.222482690370258, -0.3640184612869564, 1.7053626847014656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196091741422, -0.4403409190052954, 0.024032719370823248]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.915185025717901e-06, 0.0002789997715310093, -0.0001896596622333224, 0.0, 0.00035410295680355535, 0.0001620683938012719, 4.315568167552039e-05, 0.0004462605218899997, -1.4859343083454556e-05, -0.0002348471427225327, -0.00015308201027994006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027165354932404285, 0.03380293241563895, -0.09128519195267903, -0.005860336077119565, -0.021745885680302154, 0.04082013777241842, 0.08754859870313353, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.731050726891179e-09, -4.58944610775106e-09, -0.0003028698634465459]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922203164538525, 0.23504891307276912, 0.841032541842507, 0.0, -0.12418366740896726, -0.24440192084839657, -2.6081965020990285, -0.7130456612191032, -0.5581041338020172, -1.1987636644722774, -2.876673544051086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4775428382354116, 0.9094867432162603, 0.9475650547121593, -1.2010920480404839, -2.223604478160592, -0.3619803142765615, 1.7097673090060426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960914598313, -0.4403409192310516, 0.02401760180827296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.655269698775106e-06, 0.00027851350284206105, -8.689225920218913e-05, 0.0, 0.00035361547258678437, 0.00016691366995180907, 4.2614732565614394e-05, 0.00044555036250906017, -1.4499823817667592e-05, -0.00023401025206547227, -0.0001529637170595984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027370670879302096, 0.033674777302491084, -0.09139431079127737, -0.005882663911359049, -0.022435755806672526, 0.04076294020789779, 0.08809248609153901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.631816940030336e-09, -4.515125428379149e-09, -0.0003023512510057976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218624636338, 0.23506281281421168, 0.8410356756575126, 0.0, -0.12416600432264169, -0.24439321694763538, -2.608194436426376, -0.7130234228233399, -0.5581048018148895, -1.1987753136380845, -2.876681199480581, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47616409798292436, 0.9111639678647261, 0.9429900709564467, -1.2013872631601683, -2.224761182138141, -0.3599451670496676, 1.7141994056720824, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960911738547, -0.44034091945324066, 0.024002511926413173]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383635029025387e-06, 0.00027799482885125325, 6.26763001119526e-05, 0.0, 0.00035326172651137423, 0.0001740780152235415, 4.131345304538199e-05, 0.00044476791526665467, -1.3360257447749238e-05, -0.00023298331614080524, -0.0001531085898994188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.027574805049744477, 0.03354449296931504, -0.09149967511425215, -0.005904302393688978, -0.023134079550981332, 0.04070294453787818, 0.08864193332079673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.719530654727784e-09, -4.443781211465503e-09, -0.0003017976371957132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922170704203732, 0.23507668502075083, 0.8410423074849374, 0.0, -0.1241483623155468, -0.244384310557527, -2.6081924300125126, -0.7130012257667365, -0.5581054190160493, -1.1987869114340584, -2.876688859076571, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47477521540227136, 0.9128345692861699, 0.9384100182269607, -1.20168352459866, -2.225953224315494, -0.35791316440846443, 1.7186592461985255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960908809377, -0.44034091967180033, 0.02398745145288188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1084319293768643e-06, 0.00027744413078277237, 0.0001326365484943806, 0.0, 0.00035284014189772793, 0.00017812780216790056, 4.01282772728635e-05, 0.00044394113206605953, -1.2344023195454017e-05, -0.00023195591947688265, -0.00015319191979646822, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02777765161305974, 0.033412028428875376, -0.09160105458971957, -0.0059252287698322425, -0.02384084354705729, 0.04064005282406402, 0.08919681052886042, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.858339466261557e-09, -4.371193406864528e-09, -0.00030120947062583256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922156543450052, 0.23509052810004516, 0.8410492694389827, 0.0, -0.12413074689682618, -0.24437535618911002, -2.6081904678915984, -0.712979072046481, -0.5581060010212636, -1.1987984597786585, -2.8766965163409224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47337625952659734, 0.9144984368578705, 0.9338251048857156, -1.2019807958468574, -2.2271810265116145, -0.3558844549669417, 1.7231470978947316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960905813695, -0.44034091988659374, 0.023972422108249798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8321507362843026e-06, 0.00027686158588654494, 0.00013923908090758875, 0.0, 0.00035230837441229307, 0.00017908736833938907, 3.9242418287363135e-05, 0.0004430744051094812, -1.1640104287746735e-05, -0.00023096689200289316, -0.00015314528703072957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02797911751348016, 0.03327735143401081, -0.09169826682490159, -0.00594542496394866, -0.024556043922417028, 0.0405741888304541, 0.08975703392412263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.99136182881903e-09, -4.295868409399808e-09, -0.00030058689264164613]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092214376950768, 0.2351043404631002, 0.841055000947925, 0.0, -0.12411316316685755, -0.24436644803037927, -2.6081885369185116, -0.7129569637734708, -0.5581065615745155, -1.1988099601669355, -2.8767041654304397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4719673035386995, 0.916155459116594, 0.9292355465253229, -1.2022790396236822, -2.228445010501852, -0.3538591902620027, 1.7276632254874882, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196090276409, -0.44034092009746506, 0.023957425614455224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.554788474152601e-06, 0.00027624726110047753, 0.00011463017884518368, 0.0, 0.0003516745993725979, 0.000178163174614961, 3.861946173756925e-05, 0.0004421654602037304, -1.1211065038467111e-05, -0.00023000776553994804, -0.0001529817903483625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02817911975795758, 0.033140445174471, -0.09179116720785228, -0.005964875536498757, -0.025279679804751456, 0.04050529409878031, 0.0903225518551289, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.099211472283008e-09, -4.217426245952425e-09, -0.00029992987589149664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132402106286, 0.23511812054038544, 0.8410520894025295, 0.0, -0.12409562383109912, -0.2443578314158735, -2.608186590890484, -0.712934902017406, -0.5581071484951111, -1.1988214212369817, -2.8767117882556934, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47054842423382764, 0.9178055245993192, 0.9246415639932796, -1.202578217928743, -2.229745597925077, -0.3518375237867856, 1.7322078925422681, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196089970556, -0.4403409203040926, 0.023942463678312494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.2734802787669106e-06, 0.00027560154570521126, -5.8230907909955594e-05, 0.0, 0.000350786715168619, 0.0001723322901152663, 3.892056055380001e-05, 0.00044123512129748107, -1.1738411910820731e-05, -0.0002292214009220766, -0.0001524565050773675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028377586097436923, 0.033001309654503014, -0.09187965064086771, -0.0059835661012142315, -0.02601174846449523, 0.0404333295043409, 0.09089334109560107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.1170619527525975e-09, -4.1325504136064795e-09, -0.00029923872285463716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922122434115142, 0.23513186671753447, 0.8410480627601596, 0.0, -0.12407813314545002, -0.24434945545829273, -2.608184620574443, -0.7129128891496048, -0.5581077715045112, -1.198832843569758, -2.8767193803773026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4691197012732411, 0.9194485226447213, 0.9200433810360168, -1.2028782923185342, -2.2310832111884804, -0.34981960999287814, 1.7367813640484877, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960896649155, -0.44034092050638907, 0.02392753805860094]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.993598228687448e-06, 0.0002749235429804493, -8.053284739664491e-05, 0.0, 0.00034981371298213994, 0.00016751915161527365, 3.9406320815882495e-05, 0.0004402573560225493, -1.2460188001387484e-05, -0.00022844665552575148, -0.00015184243218659447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028574459211730487, 0.032859960908041684, -0.09196365914525552, -0.006001487795825586, -0.026752265268074542, 0.04035827587814968, 0.09146943012439056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.112808490593471e-09, -4.045929541332256e-09, -0.00029851239423111863]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211389827854, 0.23514557736365363, 0.8410578585477725, 0.0, -0.12406070988152301, -0.24434158934098602, -2.608182553769859, -0.7128909254979008, -0.5581085052234442, -1.1988442413850604, -2.8767269140492373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4676812169158026, 0.9210843438719359, 0.9154412233761499, -1.2031792237209296, -2.2324582726969604, -0.3478056037279826, 1.741383906369289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960893591872, -0.44034092070432945, 0.023912650529372945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7071673205114855e-06, 0.00027421292238309636, 0.00019591575225744434, 0.0, 0.00034846527854018143, 0.000157322346134472, 4.133609168080293e-05, 0.0004392730340808338, -1.4674378662152341e-05, -0.00022795630604805403, -0.00015067343869631415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02876968714876997, 0.032716424544291745, -0.09204315319733973, -0.006018628047907992, -0.027501230169602837, 0.0402801252979109, 0.09205084641602652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.114568185997018e-09, -3.958807443717854e-09, -0.0002977505845598786]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210672469882, 0.23515925083401482, 0.8410652320488057, 0.0, -0.12404332566823896, -0.24433336627992613, -2.608180522997439, -0.7128690180598636, -0.5581092132659031, -1.1988555845615416, -2.876734437299029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46623305579286745, 0.9227128804080058, 0.9108353175470177, -1.2034809732727259, -2.2338712072731286, -0.3457956600814619, 1.7460157904635891, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960890519567, -0.44034092089783095, 0.02389780286694324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4347159446389079e-06, 0.00027346940722347367, 0.00014747002066334785, 0.0, 0.0003476842656809194, 0.00016446122119761613, 4.0615448397339356e-05, 0.0004381487607450033, -1.4160849177094524e-05, -0.00022686352962361731, -0.00015046499583523993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02896322245870369, 0.03257073072139712, -0.09211811658264313, -0.00603499103592687, -0.028258691523363376, 0.04019887293041388, 0.09263768188600079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.144607672069865e-09, -3.870029836860596e-09, -0.0002969532485941604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210100400509, 0.23517288551398433, 0.8410664138041404, 0.0, -0.1240259996089749, -0.24432528532443024, -2.608178454395147, -0.7128471669546982, -0.5581099719448497, -1.198866887773201, -2.8767419218274246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4647753056448859, 0.9243340253193703, 0.9062258936717704, -1.2037835010299036, -2.235322437674143, -0.3437899350125588, 1.750677285561212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960887517417, -0.44034092108648143, 0.023882996819733292]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1441387459766836e-06, 0.0002726935993901465, 2.3635106694689962e-05, 0.0, 0.00034652118528124735, 0.0001616191099181937, 4.1372045842379415e-05, 0.0004370221033072508, -1.5173578930017302e-05, -0.0002260642331865976, -0.00014969056791598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029155002959631346, 0.03242289822728867, -0.09218847750494656, -0.006050555143554061, -0.029024608020289562, 0.04011450137806245, 0.09322990195245989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.004299680337448e-09, -3.7730098884789655e-09, -0.0002961209441989173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092209669726632, 0.23518647970489048, 0.8410609226416369, 0.0, -0.12400872906868333, -0.24431719191532206, -2.608176369004111, -0.7128253755692321, -0.5581107597717642, -1.1988781450453656, -2.876749374387809, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4633080561386832, 0.9259476735196431, 0.9016131818317626, -1.2040867669585253, -2.236812388228808, -0.34178858417897373, 1.7553686651971052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960884538656, -0.44034092127040986, 0.023868234227515342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.613477534914119e-07, 0.00027188381812338203, -0.00010982325006922625, 0.0, 0.000345410805831185, 0.00016186818216330927, 4.170782071484811e-05, 0.0004358277093212305, -1.575653829063398e-05, -0.00022514544329536624, -0.0001490512076832327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029344990124054126, 0.03227296400545834, -0.09225423680015506, -0.006065318572435898, -0.02979901109329317, 0.0400270166717004, 0.09382759271786134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.957524940023932e-09, -3.6785690750768175e-09, -0.0002952518443589767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093822929072, 0.2352000317341201, 0.8410524181684602, 0.0, -0.12399151746904731, -0.24430910863530028, -2.608174261444083, -0.7128036463850764, -0.5581115824848359, -1.1988893561534155, -2.876756791973215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46183139963036696, 0.9275537212519152, 0.8969974141792522, -1.2043907305783736, -2.238341482998964, -0.3397917636906221, 1.7600902039997306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960881578726, -0.4403409214495698, 0.0238535169087839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.748674497860114e-07, 0.0002710405845922016, -0.00017008946353326963, 0.0, 0.0003442319927206149, 0.0001616656004355191, 4.215120056168994e-05, 0.00043458368311318613, -1.645426143494226e-05, -0.0002242221609999945, -0.00014835170811919904, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029533130166324435, 0.03212095464544021, -0.09231535305020915, -0.006079272396967082, -0.030581895403125385, 0.039936409767033054, 0.09443077605250862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.91986084688446e-09, -3.5831994274456708e-09, -0.0002943463746288033]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373323128, 0.23521353992827793, 0.8410438725266971, 0.0, -0.12397436044111262, -0.244300887496518, -2.6081721601693726, -0.7127819829808627, -0.558112410947662, -1.1989005135506143, -2.876764184099484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4603454313905481, 0.9291520657795702, 0.8923788256592536, -1.204695351075815, -2.239910145922031, -0.33779963049762673, 1.7648421773105925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960878624786, -0.4403409216239188, 0.023838846682848473]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8992118888876934e-07, 0.0002701638831565353, -0.00017091283526128758, 0.0, 0.0003431405586938345, 0.00016442277564585636, 4.202549420018781e-05, 0.00043326808427352663, -1.6569256520598532e-05, -0.00022314794397777974, -0.0001478425253884784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029719364796376244, 0.03196689055310157, -0.09237177039997145, -0.006092409948825406, -0.031373258461334215, 0.03984266385990679, 0.09503946621723514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907879199330411e-09, -3.486980077253522e-09, -0.00029340451870856404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922092373722798, 0.23522700262504698, 0.8410374403757168, 0.0, -0.12395726578111037, -0.24429269050492022, -2.6081700407288655, -0.7127603871926259, -0.5581132705496118, -1.1989116211622244, -2.8767715407119447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.458850249996433, 0.9307426050694383, 0.8877576552539141, -1.2050005870186693, -2.2415187994729133, -0.3358123427934258, 1.7696248590278236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196087569427, -0.4403409217933179, 0.023824225354744655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.993361838705048e-11, 0.0002692539353811438, -0.00012864301960679008, 0.0, 0.0003418932000452387, 0.00016393983195510124, 4.2388810139131095e-05, 0.0004319157647347982, -1.719203899706572e-05, -0.00022215223220196987, -0.00014713224921229104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029903627882302698, 0.03181078579736128, -0.09242340810678894, -0.006104718857087361, -0.03217307101764898, 0.039745754084018536, 0.09565363434462144, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.861033564134219e-09, -3.387982440439172e-09, -0.0002924265620763873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922093803793915, 0.23524041814845156, 0.8410374906842297, 0.0, -0.12394022730095001, -0.2442843307062041, -2.6081679394647272, -0.712738862857545, -0.558114124022187, -1.198922669739127, -2.8767788742441045, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4573459573374052, 0.9323252377254454, 0.8831341459157536, -1.2053063966618953, -2.2431678654292573, -0.33383006012496247, 1.7744385224039096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960872769383, -0.4403409219577329, 0.02380965473961995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.860142235474362e-07, 0.0002683104680918212, 1.0061702575075656e-06, 0.0, 0.0003407696032069348, 0.00016719597432282023, 4.202528276281991e-05, 0.00043048670161862127, -1.706945150298024e-05, -0.0002209715380559683, -0.0001466706431985636, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03008585318055555, 0.031652653120141615, -0.09247018676321055, -0.00611619286451865, -0.032981319126879634, 0.039645653369266835, 0.09627326752172037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.849774123333481e-09, -3.2882997372638714e-09, -0.0002914123024940956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922096657396688, 0.2352537848481625, 0.8410424879608319, 0.0, -0.12392323099804707, -0.24427550322994218, -2.608165926451545, -0.7127174147928246, -0.5581148993177725, -1.1989336427949417, -2.876786209655038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4558326592403161, 0.9338998624960788, 0.8785085463058647, -1.2056127377883856, -2.2448577636846556, -0.3318529440691488, 1.7792834377311177, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960869837198, -0.44034092211708964, 0.023795136622358486]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.707205544453632e-07, 0.00026733399421898104, 9.99455320436035e-05, 0.0, 0.00033992605805876916, 0.00017654952523818242, 4.026026364787405e-05, 0.00042896129440782137, -1.550591171088359e-05, -0.0002194611162937864, -0.000146708218664564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030265961941782726, 0.03149249541266861, -0.09251199219777764, -0.0061268225298059045, -0.03379796510796265, 0.039542321116274225, 0.09689830654416252, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.86437310864071e-09, -3.187134913313221e-09, -0.00029036234522933065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922100965552448, 0.23526710107514773, 0.8410490640684287, 0.0, -0.12390627994451152, -0.2442664026430487, -2.60816399756591, -0.7126960453592284, -0.5581156008578939, -1.198944539937928, -2.8767935444610173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4543104655338203, 0.9354663782831726, 0.8738811111354717, -1.2059195673919778, -2.246588910859805, -0.3298811581868147, 1.7841598707715598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960866898349, -0.4403409222713018, 0.023780672785392188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.616311522513805e-07, 0.0002663245397044324, 0.0001315221519361624, 0.0, 0.000339021070711086, 0.0001820117378696219, 3.857771269517252e-05, 0.0004273886719234314, -1.4030802428831007e-05, -0.00021794285972423394, -0.0001466961195899939, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030443874129915626, 0.031330315741874865, -0.09254870340785973, -0.006136592071843622, -0.03462294350299033, 0.039435717646682064, 0.09752866080883925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.877696582075045e-09, -3.0842428966251893e-09, -0.00028927673932593894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092210673237465, 0.235280365187046, 0.8410550975979828, 0.0, -0.12388938100491373, -0.24425724891563522, -2.608162132255566, -0.7126747564615128, -0.5581162500032212, -1.1989553642943187, -2.8768008700700447, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4527794894455337, 0.9370246848142204, 0.8692520991614596, -1.2062268420164741, -2.2483617212788136, -0.3279148672301889, 1.7890680851332526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960863958802, -0.4403409224202819, 0.023766265007226756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1533644406949973e-06, 0.00026528223796546833, 0.00012067059108091881, 0.0, 0.00033797879195573256, 0.00018307454826957186, 3.73062068809094e-05, 0.00042577795431106595, -1.2982906544877191e-05, -0.0002164871278149365, -0.00014651218054448473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030619521765731874, 0.031166130620956245, -0.09258023948024134, -0.006145492489924126, -0.03545620838017727, 0.03932581913251551, 0.09816428723385391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.879091789393594e-09, -2.979601671892309e-09, -0.0002881555633086335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092211398984335, 0.2352935755878579, 0.8410555050831465, 0.0, -0.12387255996124569, -0.24424862974986714, -2.6081602276898908, -0.7126535474193972, -0.5581169529252559, -1.198966136758033, -2.8768081474179703, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4512398472649066, 0.9385746831577152, 0.8646217720329866, -1.20653451772497, -2.2501766065511055, -0.32595423653796046, 1.7940083427031794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960861098235, -0.4403409225636437, 0.023751915023692883]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.451493739797756e-06, 0.0002642080162376779, 8.149703274743813e-06, 0.0, 0.0003364208733607873, 0.00017238331536136223, 3.809131350543452e-05, 0.00042418084231146783, -1.4058440694780964e-05, -0.00021544927428580668, -0.00014554695851592048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03079284361254177, 0.030999966869896325, -0.0926065425694596, -0.00615351416991691, -0.036297705445837984, 0.03921261384456869, 0.09880515139853736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.721133778020836e-09, -2.8672360332484574e-09, -0.00028699967067747945]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221227393265, 0.23530673061450377, 0.8410565945129704, 0.0, -0.12385584263010913, -0.24424086611527335, -2.608158181332645, -0.7126324177743517, -0.5581178155082985, -1.1989768780505843, -2.8768153374764402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4496916576505383, 0.9401162761748174, 0.8599903925518251, -1.2068425503342475, -2.252033976608772, -0.3239994313693354, 1.798980905793647, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960858334568, -0.4403409227013466, 0.02373762464347082]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.749896630280465e-06, 0.0002631005329173592, 2.1788596477419196e-05, 0.0, 0.00033434662273115046, 0.00015527269187593876, 4.092714491516038e-05, 0.0004225929009102559, -1.7251660853081745e-05, -0.0002148258510234415, -0.00014380116939687583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030963792287366225, 0.03083186034204511, -0.09262758962322996, -0.006160652185548577, -0.037147401153326536, 0.0390961033725009, 0.09945126180934931, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.527332100915927e-09, -2.7540586281405656e-09, -0.0002858076044412479]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922132919391548, 0.23531982864719386, 0.841063223931719, 0.0, -0.1238392122362804, -0.24423321920061875, -2.6081560758377376, -0.7126113735463446, -0.5581187527877131, -1.1989875685837716, -2.8768224695965015, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44813504236501883, 0.941649368224787, 0.8553582259425409, -1.2071508962014381, -2.2539342407502954, -0.3220506177501416, 1.8039860375006576, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196085635504, -0.44034092283093423, 0.023723395630806134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.03601300906797e-06, 0.0002619606538019357, 0.0001325883749712573, 0.0, 0.0003326078765743858, 0.000152938293091898, 4.210989814999217e-05, 0.0004208845601416009, -1.8745588290554045e-05, -0.00021381066374907771, -0.00014264240122127474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031132305710390124, 0.030661840999390497, -0.09264333218568391, -0.006166917343814103, -0.03800528283046801, 0.038976272383875785, 0.10010263414021117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.959053397238659e-09, -2.5917525910362977e-09, -0.00028458025329374653]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922144519139135, 0.2353328680869434, 0.8410676669346647, 0.0, -0.12382263726512502, -0.24422491913739267, -2.6081540567514145, -0.7125904214700881, -0.5581196148820815, -1.1989981758353803, -2.8768295968508615, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4465701270552781, 0.9431738636921824, 0.8507255432224222, -1.207459510790999, -2.2558778039573784, -0.3201079635102819, 1.8090239953968683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960854533182, -0.4403409229545072, 0.023709229726479042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199495176391782e-06, 0.00026078879499084965, 8.886005891627416e-05, 0.0, 0.0003314994231077098, 0.00016600126452181964, 4.038172646392046e-05, 0.00041904152513015484, -1.7241887368174105e-05, -0.0002121450321726098, -0.00014254508720348415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03129830619481516, 0.030489909347908482, -0.09265365440237223, -0.006172291791215753, -0.03887126414166291, 0.038853084797193384, 0.1007591579242136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.643715639193411e-09, -2.4714595723696988e-09, -0.00028331808654188023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922157604694372, 0.23534584736592495, 0.8410668504909772, 0.0, -0.12380612670554354, -0.24421636926187285, -2.6081520936769205, -0.7125695627130906, -0.5581204332535905, -1.1990087053101475, -2.8768367071660017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4449970414885467, 0.94468966757663, 0.8460926213960657, -1.2077683487512805, -2.2578650650041974, -0.3181716381099931, 1.8140950299117282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960852664008, -0.44034092307275113, 0.023695128639661108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6171110473867365e-06, 0.0002595855796310719, -1.6328873750977248e-05, 0.0, 0.0003302111916294966, 0.00017099751039630092, 3.9261489880747366e-05, 0.0004171751399507709, -1.636743018040559e-05, -0.0002105894953461487, -0.00014220630280115963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146171133462829, 0.030316077688951552, -0.09265843652713089, -0.006176759205631756, -0.0397452209363828, 0.038726508005776, 0.1014206902972002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.738346712078653e-09, -2.3648780842152937e-09, -0.00028202173635868386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922172187093444, 0.235358764914175, 0.8410654898822433, 0.0, -0.12378970357889556, -0.24420812020919186, -2.608150095496031, -0.7125487967681349, -0.5581213019711135, -1.1990191755044783, -2.8768437658949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4434159178476597, 0.9461966869587102, 0.8414597384723083, -1.2080773645313565, -2.2598964193485593, -0.31624181071038876, 1.8191993904816701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960850686543, -0.4403409231858745, 0.023681094082104545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.916479814417497e-06, 0.00025835096500088103, -2.721217467799101e-05, 0.0, 0.0003284625329597579, 0.00016498105361986836, 3.996361778996376e-05, 0.00041531889911317413, -1.7374350460272283e-05, -0.00020940388661766464, -0.00014117457796544163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03162247281773904, 0.03014038764160504, -0.09265765847514915, -0.006180315601519984, -0.040627086887241, 0.038596547992087005, 0.10208721139883624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.954931207271424e-09, -2.2624669460461017e-09, -0.00028069115113125986]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092218820509567, 0.2353716191701673, 0.8410633476626547, 0.0, -0.1237733545919424, -0.24419974024874178, -2.6081481290056185, -0.7125281285220432, -0.5581221523588407, -1.1990295706059233, -2.8768507967261296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44182689050891993, 0.9476948312002192, 0.8368271724979245, -1.2083865130951508, -2.2619722611590123, -0.31431865007858156, 1.824337328212959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960848777775, -0.44034092329331354, 0.02366712775352238]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2036004456094876e-06, 0.0002570851198458028, -4.28443917725028e-05, 0.0, 0.00032697973906325436, 0.00016759920900176153, 3.932980824228668e-05, 0.000413364921835116, -1.7007754542764683e-05, -0.00020790202889795674, -0.0001406166245909901, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03178054677479595, 0.02996288483018038, -0.09265131948767472, -0.006182971275886583, -0.04151683620905522, 0.038463212636144044, 0.10275875462577573, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.817535953222311e-09, -2.1487807233846523e-09, -0.00027932657164330354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209221916360722, 0.23538440877937317, 0.84113623431204, 0.0, -0.12375716825404547, -0.24419305877140782, -2.608145824566453, -0.7125075583188882, -0.5581233419857754, -1.1990400234739393, -2.87685766726029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.44024420765108996, 0.9491709563510456, 0.832235792593017, -1.208693270166394, -2.2640751584080365, -0.31229657903902314, 1.829464531952495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960847210564, -0.4403409233974491, 0.023653231142714507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.861953054122794e-07, 0.000255792184117114, 0.0014577329877055664, 0.0, 0.00032372675793870207, 0.00013362954667919574, 4.6088783318532606e-05, 0.0004114040630983184, -2.3792538695589267e-05, -0.0002090573603190461, -0.0001374106832015365, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03165365715659935, 0.02952250301652904, -0.0918275980981496, -0.006135141424863823, -0.04205794498048291, 0.04044142079116874, 0.10254407479071907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1344232765148914e-09, -2.0827119200966643e-09, -0.00027793221615745386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922201868250198, 0.23539634306990492, 0.8412314006554471, 0.0, -0.12374207508064684, -0.24418789206263306, -2.6081432812967753, -0.7124882530489969, -0.5581248514787112, -1.1990499100341336, -2.8768639699113385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43850370439191116, 0.9507742115167876, 0.8272174784440234, -1.209027128457125, -2.266421303994671, -0.30998379134964577, 1.8351043704068524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846727415, -0.44034092351037646, 0.02364019598329647]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0464356000538463e-06, 0.00023868581063525855, 0.0019033268681426727, 0.0, 0.00030186346797247786, 0.00010333417549517549, 5.0865393554811415e-05, 0.0003861053978273925, -3.0189858715893594e-05, -0.00019773120388399588, -0.00012605302097634758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.034810065183576266, 0.03206510331484076, -0.10036628297987271, -0.006677165814621422, -0.0469229117326932, 0.04625575378754693, 0.11279676908714747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.66298946820811e-10, -2.2585461717950393e-09, -0.0002607031883607115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922216437310262, 0.2354080849464401, 0.8413213449530466, 0.0, -0.12372725721475548, -0.24418254640448694, -2.6081406111655814, -0.7124692442472988, -0.5581265156307138, -1.1990596621045952, -2.8768701100452763, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43673363940883975, 0.9523871568461224, 0.8221391334650482, -1.2093648423795467, -2.26884706203803, -0.30766750998431247, 1.840851733829424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960846677342, -0.44034092362250954, 0.023627366179124365]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.913812013021153e-06, 0.00023483753070400228, 0.00179888595198974, 0.0, 0.0002963573178272846, 0.00010691316292219053, 5.340262387741816e-05, 0.0003801760339596849, -3.328304005376323e-05, -0.00019504140923134718, -0.00012280267875417538, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03540129966142834, 0.03225890658669601, -0.10156689957950295, -0.006754278448434319, -0.0485151608671812, 0.046325627306666436, 0.11494726845142962, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0014635555554529e-10, -2.242661711052622e-09, -0.00025659608344215124]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922230828349167, 0.23542179120280785, 0.8413961196175765, 0.0, -0.1237101320622456, -0.2441748125719034, -2.608137768907168, -0.7124473589817228, -0.5581281884138987, -1.1990708510518875, -2.8768772695111755, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4350979902425157, 0.9538648375688505, 0.8174609802263084, -1.2096783122332178, -2.271137094484585, -0.305621782567045, 1.846191036079717, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960845977244, -0.4403409237343511, 0.02361258903531463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8782077809993562e-06, 0.0002741251273545041, 0.0014954932906001, 0.0, 0.00034250305019766023, 0.0001546766516706125, 5.684516826768007e-05, 0.0004377053115208709, -3.3455663696616285e-05, -0.00022377894584475218, -0.0001431893179887565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03271298332648065, 0.029553614454562817, -0.09356306477479633, -0.006269397073421333, -0.04580064893110514, 0.04091454834535009, 0.10678604500586072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4001961193872394e-09, -2.236830667351529e-09, -0.0002955428761946808]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922243783393282, 0.23543903852997633, 0.8414513434500096, 0.0, -0.12368880508011355, -0.24416378984995993, -2.60813464483527, -0.7124202454252593, -0.5581298364460988, -1.1990846663697565, -2.876886296613515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4336623984435202, 0.9551532708001835, 0.8133606711026311, -1.209957272600563, -2.273199334011333, -0.3039200237919479, 1.850916595958042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196084406267, -0.44034092384720275, 0.023594268486829852]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.591008822977664e-06, 0.0003449465433696476, 0.001104476648661621, 0.0, 0.0004265396426407557, 0.00022045443886932763, 6.248143796103482e-05, 0.0005422711292714019, -3.296064400230728e-05, -0.0002763063573822093, -0.00018054204678421757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02871183597991043, 0.02576866462665916, -0.08200618247354668, -0.00557920734690619, -0.041244790534955666, 0.034035175501941975, 0.09451119756650121, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.8291438123780864e-09, -2.2570332791828863e-09, -0.00036641096969553655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922255106794738, 0.23546013123742882, 0.8414867720698173, 0.0, -0.12366286242224352, -0.24414972837577267, -2.6081311939056873, -0.7123873802711952, -0.558131470146458, -1.1991013861642983, -2.876897373484767, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43242675695397453, 0.9562573128632461, 0.8098307629874593, -1.2102024622712715, -2.2750240339463406, -0.30252510162345925, 1.8550265512441675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960840910455, -0.44034092395784474, 0.023572049757173866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.26468029088339e-06, 0.0004218541490494525, 0.0007085723961537018, 0.0, 0.0005188531574006369, 0.00028122948374484466, 6.901859164659148e-05, 0.0006573030812827114, -3.267400718439803e-05, -0.0003343958908373568, -0.00022153742504650204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02471282979091402, 0.022080841261251077, -0.07059816230343761, -0.004903793414171123, -0.036493998700152935, 0.027898443369773075, 0.0821991057225074, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.304433286892409e-09, -2.2128403986714446e-09, -0.000444374593119745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922265159170025, 0.23548434886488395, 0.8415061255847035, 0.0, -0.1236330840946502, -0.24413351552177873, -2.608127454022146, -0.7123497254554765, -0.5581331059967973, -1.19912053705499, -2.8769101520880205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.43135851539591985, 0.9572093754222624, 0.8067750353053372, -1.2104195732844663, -2.276643595151556, -0.3013598281014676, 1.8586187114510089, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960836810974, -0.44034092406159986, 0.023546586131306835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.010475057647412e-06, 0.0004843525491029461, 0.00038707029772529206, 0.0, 0.0005955665518662969, 0.0003242570798786655, 7.479767081710877e-05, 0.0007530963143733585, -3.2717006786872644e-05, -0.00038301781383230676, -0.00025557206506673664, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021364831161093535, 0.01904125118032559, -0.06111455364244099, -0.00434222026389549, -0.032391224104307406, 0.023305470439832707, 0.07184320413682947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.19896031598218e-09, -2.0751025149419598e-09, -0.000509272517340654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922274555400075, 0.23551049919664788, 0.8415149219583403, 0.0, -0.12360081504552632, -0.24411619699799172, -2.6081235111311813, -0.712308950582451, -0.5581347560571188, -1.1991412817206182, -2.876924034508455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4304134333681977, 0.9580505897866057, 0.8040671225441811, -1.2106158703853926, -2.2781080914157794, -0.30034361325339415, 1.861827325592487, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960832140596, -0.44034092415520626, 0.023519010503724798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8792460097681025e-06, 0.0005230066352782863, 0.00017592747273691278, 0.0, 0.000645380982477355, 0.00034637047574014696, 7.885781929856352e-05, 0.0008154974605094604, -3.3001206429091666e-05, -0.00041489331256218425, -0.0002776484086882363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018901640554443433, 0.016824287286867967, -0.05415825522312133, -0.003925942018529482, -0.029289925284466382, 0.020324296961469136, 0.06417228282956303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.340756875042724e-09, -1.8721281955298883e-09, -0.0005515125516407263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922283902802277, 0.23553740499180734, 0.8415182253375447, 0.0, -0.12356741262006192, -0.244098656648433, -2.6081194585706613, -0.7122667452605677, -0.5581364278203959, -1.1991627663390112, -2.876938417438849, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4295475700577736, 0.9588204602625764, 0.8015834397600468, -1.2107984291261271, -2.2794706522647883, -0.2994086858988451, 1.8647869579812928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960827229942, -0.4403409242374828, 0.02349046859225637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8694804402221444e-06, 0.0005381159031892923, 6.606758408896761e-05, 0.0, 0.000668048509288048, 0.00035080699117424197, 8.105121039951375e-05, 0.0008441064376684413, -3.3435265540814266e-05, -0.0004296923678604655, -0.000287658607876933, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01731726620848244, 0.015397409519414065, -0.04967365568268607, -0.003651174814689638, -0.027251216980177163, 0.01869854709098071, 0.059192647776113216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.821306158070047e-09, -1.6455303699486633e-09, -0.0005708382293685547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092229362213521, 0.23556419214109076, 0.8415193673058253, 0.0, -0.12353391477712479, -0.24408145874473222, -2.608115372253596, -0.7122244048578634, -0.5581381237752528, -1.1991843319310758, -2.8769528395699946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42872445430342665, 0.9595510565704616, 0.7992223359452336, -1.2109731199137916, -2.280777720365814, -0.2985065236544123, 1.8676104953770492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196082231266, -0.4403409243088011, 0.02346183822581013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9438665863407815e-06, 0.0005357429856686259, 2.283936561278392e-05, 0.0, 0.0006699568587426542, 0.0003439580740157031, 8.17263413041995e-05, 0.000846808054083768, -3.39190971396814e-05, -0.0004313118412897082, -0.000288442622914387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01646231508693933, 0.01461192615770454, -0.04722207629626339, -0.003493815753291094, -0.026141362020514175, 0.018043244888655965, 0.056470747915129293, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.83456558593435e-09, -1.426367202242299e-09, -0.000572607328924798]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922303880110799, 0.23559038168015178, 0.8415199852882396, 0.0, -0.1235009259124147, -0.24406483268837104, -2.6081113018315367, -0.7121826869037292, -0.5581398408669545, -1.1992055894462346, -2.876967032815702, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42791895589001544, 0.9602641198930109, 0.7969141609822934, -1.2111440345584141, -2.2820628385253374, -0.2976091306509349, 1.8703766996585587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960817519064, -0.4403409243703063, 0.02343363234899367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0515951175859435e-06, 0.0005237907812203649, 1.2359648284266457e-05, 0.0, 0.0006597772942017476, 0.000332521127223907, 8.140844119091067e-05, 0.0008343590826838142, -3.4341834033013567e-05, -0.0004251503031771353, -0.00028386491415034406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016109968268223928, 0.014261266450985874, -0.04616349925880549, -0.0034182928924479396, -0.02570236319046215, 0.017947860069547936, 0.055324085630191866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.587193975638144e-09, -1.2301036995276342e-09, -0.00056411753632922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922314643975465, 0.23561584225978577, 0.8415206281416071, 0.0, -0.12346865914893124, -0.24404875443383964, -2.6081072718949243, -0.7121418622418272, -0.5581415717556476, -1.1992263960601717, -2.8769809036549896, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4271176920472807, 0.9609710640627841, 0.7946219475397546, -1.2113134147462656, -2.2833449298152786, -0.29670604552711033, 1.8731283167796038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960812893364, -0.44034092442329237, 0.023406033978459983]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152772933227082e-06, 0.0005092115926796831, 1.2857067350550212e-05, 0.0, 0.0006453352696690721, 0.0003215650906277757, 8.059873225149452e-05, 0.0008164932380410139, -3.461777386295665e-05, -0.00041613227874423325, -0.0002774167857476666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016025276854695188, 0.014138883395464165, -0.045844268850776165, -0.0033876037570306798, -0.025641825798819465, 0.018061702476492185, 0.05503234242090225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.251399377513169e-09, -1.0597212265636223e-09, -0.0005519674106737503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092232580107623, 0.23564067171667163, 0.8415212349419124, 0.0, -0.1234370605731956, -0.24403306406223987, -2.608103288474411, -0.7121018685308353, -0.5581433072688579, -1.1992467787880954, -2.87699447765998, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42631633281947695, 0.9616754935931877, 0.792333738387956, -1.2114820654238903, -2.2846310717664897, -0.29579816557776584, 1.8758799956162546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960808423015, -0.4403409244688435, 0.023379000395382613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2314201529564266e-06, 0.0004965891377175496, 1.2136006107188386e-05, 0.0, 0.0006319715147126685, 0.0003138074319952333, 7.966841026668133e-05, 0.000799874219836588, -3.4710264206142476e-05, -0.0004076545584751738, -0.0002714800998085875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016027184556074832, 0.014088590608071366, -0.045764183035973204, -0.003373013552493929, -0.025722839024224495, 0.01815759898688995, 0.055033576733016905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.940694945966608e-09, -9.110227440188435e-10, -0.000540671661547411]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209223372539627, 0.23566506806782841, 0.8415217812975562, 0.0, -0.12340594956291107, -0.24401758090343914, -2.6080993451677648, -0.7120624836986472, -0.5581450407705657, -1.1992668474692554, -2.8770078362267806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42551557505713944, 0.9623767297213253, 0.7900514091170274, -1.2116499838904833, -2.2859214864877115, -0.29489107317242, 1.8786305914415817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960804069877, -0.44034092450770895, 0.023352380809571575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2905772941065556e-06, 0.00048792702313550185, 1.0927112874049084e-05, 0.0, 0.0006222202056907677, 0.00030966317601457835, 7.88661329248291e-05, 0.0007876966437629345, -3.4670034157743676e-05, -0.0004013736231996911, -0.00026717133601586484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01601515524674981, 0.014024722562751344, -0.045646585418570494, -0.003358369331861143, -0.0258082944244407, 0.018141848106916394, 0.055011916506542455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.706274311049773e-09, -7.773093037112224e-10, -0.0005323917162207316]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922348953618178, 0.23568922979927492, 0.8415222566785925, 0.0, -0.123375129465284, -0.24400216448610904, -2.608095430822606, -0.712023463875547, -0.5581467688719711, -1.1992867246130448, -2.8770210672879366, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42471767050002407, 0.9630727822489621, 0.7877811163116816, -1.2118169029211905, -2.28721408021122, -0.29399025899148507, 1.8813739028142424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960799793762, -0.4403409245403216, 0.023326009828649293]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3399310956571104e-06, 0.00048323462893022737, 9.507620725404603e-06, 0.0, 0.0006164019525410937, 0.00030832834660205323, 7.828690317029863e-05, 0.000780396462003816, -3.456202810875578e-05, -0.0003975428757877269, -0.00026462122312433816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015958091142307503, 0.013921050552737518, -0.045405856106917414, -0.003338380614145172, -0.02585187447017159, 0.018016283618698822, 0.05486622745321367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.552228758823872e-09, -6.522531359252474e-10, -0.000527419618445673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092236089442465, 0.2357133007651516, 0.8415226672037902, 0.0, -0.12334445117290906, -0.24398673651659994, -2.6080915348528966, -0.7119846230807773, -0.5581484910085028, -1.199306504474441, -2.877034237148521, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42392436326708854, 0.9637620898156535, 0.785527656721029, -1.2119826123190947, -2.2885072294691815, -0.29309891318302905, 1.8841050985136476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196079556518, -0.4403409245668912, 0.023299761418517764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.388161294365743e-06, 0.0004814193175336523, 8.210503954310316e-06, 0.0, 0.0006135658474991242, 0.00030855939018207835, 7.791939418756594e-05, 0.0007768158953953921, -3.4442730633713985e-05, -0.0003955972279284372, -0.00026339721168615413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015866144658710776, 0.013786151333827379, -0.045069191813052134, -0.003314187958082865, -0.02586298515922863, 0.01782691616911975, 0.054623913988103075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.457162595218221e-09, -5.313923472491648e-10, -0.0005249682026306076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922373096431715, 0.2357373554602591, 0.8415230305637231, 0.0, -0.12331383313096314, -0.24397127446279795, -2.6080876499174175, -0.71194585879409, -0.5581502083641651, -1.1993262395279525, -2.8770473817984348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4231361474736072, 0.9644441377747965, 0.7832924464386829, -1.2121470755077381, -2.2898008375515504, -0.292217667083622, 1.8868230698752826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960791368715, -0.44034092458751367, 0.023273566174345575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4404014132461273e-06, 0.00048109390215006183, 7.267198659375373e-06, 0.0, 0.0006123608389183291, 0.00030924107603955115, 7.769870958462718e-05, 0.0007752857337444723, -3.4347113243743554e-05, -0.00039470107022578484, -0.0002628929982758232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015764315869626497, 0.013640959182861963, -0.04470420564692132, -0.003289263772868496, -0.025872161647381108, 0.017624921988140904, 0.05435942723269867, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.392931709869209e-09, -4.124487802740948e-10, -0.0005239048834437878]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092238558825656, 0.23576141053205174, 0.8415233686300534, 0.0, -0.12328325243654976, -0.2439557920151657, -2.6080837724010726, -0.7119071414159466, -0.5581519227870049, -1.199345945387338, -2.8770605110628282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4223523698543891, 0.9651193702015691, 0.7810737984948897, -1.2123104169868437, -2.2910962516623736, -0.29134533396449097, 1.8895301632215622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960787200638, -0.4403409246022554, 0.023247404124884127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4983649688536877e-06, 0.0004811014358528989, 6.761326606055589e-06, 0.0, 0.0006116138882675735, 0.00030964895264502747, 7.755032689620944e-05, 0.0007743475628682688, -3.4288456795332206e-05, -0.00039411718771227295, -0.0002625852878715163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015675552384362555, 0.013504648535452373, -0.04437295887586491, -0.0032668295821129466, -0.02590828221646176, 0.017446662382620555, 0.054141866925591864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.336152004959027e-09, -2.9483383204032195e-10, -0.0005232409892289644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922398394839423, 0.23578544723407127, 0.8415237008592102, 0.0, -0.12325272323726047, -0.2439403182548261, -2.608079901591061, -0.7118684876951991, -0.5581536360211438, -1.1993656140432984, -2.8770736183330112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42157170330215116, 0.9657887980086253, 0.7788682009049951, -1.2124728538313292, -2.292395659042311, -0.2904799007452496, 1.8922307511121659, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960783064311, -0.44034092461119667, 0.023221286690121322]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5613165727152883e-06, 0.00048073404039043435, 6.644583136598058e-06, 0.0, 0.0006105839857859857, 0.0003094752067921484, 7.741620023622234e-05, 0.0007730744149506638, -3.426468277858962e-05, -0.00039337311920644867, -0.00026214540366160043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01561333104475981, 0.013388556141123548, -0.04411195179789197, -0.003248736889710461, -0.025988147598741438, 0.01730866438482799, 0.054011757812075435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.272654326006525e-09, -1.788258857433844e-10, -0.0005223486952560803]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092241153103414, 0.23580943343363525, 0.8415240404833962, 0.0, -0.1232222746465587, -0.24392488207649005, -2.608076038413205, -0.7118299333489168, -0.5581553493164322, -1.1993852276726218, -2.8770866904437438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42079265955417344, 0.9664535785191612, 0.7766716961082093, -1.212634621195772, -2.293701407394966, -0.2896193457177761, 1.8949296662867212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960778965756, -0.440340924614439, 0.02319523811198458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.627238943820995e-06, 0.000479723991279697, 6.792483720689729e-06, 0.0, 0.0006089718140354803, 0.0003087235667211426, 7.726355711621118e-05, 0.000771086925645637, -3.426590576893101e-05, -0.00039227258646606824, -0.0002614422146470036, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015580874959554462, 0.013295610210719745, -0.04393009593571532, -0.003235347288853942, -0.02611496705310561, 0.017211100549470552, 0.05397830349110793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.197111136692185e-09, -6.484728093278991e-11, -0.0005209715627347895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092242500054431, 0.23583333917995253, 0.8415243937262556, 0.0, -0.12319193475318685, -0.24390950385004634, -2.6080721843085497, -0.7117915131284361, -0.5581570633418861, -1.1994047687729104, -2.8770997147905937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4200139636292416, 0.9671147104640737, 0.7744808856812928, -1.2127959181453245, -2.295015497776658, -0.28876212112143645, 1.8976310505495397, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960774910598, -0.4403409246120918, 0.02316928194668761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6939020335182154e-06, 0.00047811492634575376, 7.064857187734985e-06, 0.0, 0.0006067978674369437, 0.00030756452887392905, 7.70820931088602e-05, 0.0007684044096126242, -3.428050907739793e-05, -0.0003908220057691243, -0.0002604869369985441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015573918498637348, 0.013222638898248726, -0.043816208538330355, -0.00322593899105221, -0.026281807633830957, 0.017144491926792838, 0.05402768525636815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.110315293499276e-09, 4.6944804177953823e-11, -0.0005191233059394407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922438798573534, 0.2358571444272394, 0.8415247611308359, 0.0, -0.12316172246009313, -0.24389419335789833, -2.608068340507095, -0.7117532505645536, -0.558158778287458, -1.199424225430224, -2.8771126829367297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41923473532055916, 0.9677728866796532, 0.7722934161990574, -1.212956881883158, -2.2963393354168686, -0.2879073096273501, 1.9003377944197228, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960770902595, -0.4403409246042542, 0.023143434124516634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7596058447164707e-06, 0.000476104945737298, 7.348091605041611e-06, 0.0, 0.0006042458618744598, 0.00030620984296020646, 7.687602909510037e-05, 0.0007652512776494267, -3.429891143800084e-05, -0.0003891331462746232, -0.00025936292271699256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0155845661736487, 0.013163524311589642, -0.04374938964470688, -0.0032192747566692206, -0.02647675280421163, 0.017096229881726443, 0.054134877403664294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.01600633038393e-09, 1.5675137198967494e-10, -0.0005169564434195082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922452916000858, 0.2358808403621116, 0.8415251397821107, 0.0, -0.12313164583970654, -0.24387895172115687, -2.6080645077163536, -0.711715155813482, -0.5581604940444943, -1.1994435924773454, -2.87712559131105, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41845450336903484, 0.9684284818251855, 0.7701080173027351, -1.2131175865810657, -2.2976737120383386, -0.2870545511453888, 1.9030514941192362, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196076694342, -0.4403409245910031, 0.02311770150108781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8234854651376114e-06, 0.0004739186974440934, 7.573025496729262e-06, 0.0, 0.0006015324077317446, 0.00030483273482931615, 7.66558148236624e-05, 0.0007618950214334908, -3.4315140727767546e-05, -0.0003873409424277983, -0.0002581674864028675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015604639030486773, 0.01311190291064501, -0.043707977926445755, -0.0032140939581541406, -0.026687532429398322, 0.01705516963922575, 0.054273993990267506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.918348766056197e-09, 2.650229335057428e-10, -0.000514652468576475]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922467343183218, 0.2359044269142091, 0.8415255254644389, 0.0, -0.12310170444313419, -0.24386377493927877, -2.608060686115852, -0.7116772284471309, -0.5581622103830651, -1.1994628701224501, -2.8771384401500866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4176731159377752, 0.9690816227511331, 0.7679242635833511, -1.2132780573832522, -2.299018936029712, -0.28620385908414797, 1.9057727319204802, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960763033183, -0.440340924572389, 0.023092083757146897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8854364718654023e-06, 0.0004717310419500043, 7.713646564592234e-06, 0.0, 0.0005988279314469956, 0.00030353563756180154, 7.643201002834777e-05, 0.0007585473270231177, -3.4326771416632615e-05, -0.00038555290209570716, -0.00025697678073433646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015627748625193033, 0.013062818518951868, -0.043675074387681916, -0.003209416043731131, -0.02690447982746789, 0.017013841224816428, 0.05442475602487812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.820471259658485e-09, 3.7228274721579084e-10, -0.0005123548788182946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922482072344842, 0.2359279089154134, 0.841525914222004, 0.0, -0.1230718930598605, -0.24384865728966337, -2.608056875514007, -0.7116394620836728, -0.55816392708018, -1.1994820616189485, -2.8771512318041363, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4168906142633456, 0.9697322875982185, 0.7657422392854535, -1.2134382896662679, -2.3003750177240807, -0.28535542471059344, 1.90850147292552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960759171188, -0.4403409245484401, 0.023066576541881698]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9458323249921477e-06, 0.00046964002408588835, 7.775151300331361e-06, 0.0, 0.000596227665474031, 0.00030235299230778275, 7.621203690126238e-05, 0.0007553272691621398, -3.433394229827986e-05, -0.0003838299299675208, -0.0002558330809954987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015650033488590995, 0.01301329694170914, -0.043640485957952946, -0.003204645660315158, -0.027121633887366898, 0.016968687471091107, 0.05457482010079753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.723991917998616e-09, 4.789779770359519e-10, -0.0005101443053039941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922487188422875, 0.2359512926173417, 0.8414798981621372, 0.0, -0.12304217007769358, -0.2438328025892432, -2.608053233455713, -0.7116018612972712, -0.5581654649798811, -1.1995011740929382, -2.87716403092832, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41622679897001835, 0.9702865401809379, 0.763883358433907, -1.2135778829397672, -2.3015461478541615, -0.284671909354924, 1.9108411860728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075585609, -0.44034092452713464, 0.023041174375794907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0232156067228836e-06, 0.0004676740385663791, -0.0009203211973347449, 0.0, 0.0005944596433383856, 0.0003170940084034714, 7.284116588084856e-05, 0.0007520157280314512, -3.0757994020575036e-05, -0.0003822494797954897, -0.000255982483672668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013276305866545001, 0.011085051654385976, -0.03717761703092988, -0.002791865469985349, -0.023422602601618707, 0.013670307113389343, 0.04679426294614361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.630193781554256e-09, 4.2610865232925507e-10, -0.0005080433217358516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2092248984882419, 0.235974268389336, 0.8414506529541362, 0.0, -0.1230129407403171, -0.24381756337189522, -2.6080496259565082, -0.7115648801886544, -0.5581669870332563, -1.199520018068767, -2.87717661581652, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4157054495725053, 0.970726134875539, 0.7624113404522476, -1.2136924119698704, -2.302488665425653, -0.28416729112142136, 1.9127088918606323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960753270093, -0.44034092451105267, 0.02301618802811448]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.320802629738785e-07, 0.00045951543988579204, -0.0005849041600194818, 0.0, 0.0005845867475296946, 0.00030478434695945265, 7.214998409164552e-05, 0.0007396221723374655, -3.044106750547131e-05, -0.00037687951657553657, -0.00025169776400109383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010426987950260405, 0.00879189389202301, -0.02944035963318739, -0.00229058060206577, -0.018850351429836387, 0.010092364670052284, 0.03735411575610158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.171997670780403e-09, 3.216397380081335e-10, -0.0004997269536085335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922491494170983, 0.23599624983988501, 0.8414483496448353, 0.0, -0.122984921306867, -0.24380364302824198, -2.608046030740962, -0.7115293881312232, -0.5581685710940243, -1.1995381647932162, -2.8771886485782794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4153133445449481, 0.9710617032434499, 0.7612911261863405, -1.2137835548633018, -2.303218483848184, -0.2838093796255577, 1.9141429507514227, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751444154, -0.4403409245013862, 0.022992208098654425]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2906935816892777e-07, 0.00043962901098051926, -4.606618601843708e-05, 0.0, 0.0005603886690020853, 0.0002784068730651544, 7.19043109229564e-05, 0.0007098411486224862, -3.1681215360431484e-05, -0.0003629344889806832, -0.00024065523518950488, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007842100551144033, 0.006711367358216193, -0.022404285318141592, -0.0018228578686265181, -0.014596368450615259, 0.007158229917273065, 0.02868117781580587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.651877703104973e-09, 1.933301689856042e-10, -0.00047959858920105706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492437373727, 0.23601658623147476, 0.8414590466242347, 0.0, -0.12295889779171289, -0.2437913255747105, -2.608042497371656, -0.7114963632547027, -0.5581702289630247, -1.1995551136100802, -2.8771997770817075, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41502627397516445, 0.9713122651738108, 0.760458530364623, -1.2138548491255416, -2.303770441791338, -0.2835593787138501, 1.9152187220931172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.28119607504069, -0.44034092450048995, 0.02296989711802654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.8864054873582224e-07, 0.000406727831794947, 0.0002139395879865806, 0.0, 0.0005204703030823638, 0.00024634907062953237, 7.066738611790935e-05, 0.0006604975304108868, -3.315738000833834e-05, -0.0003389763372812621, -0.0002225700685628714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005741411395673626, 0.005011238607218407, -0.016651916434352116, -0.0014258852447985985, -0.011039158863079185, 0.005000018234151651, 0.02151542683389112, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0745040033420788e-09, 1.7924738970382162e-11, -0.00044621961255772425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922492933419876, 0.23603475577432742, 0.8414750227616592, 0.0, -0.1229355231945582, -0.2437809814534243, -2.6080390312703785, -0.7114666078848317, -0.5581720073977583, -1.1995704589743537, -2.877209698784248, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4148198000911033, 0.9714968972861152, 0.7598487496944001, -1.2139100078181488, -2.304181407589278, -0.2833847366983969, 1.9160138213012863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960750336107, -0.4403409245145704, 0.02294979900678752]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.920922989975184e-08, 0.00036339085705321047, 0.00031952274849119864, 0.0, 0.00046749194309373803, 0.0002068824257242287, 6.932202555167622e-05, 0.000595107397419589, -3.5568694672535596e-05, -0.00030690728546846455, -0.00019843405081240186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004129477681223238, 0.0036926422460890037, -0.012195613404458027, -0.0011031738521428088, -0.008219315958802705, 0.003492840309064276, 0.015901984163380244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4158986410701592e-10, -2.8160915053321025e-10, -0.0004019622247804496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493099129635, 0.23605046525805473, 0.8414448279092318, 0.0, -0.12291510482198442, -0.2437709778967978, -2.608035990795053, -0.7114406115277784, -0.5581735692497372, -1.1995838798835885, -2.877218364229198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4146730376185007, 0.9716318981989475, 0.7594062208513683, -1.2139523496896159, -2.304484103164397, -0.28326203612539763, 1.916595816208237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2811960751141298, -0.44034092454431645, 0.022932238233061203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.314195200306826e-08, 0.00031418967454627315, -0.0006038970485487139, 0.0, 0.0004083674514753187, 0.0002000711325302667, 6.0809506508185485e-05, 0.0005199271410681618, -3.123703957631058e-05, -0.000268418184694739, -0.0001733088989992726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002935249452052032, 0.0027000182566449277, -0.008850576860634755, -0.0008468374293380021, -0.006053911502375485, 0.0024540114599855816, 0.011639898139017498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6103848084768415e-09, -5.949203318875397e-10, -0.0003512154745262834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20922493104040848, 0.23606365717311636, 0.8413724547795586, 0.0, -0.12289772275178933, -0.2437611459551833, -2.6080335107422443, -0.711418514534015, -0.5581747862028298, -1.199595274141099, -2.8772257708797935, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41456955499475034, 0.9717301605493174, 0.7590869279578832, -1.213984645147714, -2.3047052786869795, -0.2831748818362176, 1.9170190087748016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.281196075219521, -0.4403409245856499, 0.022917307953974907]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0" + "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935004775600904, 0.03579287115241836, -0.3486119528240798, 0.0, -1.0026363626456556, 0.487280835369237, -0.9525215184808308, -1.3886278121727262, -2.334886341128509, -0.4522777612376269, 0.11051798980154005, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424668997, 0.015377231220805351, 1.7420423753142413, -2.030174589286868, -1.4902477605001245, -0.10303703296564161, 0.21776153355159686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092742949935, -0.0006253904815580002, -0.0006249658519791201]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879819642, -0.12175818987754719, 0.2400789262452849, 0.0, 0.04188888115403446, -0.0017414101004064207, -0.07499999999999428, 0.07499999999999567, -0.07499999999998637, 0.051835065041060883, -0.07499999999999458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999445, 0.0749999999999933, 0.07499999999999102, 0.007475929198080923, -0.0749999999999336, -0.04364127965111987, -0.06817451567682108, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01249218548589987, -0.012507809631160003, -0.012499317039582403]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1987000955118654, 0.024080358963143086, -0.32789257823924267, 0.0, -1.0000374803489949, 0.4871546802127561, -0.9637715184807714, -1.377377812171733, -2.346136341128505, -0.4433442547461819, 0.09926798980154829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8650033424646424, 0.02662723122095179, 1.753292375314062, -2.027566476647114, -1.501497760500122, -0.11115116089492502, 0.21469408198177917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.002497264252385374, -0.002502732574253318, -0.0012498975577598962]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882872538, -0.23425024378550546, 0.4143874916967424, 0.0, 0.05197764593321432, -0.002523103129618494, -0.22499999999998566, 0.22499999999998815, -0.22499999999992076, 0.17867012982890113, -0.22499999999998604, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22499999999998438, 0.22499999999998208, 0.2249999999999753, 0.05216225279507682, -0.2249999999998406, -0.1622825585856681, -0.061349031396353684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0374530995618076, -0.03754684185390636, -0.012498634115615522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19805014326784395, 0.009163766288081052, -0.30283686996554215, 0.0, -0.9978836509932686, 0.4851544679925391, -0.9843965184807717, -1.3567528121717378, -2.361136341128498, -0.4246496660033108, 0.07864298980154821, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8453176331660688, 0.04725223122095102, 1.773899118231944, -2.0212985733357707, -1.5191122127905634, -0.12891035713212942, 0.21571790462598486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.00593046539789056, -0.005944526059152402, -0.001249795117342325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880429049, -0.2983318535012406, 0.50111416547401, 0.0, 0.04307658711452586, -0.04000424440434057, -0.4125000000000071, 0.41249999999990455, -0.2999999999998565, 0.37389177485742187, -0.41250000000000153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.393714185971473, 0.41249999999998466, 0.41213485835763863, 0.12535806622686507, -0.3522890458088269, -0.3551839247440879, 0.02047645288411372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06866402291010373, -0.06883586969798167, 2.048808351421544e-06]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019102358305, -0.00709741536618394, -0.27618797068082396, 0.0, -0.9968266099456617, 0.4807097474673838, -1.012834018480867, -1.329453416384282, -2.3761363412057532, -0.39782084205093726, 0.05020548980146977, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8208447598151705, 0.07568973122064448, 1.800112604085682, -2.011791355899208, -1.539341117554956, -0.15256462167730755, 0.22458300148417265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010670050348371164, -0.010684107773593876, 3.414691331167421e-07]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044885217824, -0.3252236330852998, 0.5329779856943639, 0.0, 0.021140820952136388, -0.08889441050310486, -0.5687500000019068, 0.5459879157491171, -0.3000000015451077, 0.5365764790474705, -0.5687500000015688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.48945746701796455, 0.5687499999938693, 0.524269717074763, 0.1901443487312527, -0.4045780952878528, -0.4730852909035629, 0.17730193716375559, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09479169900961207, -0.09479163428882947, 0.025002731729508836]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023877955897, -0.023275380310688133, -0.24927729873138352, 0.0, -0.9969321633200399, 0.47492671830707056, -1.0475840184809435, -1.2992296247946589, -2.387386341360299, -0.3643577828890391, 0.015455489801406985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7949376047310681, 0.11043973122040035, 1.8281828328752878, -1.999624880566592, -1.5584344747933812, -0.17836395453046028, 0.24322058219932916, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016476978965513554, -0.016460472163217305, 0.0026386413666429596]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880482017, -0.32355929889008384, 0.5382134389888087, 0.0, -0.002111067487563234, -0.11566058320626539, -0.6950000000015298, 0.604475831792462, -0.22500000309091267, 0.6692611832379638, -0.6950000000012557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5181431016820468, 0.6949999999951174, 0.561404575792115, 0.24332950665232017, -0.38186714476850203, -0.5159866570630381, 0.3727516143031302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11613857234284779, -0.11552728779246856, 0.052765997950196854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028653528302, -0.038387512901389045, -0.22263388530520128, 0.0, -0.9975569893600359, 0.46866534813531446, -1.08738401848104, -1.2693116176575314, -2.392228118071455, -0.3255873386435427, -0.024344510198662142, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.769731099419793, 0.15023973122006226, 1.8543598053360464, -1.9851864466453972, -1.5730208830209418, -0.20255835612588932, 0.2700018994619217, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023150257086495492, -0.023053618704875423, 0.0060401055027243565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044885518812, -0.30224265181401816, 0.5328682685236444, 0.0, -0.012496520799919598, -0.12522740343512184, -0.7960000000019307, 0.5983601427425489, -0.09683553422311905, 0.775408884909927, -0.7960000000013824, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5041301062255001, 0.795999999993238, 0.5235394492151696, 0.2887686784238945, -0.29172816455121264, -0.48388803190858065, 0.535626345251851, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13346556241963872, -0.1318629308331624, 0.06802928272162793]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1954503342912846, -0.05189640655835118, -0.19640894217534255, 0.0, -0.997957994660567, 0.46229408036443376, -1.1312240184811078, -1.2410058591494508, -2.392044389348854, -0.28257098633122174, -0.06818451019868726, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7450870087007764, 0.1913397312202789, 1.8808590598573596, -1.9689808643747688, -1.5858220897600042, -0.22779991562278304, 0.30342695327188174, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030526583689117773, -0.030289954890102812, 0.009579782743985136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879968351, -0.2701778731392426, 0.5244988625971749, 0.0, -0.008020106010623185, -0.127425355417614, -0.8768000000013583, 0.5661151701616131, 0.0036745744520212675, 0.8603270462464196, -0.8768000000005023, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4928818143803325, 0.8220000000043325, 0.5299850904262638, 0.32411164541257026, -0.25602413478124675, -0.5048311899378742, 0.6685010761992001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14752653205244562, -0.14472672370454778, 0.0707935448252156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19480038204750924, -0.06378126722720769, -0.17059839925484244, 0.0, -0.9981487691106901, 0.4543105869613007, -1.1782960184812163, -1.2161436618652872, -2.3871803808699363, -0.23905872577160636, -0.11525651019870915, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.71995605760354, 0.22998973123564354, 1.9113745871558452, -1.9514277816677486, -1.6001507887703625, -0.2578386330210367, 0.3421669963198305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0384733004933539, -0.038032577329402864, 0.013007740500501954]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875507352, -0.2376972133771302, 0.5162108584100022, 0.0, -0.0038154890024610175, -0.15966986806266026, -0.9414400000021712, 0.49724394568327146, 0.09728016957835495, 0.8702452075829168, -0.9414400000004377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5026190219447283, 0.7730000003072925, 0.6103105459697143, 0.3510616541404071, -0.2865739802071669, -0.6007743479650738, 0.7748008609589757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15893433608472254, -0.1548524487860011, 0.06855915513033636]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1941504298034978, -0.07407266533993596, -0.14514291568062926, 0.0, -0.9982222795025852, 0.44212143758627886, -1.2279536184812154, -1.1961315056313289, -2.3766181156129362, -0.19880055732544735, -0.16491411019870095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.694184024184408, 0.2624397346733757, 1.945090331198005, -1.932668688128486, -1.6166888973316518, -0.2938696069391025, 0.38515903075810215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0468828938222008, -0.04617333404578674, 0.016242132029195996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488022866, -0.20582796225456554, 0.5091096714842638, 0.0, -0.0014702078379038221, -0.2437829875004373, -0.9931519999999829, 0.400243124679165, 0.21124530514000023, 0.805163368919551, -0.9931519999998355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5154406683826414, 0.6490000687546438, 0.674314880843196, 0.37518187078525195, -0.3307621712257831, -0.7206194783613166, 0.8598406887654334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.168191866576938, -0.1628151343276775, 0.06468783057388082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19350047756019342, -0.08283073801450576, -0.11996749640256044, 0.0, -0.9981119532275723, 0.4248057884027918, -1.2779536435317629, -1.181742331772493, -2.3609615205313768, -0.16554648081212237, -0.2149141101968043, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6676919455340091, 0.28916553827362484, 1.9806422573554816, -1.9128932292758807, -1.635924752856884, -0.3346943860390268, 0.43155265830326833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05566840869963582, -0.05462664523497049, 0.019268282626884434]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904486608754, -0.17516145349139595, 0.5035083855613763, 0.0, 0.002206525500258042, -0.3463129836697408, -1.00000050101095, 0.287783477176716, 0.3131319016311939, 0.6650815302664999, -0.9999999999620668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5298415730079769, 0.5345160720049826, 0.7110385231495326, 0.39550917705210575, -0.3847171105046487, -0.8164955819984858, 0.9278725509033235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17571029754870024, -0.16906622378367492, 0.06052301195376879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052531632355, -0.09012282790928375, -0.0949945158128233, 0.0, -0.9976918005572822, 0.4026379572150482, -1.3279536685823663, -1.1730634727276574, -2.34133298490516, -0.14304649451542698, -0.2649141101962771, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6403587455404234, 0.3122121626510556, 2.016897499986658, -1.8923979070698704, -1.658532571824784, -0.37935420931224917, 0.4806675603382588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06475954680006092, -0.06332478802745585, 0.02208809866024527]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877397654, -0.14584179789555962, 0.49945961179474274, 0.0, 0.008403053405801395, -0.4433566237548721, -1.000000501012068, 0.17357718089671292, 0.39257071252433307, 0.4499996916138813, -0.9999999999894564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.546663999871713, 0.46093248754861493, 0.7251048526235306, 0.40990644412020644, -0.4521563793579988, -0.8931964654644475, 0.982298040699809, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18182276200850217, -0.1739628558497072, 0.05639632066721667]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057307258226, -0.09594093552277741, -0.07014707637061485, 0.0, -0.9965656124294026, 0.3766803497512302, -1.3779536936204972, -1.169030167948862, -2.3188933312720117, -0.12755060186777403, -0.3149141101951814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6121516039012516, 0.33322900331581234, 2.053048335335069, -1.8715176368705742, -1.6848067143323457, -0.42708206792039877, 0.530667560337271, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07409876019703565, -0.07221494148670667, 0.02462889338418732]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044874825585, -0.11636215226987334, 0.4969487888441691, 0.0, 0.0225237625575933, -0.5191521492763591, -1.0000005007626211, 0.08066609557590844, 0.448793072662968, 0.3099178529530587, -0.999999999978086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5641428327834341, 0.4203368132951341, 0.7230167069682218, 0.41760540398592727, -0.5254828501512318, -0.9545571721629916, 0.9999999999802442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1867842679394946, -0.17780306918501634, 0.05081589447884099]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1915506208284794, -0.10036310844292455, -0.045350139427469405, 0.0, -0.994422224041471, 0.34834388416853784, -1.4279537185076305, -1.1689940768341889, -2.2951883693504262, -0.11630060943476574, -0.3649141101951757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5826959934577998, 0.3496611586433309, 2.087412527711624, -1.8528999680816072, -1.717800433522904, -0.4770820929756406, 0.5806675603372661, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08363935941947381, -0.08125553370904845, 0.026902815369241072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882057293, -0.08844345840294277, 0.49593873886290873, 0.0, 0.042867767758631964, -0.5667293116538475, -1.0000004977426664, 0.00072182229346264, 0.47409923843170926, 0.22499984866016598, -0.9999999999998861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5891122088690359, 0.328643106550371, 0.6872838475311028, 0.37235337577933897, -0.6598743838111675, -1.0000005011048363, 0.9999999999999002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19081198444876327, -0.1808118444468358, 0.04547843970107507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19090066858407462, -0.10323491255116392, -0.020530267648986685, 0.0, -0.9906616460684254, 0.31732411906218994, -1.4779537435627763, -1.1711932832728438, -2.269339733306679, -0.10692561567629634, -0.41491411019515523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.55273032354188, 0.3613532970549822, 2.11811519605928, -1.838500055732416, -1.7561954088753378, -0.5270821180306766, 0.6306675603372348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09334129327795843, -0.09041616874373477, 0.02868910949959598]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044888095715, -0.05743608216478737, 0.4963974355696544, 0.0, 0.07521155946091031, -0.6203953021269575, -1.0000005011029138, -0.04398412877309881, 0.5169727208749474, 0.18749987516938793, -0.9999999999995902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5993133983183974, 0.2338427682330254, 0.6140533669531139, 0.28799824698382426, -0.7678995070486744, -1.0000005011007207, 0.9999999999993754, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19403867716969223, -0.18321270069372653, 0.03572588260709818]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071634004234, -0.10457855053763135, 0.004385786626315297, 0.0, -0.9849369381476, 0.2839002360148954, -1.5279537686180218, -1.17466610110415, -2.2414735593357737, -0.10317562021799674, -0.4649141101951504, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5233229725962216, 0.36969446740304934, 2.143038650411786, -1.8291699046431946, -1.798911389157298, -0.5756053876972766, 0.6806675603372229, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10317100955539824, -0.09967415935561454, 0.029943606245836273]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880645341, -0.026872759729348675, 0.49832108550603965, 0.0, 0.11449415841650931, -0.6684776609458908, -1.0000005011049091, -0.06945635662612402, 0.5573234794180997, 0.07499990167861059, -0.9999999999999034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5881470189131661, 0.16682340696134274, 0.49846908705011983, 0.1866030217844274, -0.8543196056392057, -0.9704653933320009, 0.999999999999761, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1965943255487961, -0.18515981223759514, 0.025089934924805872]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076409519933, -0.10453057389574948, 0.029471171578727164, 0.0, -0.9771085917043104, 0.2485330794209001, -1.5779537936732664, -1.1788548881732956, -2.2118268152936804, -0.10317562216549314, -0.5149141101951414, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.495306006269499, 0.3761419989059404, 2.160891662915417, -1.824899582317421, -1.8450841733827208, -0.619577208476581, 0.7306675603371922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11310118230716668, -0.10901189464256239, 0.030737684190383353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044896860483, 0.0009595328376374654, 0.5017076990482373, 0.0, 0.1565669288657919, -0.7073431318799055, -1.0000005011048938, -0.08377574138291399, 0.5929348808418623, -3.8949927727571776e-08, -0.9999999999998208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5603393265344536, 0.1289506300578212, 0.3570602500726246, 0.08540644651547091, -0.9234556845084538, -0.8794364155860872, 0.9999999999993857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19860345503536875, -0.18675470573895703, 0.015881558890941574]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081185053514, -0.10325887035266997, 0.054799724407209094, 0.0, -0.9671468194654598, 0.21170593900339751, -1.6279538187285196, -1.1834283585822387, -2.180593818016655, -0.10317562119898441, -0.5649141101951358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4688487342508203, 0.3814027872192266, 2.1719326853827745, -1.825171873241273, -1.8940224007630342, -0.6580094539680865, 0.78066756033716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12310997120708991, -0.11841527876514904, 0.03117675768890945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044893283523, 0.025434070861590136, 0.5065710565696384, 0.0, 0.19923544477701283, -0.7365428083500519, -1.0000005011050657, -0.0914694081788625, 0.6246599455405074, 1.9330174691911513e-08, -0.9999999999998875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5291454403735715, 0.10521576626572367, 0.22082044934715017, -0.005445818477038247, -0.9787645476062656, -0.7686449098301102, 0.999999999999356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017577799846473, -0.18806768245173283, 0.008781469970521932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18830085960652074, -0.10094106828000085, 0.08044648176792582, 0.0, -0.9551158192300108, 0.17385418948230297, -1.6779538437837669, -1.1882353885402366, -2.148025953887049, -0.10317562119899297, -0.6149141101951241, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4438513795930497, 0.38604038290500425, 2.1769110942114307, -1.8290985891323805, -1.9440224007630011, -0.690938830721111, 0.8306675603370197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13318029585907415, -0.12787262454713696, 0.03137996710546729]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488028826, 0.04635604145338236, 0.5129351472143346, 0.0, 0.24062000470898037, -0.7570349904218909, -1.0000005011049475, -0.09614059915995513, 0.6513572825921219, -1.7120950368152377e-13, -0.9999999999997655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.49994709315541364, 0.09275191371555261, 0.09956817657312017, -0.07853431782215309, -0.9999999999993392, -0.6585875350604878, 0.999999999997195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20140649303968486, -0.1891469156397585, 0.004064188331156809]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090736249754, -0.09774250691140846, 0.10648834968152779, 0.0, -0.9411240359592388, 0.13536514841905334, -1.727953868839028, -1.1932265820845844, -2.114403332476961, -0.10317562119899225, -0.6649141101951245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4201341163778836, 0.39063143714604665, 2.1765951804883517, -1.835633730864658, -1.9940224007630023, -0.7187861159392873, 0.8806675603370199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14329907333356773, -0.1373739653243564, 0.03145918833284471]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880463854, 0.0639712273718478, 0.5208373582720394, 0.0, 0.2798356654154395, -0.7697808212649924, -1.0000005011052202, -0.09982387088695573, 0.6724524282017643, 1.4414515984740634e-14, -1.0000000000000073, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4743452643033202, 0.09182108482084815, -0.006318274461583409, -0.13070283464554755, -1.000000000000025, -0.5569457043635264, 1.0000000000000029, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20237554948987138, -0.1900268155443884, 0.0015844245475484528]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1870009551184788, -0.09380434713976812, 0.13300294106775307, 0.0, -0.9252870640524239, 0.09656003030771734, -1.7779538938942843, -1.198397942504916, -2.0800026432934255, -0.1031756211989961, -0.7149141101951192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3966575446828693, 0.3942814735180769, 2.173228309942234, -1.8437768276556492, -2.044022400288047, -0.7440906075280878, 0.9298125954400028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15345645516096196, -0.1469106701899372, 0.03150547657498004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880374714, 0.0787631954328065, 0.5302918277245053, 0.0, 0.31673943813629674, -0.7761023622267198, -1.0000005011051265, -0.10342720840663337, 0.6880137836707058, -7.729788349580957e-14, -0.9999999999998935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4695314339002854, 0.0730007274406058, -0.06733741092235547, -0.1628619358198225, -0.9999999905008928, -0.5060898317760081, 0.9829007020596591, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20314763654788484, -0.19073409731161634, 0.0009257648427065969]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1863510028746126, -0.08940657691239148, 0.15993646549514093, 0.0, -0.9077002177846101, 0.0577144982202569, -1.8279539189495444, -1.2037550845996223, -2.045082455288725, -0.10317562119899588, -0.7649141101951193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.373403233514618, 0.39761818177927666, 2.1677150721919367, -1.8517095702924167, -2.090272400267555, -0.7671217427461602, 0.9743554279517473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16364505891301762, -0.15647530578669536, 0.03157764315624053]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877324032, 0.08795540454753278, 0.5386704885477571, 0.0, 0.35173692535627676, -0.7769106417492088, -1.0000005011052027, -0.10714284189412701, 0.6984037600940188, 4.450678825453664e-15, -1.000000000000003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.46508622336502503, 0.066734165223995, -0.11026475500594807, -0.1586548527353489, -0.9249999995901508, -0.46062270436144914, 0.8908566502348907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2037720750411131, -0.19129271193516295, 0.0014433316252097353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1857010506306874, -0.08477395707851161, 0.18720497820862866, 0.0, -0.8884352929982886, 0.01907208418723394, -1.8779539440051352, -1.2092989879574256, -2.0098810870774675, -0.10317562119899996, -0.814914110195116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3504207039881608, 0.4011800323063187, 2.160664577479721, -1.8582488832910644, -2.130318218837731, -0.7879559727175606, 1.0125331389814698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17385931028884796, -0.16606157196264626, 0.03170496753381734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878503634, 0.09265239667759756, 0.5453702542697546, 0.0, 0.3852984957264305, -0.7728482806604591, -1.0000005011118134, -0.11087806715606638, 0.7040273642251468, -8.146622980198351e-14, -0.999999999999932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45965059052914475, 0.07123701054084097, -0.14100989424431654, -0.13078625997295515, -0.8009163714035266, -0.41668459942800695, 0.7635542205944467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2042850275166068, -0.19172532351901794, 0.0025464875515362044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100287469678, -0.08004658303450171, 0.2147149727192593, 0.0, -0.8673544013805521, -0.017515331797160368, -1.927953969060416, -1.2143074411173982, -1.9760158105709866, -0.10317562119900985, -0.8649141101951096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3277781927368582, 0.4069905617644826, 2.1533057822128603, -1.8608207883874708, -2.160952331603752, -0.8063723870543738, 1.042771122912438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18409494956248756, -0.1756642153116939, 0.03189697652684323]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880187457, 0.09454748088019785, 0.5501998902126127, 0.0, 0.42161783235473066, -0.7317483196878861, -1.0000005011056152, -0.10016906319945132, 0.6773055301296188, -1.97726774355756e-13, -0.9999999999998725, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45285022502605515, 0.11621058916327776, -0.14717590533721614, -0.051438101928126534, -0.6126822553204215, -0.36832828673626294, 0.6047596786193603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20471278547279198, -0.1920528669809529, 0.003840179860517767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095511869036, -0.07528632615850864, 0.24236838577647574, 0.0, -0.8445410002726693, -0.052170687543544945, -1.977953994115659, -1.218888525397854, -1.9433658307873134, -0.10317562119908598, -0.9149141101950806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3053702514150862, 0.41459337746870106, 2.145905680764107, -1.859865008164406, -2.1836136967779933, -0.8227303364548901, 1.0663238948101657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19434857549061726, -0.1852790253493729, 0.03214122600879182]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879871701, 0.09520513751986139, 0.5530682611443287, 0.0, 0.4562680221576549, -0.6931071149276915, -1.0000005011048618, -0.09162168560911774, 0.6529995956734658, -1.5226675328354768e-12, -0.9999999999994209, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4481588264354371, 0.1520563140843691, -0.1480020289750656, 0.01911560446129544, -0.4532273034848304, -0.32715898801032733, 0.4710554379545536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20507251856259387, -0.19229620075358023, 0.004884989638971829]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090736269682, -0.07051097554535792, 0.27005489054469406, 0.0, -0.820117098008896, -0.08532825542939047, -2.027954019170819, -1.2232720269389479, -1.911539421911304, -0.10317562119960076, -0.9649141101950837, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.283051502232509, 0.4230911108903051, 2.1384846086640117, -1.856402509099699, -2.200673827285524, -0.8375000830245992, 1.084970164605868, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20461740258981545, -0.19490270153196496, 0.03242049742283092]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904488012937, 0.09550701226301443, 0.5537300953643661, 0.0, 0.4884780452754674, -0.6631513577169105, -1.0000005011032, -0.08767003082187402, 0.6365281775201885, -1.0295615631910274e-11, -1.0000000000000606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4463749836515448, 0.16995466843208046, -0.1484214420019017, 0.06924998129414076, -0.34120261015062003, -0.29539493139418266, 0.3729253959140467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2053765419839639, -0.19247352365184098, 0.0055854282807819644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18830085960663476, -0.06573065593356968, 0.2976490144776919, 0.0, -0.7940209891948569, -0.11768237806996801, -2.0779540442260287, -1.2278303686797252, -1.8798731125643917, -0.10456172044276532, -1.014914110194661, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2606814857024655, 0.431755769507175, 2.1310046803613925, -1.851301878665199, -2.214207864379562, -0.8510876125202473, 1.1002458589104858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2148992583261869, -0.2045325429886216, 0.03273359178370046]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487875863, 0.09560639223576467, 0.5518824786599563, 0.0, 0.5219221762807835, -0.6470824528115505, -1.000000501104192, -0.09116683481554808, 0.6333261869382456, -0.027721984863291253, -0.9999999999915493, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.44740033060087214, 0.1732931723373979, -0.14959856605238572, 0.10201260869000148, -0.27068074188076024, -0.27175058991296264, 0.30551388609235586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056371147274286, -0.19259682913313322, 0.0062618872173907094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1889508118503472, -0.06094514455415829, 0.3250118638883023, 0.0, -0.7660168281955159, -0.1498820473410018, -2.127954069281119, -1.2328746095083405, -1.8476590040733998, -0.10938369658481906, -1.064914110194654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2381640305215638, 0.44013717084252785, 2.1234227978349507, -1.8451475887645252, -2.225705791667517, -0.86379626868411, 1.1132725972557043, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22519247883156732, -0.21416630923912433, 0.033081452035587405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874249214, 0.0957102275882278, 0.5472569882122083, 0.0, 0.5600832199868193, -0.6439933854206761, -1.0000005011018094, -0.10088481657230536, 0.6442821698198388, -0.09643952284107475, -0.9999999999998602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45034910361803604, 0.16762802670705734, -0.15163765052883937, 0.12308579801347541, -0.22995854575909658, -0.2541731232772522, 0.2605347669043711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20586441010760834, -0.19267532501005452, 0.006957205037738919]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1896007640943593, -0.056136295744171866, 0.3502790770731317, 0.0, -0.7358821923991324, -0.1849208229691795, -2.1779540943363824, -1.2384363426293217, -1.8144877802196402, -0.1188691806799059, -1.1149141101946507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.215463430339153, 0.44801518927411993, 2.1157062026622317, -1.838286239897125, -2.2361153657650807, -0.875836486222236, 1.124794054681236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23549568758795433, -0.22380225512893975, 0.03345246792854085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880242122, 0.09617697619972848, 0.5053442636965884, 0.0, 0.6026927159276687, -0.700775512563554, -1.0000005011052675, -0.11123466241962579, 0.6634244770751929, -0.1897096819017367, -0.9999999999999337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45401200364821753, 0.15756036863184142, -0.1543319034543817, 0.1372269773480076, -0.20819148195127996, -0.2408043507625211, 0.23042914851063429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20606417512774042, -0.19271891779630862, 0.007420317859068804]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071633837923, -0.05126875511728496, 0.37168476444784687, 0.0, -0.7033745635644513, -0.22086031987406063, -2.22795411939164, -1.2441730694071969, -1.780436008865792, -0.13350254909532316, -1.1649141101946494, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1925993695354173, 0.45532158092343755, 2.1078359396501023, -1.830903332945316, -2.2459767976272564, -0.8873471725143723, 1.1352674019011204, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24580754562115176, -0.23343923792898846, 0.033817400381839495]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880398485, 0.09735081253773807, 0.42811374749430303, 0.0, 0.6501525766936237, -0.7187899380976224, -1.000000501105156, -0.11473453555750569, 0.6810354270769632, -0.2926673683083453, -0.9999999999999719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.457281216074713, 0.14612783298635243, -0.15740526024259138, 0.1476581390361814, -0.19722863724351458, -0.2302137258427263, 0.20946694439768762, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20623716066394854, -0.1927396560009739, 0.00729864906597294]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19090066859357227, -0.04598248330987681, 0.3886109037577365, 0.0, -0.6676027099643385, -0.2560699793372169, -2.2779541444467584, -1.2479054559897538, -1.7469772680484013, -0.15154625311070333, -1.214914110194611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1700112437989867, 0.46207634811224185, 2.099915046359739, -1.8232418122144567, -2.255537595132261, -0.8985359801059064, 1.1450041779607505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25612352010166706, -0.2430800482900869, 0.033818410484089206]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904510386092, 0.10572543614816296, 0.338522786197792, 0.0, 0.7154370720022551, -0.7041931892631261, -1.000000501102369, -0.07464773165113807, 0.6691748163478137, -0.3608740803076032, -0.9999999999992314, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45176251472861234, 0.1350953437760863, -0.15841786580726494, 0.1532304146171864, -0.19121595010009734, -0.2237761518306816, 0.19473552119260332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20631948961030647, -0.1928162072219686, 2.0202044994209294e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062083595045, -0.040317521235115276, 0.40133864935816627, 0.0, -0.6302328383958651, -0.2867998021054996, -2.324204173917024, -1.249233972993645, -1.7178482851513637, -0.1767502859932872, -1.2649141101936572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1476690025447447, 0.4683333008680236, 2.09191291107895, -1.8152899458118121, -2.2649088062839944, -0.9094202366145975, 1.154124183192693, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2664396304336438, -0.2527272981107301, 0.033491878793655123]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044847563757, 0.1132992414952307, 0.2545549120085955, 0.0, 0.7473974313694678, -0.6145964404286427, -0.9250005894053064, -0.0265703400778258, 0.5825796579407504, -0.5040806576516775, -0.9999999999809237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4468448250848407, 0.12513905511563492, -0.160042705615783, 0.15903732805288917, -0.18742422303466139, -0.21768513017382185, 0.1824001046388473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20632220663953524, -0.19294499641286425, -0.006530633808681684]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057308329783, -0.03435811871924357, 0.4106071128396652, 0.0, -0.5924384257520655, -0.3092997887046269, -2.3641190113732753, -1.2479121376185047, -1.6944830038835206, -0.20891351230026609, -1.3149141101936337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1254971862108376, 0.47415393170495546, 2.083789800678732, -1.8069865192847097, -2.274116289795303, -0.9199753081595786, 1.1626655265439794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2767528016450851, -0.2623829541739807, 0.032915192927361656]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044946947718, 0.11918805031743422, 0.1853692696299788, 0.0, 0.7558882528759906, -0.44999969159426667, -0.7982967491250276, 0.02643670750280394, 0.46730562535686115, -0.6432645261395776, -0.999999999999531, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4434363266781419, 0.11641261673863741, -0.1624622080043586, 0.16606853054205084, -0.184149670226171, -0.2111014308996233, 0.17082686702572897, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626342422882576, -0.19311312126501273, -0.011533717325869332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052532763977, -0.028246681651432553, 0.417278269546565, 0.0, -0.5533046909445254, -0.3273199358428501, -2.400841854050614, -1.2441771801193224, -1.6731391108808145, -0.24664409334589987, -1.364914110193866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1033514722958775, 0.4795913155188154, 2.0754923512785957, -1.7982316041646491, -2.2831497971975154, -0.9301385149898467, 1.1706182117756505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2870613964926463, -0.27204770428101827, 0.03222404529439046]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044886838658, 0.12222874135622029, 0.13342313413799528, 0.0, 0.7826746961508023, -0.36040294275985324, -0.734456853546777, 0.07469914998364757, 0.42687786005412354, -0.7546116209126756, -1.0000000000046478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4429142782992028, 0.10874767627719871, -0.1659489880027314, 0.17509830240121216, -0.18067014804424714, -0.2032641366053611, 0.15905370463342458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617189695122384, -0.1932950021407505, -0.013822952659423841]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19350047757947533, -0.021986933544807425, 0.4221434061622202, 0.0, -0.5130500192277759, -0.3385699282758616, -2.435183288353933, -1.2376153997438408, -1.6527359320507653, -0.28882855819044684, -1.4149141101924279, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.081250423963103, 0.4846894888950291, 2.067020158165791, -1.7889953202043773, -2.2919788654504165, -0.9398948761634546, 1.1779804718250553, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2973638782122777, -0.28172233421270915, 0.03141822304156141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904503671109, 0.12519496213250256, 0.09730273231310324, 0.0, 0.80509343433499, -0.22499984866023012, -0.6868286860663773, 0.13123560750963204, 0.40806357660098147, -0.8436892968909393, -0.9999999999712385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.442020966655492, 0.10196346752427456, -0.16944386225609773, 0.1847256792054373, -0.17658136505801988, -0.195127223472158, 0.1472452009880953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20604963439262888, -0.1934925986338176, -0.016116445056581115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415042983015146, -0.015940318210569057, 0.42584211058524724, 0.0, -0.4735784370132148, -0.34679976600678003, -2.4659684518139637, -1.229742253064001, -1.6331973476449209, -0.33457613007048115, -1.4649141101914138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0587794267988824, 0.48946642596631346, 2.0582582915254526, -1.7790703593797987, -2.300597054380919, -0.9490808104615622, 1.184684280414949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30766228438160115, -0.29140399152743357, 0.030858428686362897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999045013522767, 0.12093230668476738, 0.07397408846054156, 0.0, 0.7894316442912224, -0.16459675456060263, -0.6157032692006137, 0.15746293359679744, 0.39077168811689056, -0.9149514376006856, -0.9999999999797207, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4494199432844081, 0.09553874142568745, -0.1752373328067675, 0.19849921649157368, -0.17236377861005436, -0.18371868596215365, 0.13407617179787834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596812338646886, -0.19363314629448874, -0.011195887103970254]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1948003817785157, -0.010211961403289976, 0.4288198723493238, 0.0, -0.436740694585272, -0.3505497610886175, -2.4926809098603018, -1.221532104533864, -1.6152614476139333, -0.38013680985480225, -1.5149141100153303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.035825385381281, 0.4939367019768837, 2.0491840336525255, -1.7683863190096152, -2.30899050710184, -0.9576372854441152, 1.1907105397573798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3179597789418257, -0.3010887701017077, 0.030653317206623815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999038967284646, 0.11456713614558164, 0.059555235281530755, 0.0, 0.7367548485588561, -0.07499990163674985, -0.5342491609267589, 0.16420297060273872, 0.3587180006197488, -0.9112135956864214, -0.999999996478329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45908082835202635, 0.08940552021140502, -0.18148515745853835, 0.21368080740367146, -0.16786905441842137, -0.17112949965105848, 0.12052518684861432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20594989120449095, -0.19369557148548283, -0.004102229594781623]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033402254522, -0.0047232234992234, 0.4314326130405708, 0.0, -0.40350562387742783, -0.350549759449232, -2.5159835345977135, -1.213658820867027, -1.5989292596586129, -0.4217605975434101, -1.5649141100153348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0124891843538457, 0.4981138770935389, 2.0398401390253653, -1.7569738888744086, -2.317143791957696, -0.9655843025413007, 1.1960794427474029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3282588830342648, -0.31077355784008315, 0.03073085442638707]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880590695, 0.10977475808133152, 0.0522548138249406, 0.0, 0.6647014141568836, 3.278770992209967e-08, -0.4660524947482356, 0.157465673336742, 0.3266437591064106, -0.832475753772157, -1.0000000000000906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.466724020548707, 0.08354350233310322, -0.18687789254320628, 0.2282486027041316, -0.1630656971171136, -0.15894034194370965, 0.10737805980046133, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20598208184878208, -0.19369575476750928, 0.0015507443952651216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028626450218, 0.0005977739911573578, 0.43388750662554476, 0.0, -0.3744777343318386, -0.35054975944922634, -2.5357410254809083, -1.206897316826226, -1.5842685730535615, -0.4556974931450726, -1.6149141100136624, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9888600690673232, 0.5020058769292861, 2.0302696198490073, -1.7448654934375056, -2.3250498037173886, -0.9729427837511755, 1.2008148431743053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33856153777606945, -0.3204559452647128, 0.03102658809182508]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044839139417, 0.10641994980761516, 0.04909787169947905, 0.0, 0.5805577909117838, 1.1328336769881886e-13, -0.3951498176638948, 0.13523008081601928, 0.2932137321010285, -0.6787379120332497, -0.9999999999665521, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.47258230573045196, 0.07783999671494374, -0.19141038352715636, 0.2421679087380596, -0.15812023519385113, -0.14716962419749657, 0.0947080085380473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20605309483609288, -0.19364774849259359, 0.005914673308760186]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023851750204, 0.0058067827884346526, 0.43629963435424546, 0.0, -0.34977328671760405, -0.3505497594490434, -2.5515534861851052, -1.2017523323379853, -1.5714335711273217, -0.47882349802376295, -1.6649141100218512, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9650064217284198, 0.5056166847091188, 2.020511062691655, -1.7320884987762222, -2.3327083427939947, -0.9797300216896181, 1.2049403664546836, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34886924415138293, -0.33013405924060685, 0.031491401395039406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999045059997324, 0.10418017594554589, 0.048242554574013434, 0.0, 0.4940889522846916, 3.659774971476059e-12, -0.31624921408393897, 0.10289968976481464, 0.25670003852479484, -0.46252009757380774, -1.0000000001637788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.47707294677806744, 0.07221615559665442, -0.1951711431470496, 0.2555398932256706, -0.153170781532121, -0.13574475876885275, 0.08251046560756373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2061541275062699, -0.19356227951788008, 0.009296266064286476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019076205678, 0.01094710659779356, 0.43889654427940505, 0.0, -0.32902778679993383, -0.350549759373933, -2.5632872879338184, -1.198315358941139, -1.5604962061654737, -0.4934354490988726, -1.714914110022389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9409809099977413, 0.5089478611007892, 2.010598536565035, -1.7186648939314983, -2.340124142176677, -0.9859601185588565, 1.2084781184221773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3591827297248039, -0.3398064579031829, 0.032087084044182854]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044891095112, 0.1028064761871781, 0.05193819850319245, 0.0, 0.4149099983534049, 1.5022074274711807e-09, -0.23467603497425943, 0.06873946793692268, 0.21874729923696185, -0.2922390215021926, -1.0000000000107563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4805102346135684, 0.06662352783340725, -0.19825052253240177, 0.2684720968944773, -0.14831598765364637, -0.12460193738476788, 0.0707550393498762, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626971146842019, -0.1934479732515218, 0.011913652982868894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19805014300595303, 0.01616763718753221, 0.4416266043295242, 0.0, -0.31434046046960834, -0.3479964396838741, -2.5671924307342984, -1.1950174970328917, -1.554812365961576, -0.5032833461061631, -1.7649141100222665, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9169604577879927, 0.5120072136652394, 2.00059743522944, -1.704673767036179, -2.3472996936890005, -0.9916948375641602, 1.211471161209099, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3695018483503711, -0.3494732006465865, 0.03266842201820772]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487792508, 0.10441061179477303, 0.05460120100238339, 0.0, 0.2937465266065099, 0.05106639380117792, -0.07810285600959682, 0.06595723816494561, 0.11367680407795161, -0.19695794014580975, -0.999999999997548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4804090441949723, 0.06118705128900468, -0.2000220267118964, 0.27982253790639017, -0.1435110302464684, -0.11469438010607613, 0.05986085573843309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20638237251134314, -0.19333485486807092, 0.01162675948049735]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009524997645, 0.021640331934095997, 0.4444094503665469, 0.0, -0.304737426692917, -0.3427112339558802, -2.5595189145865422, -1.1902472533215211, -1.550632050515629, -0.5121171890456344, -1.8149141100222674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8931497268190505, 0.5148052017724185, 1.9905777506774254, -1.6902082840764425, -2.3542384659824007, -0.9970080801219692, 1.2139672984600969, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37982523717026523, -0.35913610610156427, 0.033065302053414555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880468606, 0.10945389493127572, 0.055656920740453225, 0.0, 0.19206067553382752, 0.10570411455987822, 0.15347032295506577, 0.09540487422740983, 0.08360630891894133, -0.1766768587894268, -1.0000000000000187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4762146193788446, 0.05595976214358289, -0.20039369104029425, 0.28930965919472607, -0.13877544586800694, -0.10626485115617988, 0.049922745019961134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20646777639788294, -0.1932581090995557, 0.007937600704136717]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1993500474956596, 0.027447032750500533, 0.44719311617393104, 0.0, -0.29823048299466254, -0.3352181634233884, -2.542572561456278, -1.1827877741334119, -1.5442052929674068, -0.5236869779123055, -1.8649141100241524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8696467036921314, 0.5173466653397626, 1.9805781575461696, -1.675311040154937, -2.360949814515019, -1.0019336360562776, 1.2159940812038226, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.39014989056841987, -0.36879770316238975, 0.0331956858122768]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044913662933, 0.11613401632809074, 0.05567331614768283, 0.0, 0.13013887396508894, 0.14986141064983624, 0.3389270626052834, 0.14918958376218805, 0.12853515096444196, -0.2313957773334218, -1.000000000037699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4700604625383813, 0.05082927134688156, -0.1999918626251158, 0.29794487843011247, -0.1342269706523728, -0.09851111868616734, 0.040535654874511946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064930679630922, -0.19323194121651005, 0.0026076751772447955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999999997003511, 0.033592312459156615, 0.4499549798999402, 0.0, -0.29315264841581834, -0.32590245878973567, -2.518708697586323, -1.1718661023438643, -1.531782159828312, -0.5417427127055413, -1.9149141099798261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8464598471325393, 0.5196314842200286, 1.9706121252746787, -1.6599820410640642, -2.367446701831865, -1.0064703094283112, 1.2175614943098638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.40047317043285663, -0.37846080958946, 0.03305339426913867]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044093829817, 0.12290559417312169, 0.055237274520183975, 0.0, 0.1015566915768841, 0.18631409267305396, 0.47727727739910464, 0.21843343579094981, 0.24846266278189927, -0.36111469586471806, -0.9999999991134741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4637371311918405, 0.04569637760531954, -0.19932064542981973, 0.3065799818174531, -0.12993774633690805, -0.09073346744067307, 0.031348262120822826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064655972887355, -0.1932621285414052, -0.0028458308627625087]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2006499519420922, 0.04003511810004251, 0.45269094781589203, 0.0, -0.28861039686939943, -0.3147651443760416, -2.4892823022395594, -1.1570507908866805, -1.5134748485088176, -0.5680391583132592, -1.9649141099779086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8235447304128778, 0.521656394972345, 1.9606785911354212, -1.6441949516323666, -2.3737434259767833, -1.0105951578991965, 1.2186683700516299, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.410792821544449, -0.3881279303848756, 0.032677488274773736]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044834821975, 0.12885611281771786, 0.05471935831903599, 0.0, 0.09084503092837815, 0.2227462882738813, 0.5885279069352773, 0.29630622914367577, 0.3661462263898845, -0.5259289121543582, -0.9999999999616506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45830233439323115, 0.040498215046326475, -0.19867068278514982, 0.31574178863394986, -0.1259344828983689, -0.08249696941770744, 0.022137514835319477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20639302223184805, -0.19334241590831164, -0.007518119887298623]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990418579913, 0.04671538543980319, 0.4554057181909018, 0.0, -0.2838827642228798, -0.3019029479424872, -2.455884788221434, -1.1381720395643866, -1.4903458368715168, -0.6010763147994233, -2.0149141099775054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8008343802272794, 0.5234171721993149, 1.950771004995255, -1.6279119791823433, -2.379853847090309, -1.0142760082439803, 1.2193088408478379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42110715147266914, -0.39780091040365606, 0.03212661541481748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874138607, 0.13360534679521358, 0.05429540750019529, 0.0, 0.09455265293039257, 0.2572439286710881, 0.667950280362509, 0.37757502644587654, 0.4625802327460171, -0.6607431297232793, -0.9999999999919376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45420700371196837, 0.03521554453940012, -0.19815172280332605, 0.3256594490004656, -0.12220842227051065, -0.07361700689567822, 0.012809415924162066, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20628659856440296, -0.19345960037560989, -0.011017457199125055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985640854057, 0.05357324937276742, 0.45810659155045075, 0.0, -0.27828038023136986, -0.28757407765082377, -2.420452115364689, -1.1151671965650922, -1.4633713831116553, -0.639506039985464, -2.0649141099481136, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7794608664244675, 0.5244703198472045, 1.9411650492665435, -1.6108132890177125, -2.3853688117460723, -1.0162423503856675, 1.2186008742168057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4314150480332894, -0.40748076114322623, 0.031460277024761264]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904445482911, 0.13715727865928448, 0.054017467190979204, 0.0, 0.1120476798301987, 0.2865774058332679, 0.7086534571348982, 0.46009685998588584, 0.5394890751972281, -0.7685945037208132, -0.9999999994121649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.42747027605623766, 0.021062952957791307, -0.19211911457422637, 0.34197380329261556, -0.11029929311527009, -0.039326842833743554, -0.014159332620644524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20615793121240503, -0.19359701479140357, -0.013326767801124356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980863865823, 0.060558253728217847, 0.4608003339180001, 0.0, -0.27124769585929104, -0.2720714565471836, -2.384536171805477, -1.087982578750324, -1.4334078958920156, -0.682249820130641, -2.114914109927149, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7619383690801973, 0.5239413460919039, 1.9324989319144232, -1.5923745781900724, -2.3894218614842417, -1.0139187264028344, 1.2147879232101293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.44171587498106996, -0.41716813981334966, 0.030729705617939817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044602353002, 0.13970008710900855, 0.053874847350987604, 0.0, 0.14065368744157608, 0.310052422072803, 0.7183188711842404, 0.5436923562953645, 0.5992697443927931, -0.8548756029035406, -0.9999999995807045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3504499468854042, -0.010579475106011309, -0.17332234704240554, 0.36877421655280007, -0.08106099476339179, 0.04647247965666023, -0.07625902013352719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20601653895561098, -0.19374757340246815, -0.014611428136428942]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976084665441, 0.06763116936743845, 0.46349199665047647, 0.0, -0.26235884845665897, -0.25569754699541775, -2.349315057040639, -1.056465929720404, -1.4011217029463618, -0.7284448442338358, -2.1649141098676727, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7495449441077074, 0.5214804819607382, 1.9251501248039335, -1.5724409526841792, -2.3915615157597157, -1.0060987553730838, 1.2070922837320053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45200940989261845, -0.4268632815303917, 0.02997584084206367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044159923643, 0.141458312784412, 0.05383325464952704, 0.0, 0.17777694805264133, 0.327478191035317, 0.7044222952967618, 0.6303329805983988, 0.6457238589130739, -0.9239004820638986, -0.9999999988104814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24786849944979672, -0.04921728262331534, -0.1469761422097941, 0.39867251011786753, -0.04279308550947567, 0.1563994205950119, -0.15391278956248045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20587069823097007, -0.19390283434084124, -0.01507729551752297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997130844338, 0.07476229667116564, 0.46618478772117466, 0.0, -0.25128950011283474, -0.23875032963856022, -2.3157137524361513, -1.0204814385968584, -1.3669705066420434, -0.7774008635131713, -2.214914109856457, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7422497665069451, 0.5172244562577061, 1.9191726927644646, -1.5510974706307565, -2.3917003534409726, -0.992886619002887, 1.1955969381640508, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46229573129892776, -0.43656609127169094, 0.029230685132609274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044755587892, 0.14262254607454386, 0.05385582141396442, 0.0, 0.22138696687648404, 0.3389443471371508, 0.6720260920897557, 0.7196898224709112, 0.6830239260863685, -0.9791203855867099, -0.9999999997756912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1459035520152469, -0.0851205140606409, -0.1195486407893788, 0.42686964106845204, -0.0027767536251423128, 0.2642427274039362, -0.229906911359091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20572642812618652, -0.19405619482598455, -0.01490311418908793]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966532733232, 0.08192522858262052, 0.46888039415683935, 0.0, -0.23767593175400703, -0.22168354143863822, -2.2849982840336165, -0.9801644044549478, -1.3307513073431536, -0.8274008885665106, -2.264914109822181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7392115747201519, 0.5115679153440071, 1.9143876819995183, -1.5284752268909134, -2.389913935093663, -0.9751042820728416, 1.1807938630140489, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.47257518851057284, -0.4462762846687216, 0.02852318716484185]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044857970357, 0.14325863822909762, 0.053912128713293275, 0.0, 0.2722713671765543, 0.3413357639984401, 0.6143093680506944, 0.8063406828382109, 0.724383985977795, -1.0000005010667865, -0.9999999993144846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06076383573586386, -0.11313081827397765, -0.0957002152989265, 0.45244487479686285, 0.035728366946192296, 0.3556467386009085, -0.29606150300003864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20558914423290142, -0.19420386794061276, -0.014149959355348452]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961757465188, 0.08903301748486578, 0.4715794237084032, 0.0, -0.22147480879436784, -0.20506404918597032, -2.258337088505657, -0.9359107771503143, -1.2920463048020234, -0.87740091362361, -2.314914109825028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7391918173828845, 0.5049722875996087, 1.9104832483634167, -1.5046223900848206, -2.3862997616093375, -0.953775414653893, 1.1632392212627674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48284934187660894, -0.45599255170371705, 0.02794281530422694]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904494639122, 0.14215577804490517, 0.053980591031276844, 0.0, 0.3240224591927836, 0.3323898450533577, 0.53322391055919, 0.885072546092669, 0.7741000508226037, -1.0000005011419866, -1.0000000000569382, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003951467453463253, -0.13191255488796916, -0.07808867272203174, 0.4770567361218574, 0.07228346968650735, 0.4265773483789722, -0.35109283502562866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548306732072152, -0.19432534069990923, -0.011607437212298176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20584956975527796, 0.09591929435173313, 0.4742818254449502, 0.0, -0.20323394897009178, -0.18936634225229104, -2.236126259020258, -0.8885078750851945, -1.251228327329373, -0.9274009386381123, -2.364914109760475, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7408578123591797, 0.49785868085957863, 1.9071025292885182, -1.4794787630397328, -2.380912016845177, -0.9298348750177827, 1.1433840472268757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49312074315231635, -0.46571174018750716, 0.02765851237722452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043612521492, 0.13772553733734705, 0.05404803473093897, 0.0, 0.3648171964855214, 0.3139541386735858, 0.44421658970798006, 0.9480580413023973, 0.8163595494530113, -1.0000005002900476, -0.9999999987089433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.033319899525904216, -0.1422721348006006, -0.06761438149797121, 0.5028725409017544, 0.1077548952832099, 0.47881079272220706, -0.3971034807178315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2054280255141487, -0.19438376967580193, -0.005686058540048478]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064995219992295, 0.10247586891485333, 0.4769872192600208, 0.0, -0.18347680707648317, -0.17485124399808333, -2.218584463460786, -0.8385855534330408, -1.208676291225198, -0.9774009636933224, -2.4149141097604034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7431160957031382, 0.4905766522403294, 1.9039338485504134, -1.4529810274913606, -2.3737479731150892, -0.9040711371926337, 1.1215577613589578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5033933423961802, -0.47542976000208337, 0.027781497716039466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879030494, 0.13113149126240384, 0.05410787630141277, 0.0, 0.39514283787217197, 0.2903019650841543, 0.3508359111894426, 0.9984464330430733, 0.8510407220834976, -1.000000501104201, -0.9999999999985625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04516566687917056, -0.14564057238498354, -0.0633736147620975, 0.5299547109674442, 0.14328087460175465, 0.5152747565029818, -0.43652571735835655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2054519848772768, -0.1943603962915242, 0.0024597067762989174]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20714947424208874, 0.1087497798270423, 0.47969516230900283, 0.0, -0.16319645140065323, -0.16103359446106466, -2.2036510925670614, -0.7885855284092813, -1.1678977513842976, -1.0274009887478648, -2.4649141097444422, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7452872959271061, 0.48340264483539896, 1.9007569166417722, -1.4251468722520122, -2.3647620003914542, -0.8771425608227693, 1.0979982825218204, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5136706717703803, -0.4851428570373369, 0.028268135747124133]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044857184991, 0.1254782182437795, 0.05415886097964067, 0.0, 0.40560711351659895, 0.2763529907403734, 0.29866741787449347, 1.0000005004751893, 0.8155707968180089, -1.0000005010908486, -0.9999999996807786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04342400447935876, -0.1434801480986095, -0.06353863817282335, 0.5566831047869689, 0.1797194544727016, 0.538571527397288, -0.47118957674274703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2055465874840014, -0.19426194070507039, 0.00973276062169336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20779942648610297, 0.11505399951598874, 0.482405313379302, 0.0, -0.14399512818284158, -0.14671201535440748, -2.1875761606731885, -0.7385855032967514, -1.1326427072862721, -1.0774010138031231, -2.514914109777272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7463112319953491, 0.47680023294367757, 1.8972925156002587, -1.3964523903027506, -2.354485392825743, -0.8506324446720157, 1.0737267971404694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5239352503067686, -0.4942257372364583, 0.02880836449977823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880284928, 0.12608439377892897, 0.054203021405982994, 0.0, 0.38402646435623317, 0.2864315821331439, 0.3214986378774594, 1.0000005022505989, 0.7051008819605089, -1.000000501105166, -1.000000000656594, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020478721364859717, -0.13204823783442785, -0.06928802083026986, 0.5738896389852342, 0.20553215131422328, 0.5302023230150723, -0.4854297076270206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20529157072776677, -0.18165760398242817, 0.010804575053081881]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2071494742420842, 0.12174093329032455, 0.48512022863353205, 0.0, -0.12703699815286704, -0.1330316338389753, -2.1692811221070403, -0.6885854782277657, -1.1062531906929634, -1.1274010388583806, -2.564914109772917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7447721797131188, 0.4698644227828504, 1.8928468390931963, -1.370000315662169, -2.346668129674009, -0.8275798134794191, 1.0524933000882424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5341653816753601, -0.5020571886286284, 0.029006302249322744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880375872, 0.13373867548671614, 0.054298305084600804, 0.0, 0.3391626005994906, 0.2736076303086439, 0.3659007713229604, 1.000000501379713, 0.5277903318661774, -1.0000005011051478, -0.999999999912899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030781045644606056, -0.13871620321654374, -0.08891353014124645, 0.5290414928116319, 0.15634526303467822, 0.46105262385193224, -0.4246699410445408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20460262737183083, -0.15662902784340033, 0.003958754990890307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952200160285, 0.1288531968728209, 0.4877537292982551, 0.0, -0.11127879631859366, -0.12123266659801699, -2.152515976867951, -0.638585453201901, -1.0849792016045696, -1.1750080095204751, -2.614914109768534, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7403127525402534, 0.4630400930972924, 1.887522054384438, -1.3458304132489392, -2.341802604476354, -0.8086387528830363, 1.0351149030017601, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5443393163617989, -0.5080176136196273, 0.028700901168124553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044809626607, 0.14224527164992679, 0.052670013294461304, 0.0, 0.31516403668546744, 0.23597934481916613, 0.3353029047817842, 1.000000500517296, 0.4254797817678723, -0.9521394132418927, -0.9999999999123431, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08918854345730803, -0.13648659371116054, -0.10649569417516626, 0.4833980482645942, 0.09731050395310598, 0.3788212119276556, -0.3475679417296472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20347869372877544, -0.119208499819979, -0.006108021623963841]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20584956974297777, 0.13622915267109276, 0.49026997596542493, 0.0, -0.09563245738549116, -0.11201254330131988, -2.1410307249611287, -0.5885854280285516, -1.0650707400211386, -1.2170697945073672, -2.664914109768335, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.733083621328042, 0.4568044054527166, 1.8816078509680838, -1.3233471258646443, -2.339360013525105, -0.7935780776758881, 1.0211795057893378, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5544385794568797, -0.5114877119316235, 0.027852796972441026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904517250131, 0.14751911596543701, 0.05032493334339612, 0.0, 0.3129267786620501, 0.1844024659339423, 0.2297050382406099, 1.0000005034669874, 0.39816923166862045, -0.841235699737842, -0.9999999999960145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.14458262424423035, -0.12471375289151534, -0.11828406832708285, 0.4496657476858964, 0.04885181902497327, 0.30121350414296555, -0.27870794424844453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20198526190161653, -0.06940196623992366, -0.016962083913670545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961749850008, 0.14347767687799604, 0.4926883436390763, 0.0, -0.0799490845530307, -0.10473597296061643, -2.1385753663749787, -0.5385854029659267, -1.042777806598555, -1.2530083189787227, -2.7141678650258716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.723212907717397, 0.4514133974815875, 1.8753360586111512, -1.301981413310433, -2.338886394443288, -0.7819601456803171, 1.0101823202031883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5644669740578634, -0.5124715600072361, 0.026578481527876154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044889553888, 0.14497048413806565, 0.04836735347302726, 0.0, 0.3136674566492093, 0.14553140681406895, 0.04910717172737772, 1.000000501252499, 0.4458586684516722, -0.7187704894271084, -0.9850751051507305, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19741427221289898, -0.107820159422582, -0.12543584713865363, 0.42731425108422566, 0.009472381636343591, 0.232358639911418, -0.21994371172299126, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20056789201967395, -0.019676961512254725, -0.02548630889129742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966525107235, 0.1501180568282623, 0.4950581279024008, 0.0, -0.0643583983722623, -0.0986053141444437, -2.1477792342193154, -0.48858537787584494, -1.0152356226636083, -1.2833013137851883, -2.760990841056552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7109834366159921, 0.4468695283308784, 1.8688737216200249, -1.281207065531371, -2.3399299756846346, -0.7730676992512461, 1.001480798261087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5744416597538146, -0.5113878401654328, 0.025071403548264388]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044948554406, 0.1328075990053251, 0.04739568526648936, 0.0, 0.3118137236153678, 0.12261317632345448, -0.18407735688673582, 1.0000005018016358, 0.5508436786989327, -0.6058598961293146, -0.9364595206136054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24458942202809822, -0.09087738301418201, -0.12924673982252782, 0.4154869555812392, -0.0208716248269358, 0.17784892858142218, -0.17403043884202934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19949371391902437, 0.021674396836067467, -0.030141559592235332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20389971302483856, 0.1557347602845968, 0.4974355814920868, 0.0, -0.049171950719876324, -0.09290833001914381, -2.166699123922198, -0.43858535282219446, -0.983039311514298, -1.3088912161864783, -2.805051479993562, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.696631918576592, 0.44306047961185746, 1.8623103243262331, -1.2606412765175208, -2.3421891515752655, -0.766255196787645, 0.9945600283663869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.584377181551185, -0.5085839361568828, 0.02352282088400695]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044524675847, 0.11233406912669008, 0.04754907179371985, 0.0, 0.3037289530477196, 0.11393968250599804, -0.37839779405765367, 1.0000005010730098, 0.6439262229862059, -0.5117980480258004, -0.8812127787402005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2870303607880001, -0.07618097438041899, -0.13126794587583548, 0.41131578027700544, -0.04518351781261587, 0.1362500492720216, -0.13841539789400073, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1987104359474099, 0.056078080171000425, -0.03097165328514873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976078082183, 0.16004026855228848, 0.4998663148578667, 0.0, -0.03475744050340202, -0.08704928408971153, -2.1937156986745796, -0.3885853277524376, -0.9469153092290022, -1.330848638717644, -2.846731398229221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.680328560204502, 0.43983553820878407, 1.8556791868320301, -1.2400132328159672, -2.3454682780451055, -0.761004411987782, 0.989031466263781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5942847510091662, -0.5043478281575161, 0.022093544939932187]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880334902, 0.0861101653538336, 0.04861466731559875, 0.0, 0.288290204329486, 0.1171809185886454, -0.5403314950476272, 1.0000005013951379, 0.7224800457059154, -0.4391484506233125, -0.8335983647131766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3260671674417992, -0.0644988280614681, -0.1326227498840574, 0.4125608740310738, -0.06558252939680123, 0.10501569599726031, -0.11057124205211823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19815138915962352, 0.08472215998733477, -0.02858551888149523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980853628662, 0.1628810660419216, 0.5023836857779382, 0.0, -0.02146507066358042, -0.08050544006023874, -2.227328958476591, -0.3385853065366045, -0.9075100422134267, -1.350229081014295, -2.886554478075514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6622171825178012, 0.4370416681576247, 1.8489840447886192, -1.2191099997866723, -2.349599213706185, -0.7568828944553346, 0.9845644102047254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6041723284826315, -0.49892698401412294, 0.020906601296891956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044890704152, 0.056815949792662565, 0.05034741840143012, 0.0, 0.26584739679643205, 0.13087688058945599, -0.6722651960402309, 1.0000004243166616, 0.7881053403115118, -0.3876088459330212, -0.7964615969258632, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36222755373401777, -0.05587740102318819, -0.13390284086821666, 0.41806466058589586, -0.08261871322159553, 0.08243035064894742, -0.08934112118111256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19775154946930532, 0.108416882867863, -0.023738872860804647]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985629231166, 0.16403503715368722, 0.5050072272508807, 0.0, -0.011243884127353705, -0.07421039306373724, -2.2662195663178375, -0.2898353030935007, -0.8658600300289816, -1.3654800266138287, -2.922378543192585, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6422493597370729, 0.43452377840769396, 1.8421865306661536, -1.1975862116477367, -2.3543180247878333, -0.7533806159453872, 0.9807201183559711, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6140442139193496, -0.49255562128481134, 0.02022972303051304]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879498977, 0.02307942223531246, 0.05247082945884825, 0.0, 0.20442373072453424, 0.1259009399300301, -0.7778121568249285, 0.9750000688620889, 0.8330002436889006, -0.30501891199067344, -0.7164813023414127, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3993564556145661, -0.05035779499861437, -0.1359502824493128, 0.43047576277871336, -0.09437622163296054, 0.07004557019894854, -0.07688583697508587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19743770873436203, 0.12742725458623247, -0.013537565327578261]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990404829132, 0.1634528238542528, 0.5077442557294407, 0.0, -0.0052736904708706395, -0.0688637565733239, -2.3093320525908254, -0.24608531727078933, -0.8223896271717159, -1.3756473939547909, -2.953043017750895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6204459301088425, 0.43216271543255413, 1.8352615284808589, -1.1751861103482526, -2.359402241429792, -0.7501162514018523, 0.9771526473899087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6239007551967034, -0.4854186738108172, 0.02021091229376357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880406778, -0.01164426598868843, 0.054740569571201006, 0.0, 0.1194038731296613, 0.10693272980826685, -0.862249725459756, 0.8749997164542269, 0.8694080571453129, -0.2033473468192408, -0.6132894911662041, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4360685925646062, -0.04722125950279615, -0.13850004370589578, 0.4480020259896821, -0.10168433283917212, 0.0652872908706964, -0.07134941932124653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19713082554707667, 0.14273894947988258, -0.0003762147349894666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995207125083, 0.16125515316071548, 0.5105965959626493, 0.0, -0.0037487047189047433, -0.06473860939691131, -2.3558220390061826, -0.2110853491157563, -0.7770705824432016, -1.3807552560112464, -2.9786328165653635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5969319840743816, 0.42987640088613466, 1.8282067634454782, -1.1517576808179886, -2.364683061285807, -0.7468397566077684, 0.9736201630002069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6337399387311056, -0.47766274797102026, 0.02085730157444466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999039540809772, -0.043953413870746395, 0.057046804664170475, 0.0, 0.030499715039317907, 0.08250294352825183, -0.9297997283071426, 0.6999993631006605, 0.9063808945702878, -0.1021572411291091, -0.5117959762893696, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.47027892068921706, -0.04572629092838926, -0.14109530070761406, 0.46856859060527967, -0.10561639712030374, 0.06552989588167944, -0.07064968779403517, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1967836706880425, 0.1551185167959386, 0.012927785613621815]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999999984326117, 0.15768765165884438, 0.5135512489358962, 0.0, -0.00616463600715151, -0.061846554116171536, -2.405014028064136, -0.18858539873101185, -0.7298031601922028, -1.3815453045766257, -3.000000195125954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5719289977899731, 0.42761247062920993, 1.8210415729253842, -1.127232545602249, -2.3700346013699742, -0.7433995533741241, 0.9699621806321289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6435589804185872, -0.4694049232923046, 0.022059696800314513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044559793125, -0.07135003003742205, 0.05909305946493837, 0.0, -0.04831862576493534, 0.05784110561479554, -0.9838397811590689, 0.449999007694889, 0.9453484450199748, -0.015800971307585995, -0.4273475712118086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.50005972568817, -0.04527860513849512, -0.14330381040188064, 0.49050270431479176, -0.10703080168334739, 0.06880406467288452, -0.07315964736156136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19638083374963167, 0.1651564935743131, 0.02404790451739708]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1993500475993132, 0.1531059836622251, 0.5165972804966571, 0.0, -0.011321500045881627, -0.059722561727841024, -2.455014053119358, -0.1748354661144148, -0.6808404506671848, -1.3797754066509618, -3.018756930641455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.545776366805559, 0.42534237538555697, 1.8138078595489, -1.101631862133982, -2.3753719026962243, -0.7397278004894978, 0.9660930013351087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6533561077416291, -0.46074001291962563, 0.02359243322392935]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878959289, -0.09163335993238557, 0.060920631215217964, 0.0, -0.10313728077460235, 0.042479847766610235, -1.0000005011044395, 0.274998652289112, 0.9792541905003596, 0.03539795851328094, -0.3751347103100101, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5230526196882822, -0.04540190487305961, -0.1446742675296841, 0.5120136693653407, -0.1067460265249996, 0.07343505769252516, -0.07738358594040508, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1959425464608382, 0.17329820745357993, 0.03065472847229672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009535586797, 0.1478265715582224, 0.5197240940829704, 0.0, -0.018404427062329774, -0.05835052075953421, -2.5050140781741654, -0.1660855512702357, -0.630840450758246, -1.376485342803627, -3.035810258442042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5187666738714398, 0.42304827153940777, 1.8065449697932832, -1.074960536705539, -2.380613433408026, -0.7357640502338193, 0.9619317187747937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6631309078675722, -0.451745218465321, 0.025253383383543715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044868904913, -0.1055882420800543, 0.06253627172626618, 0.0, -0.14165854032896297, 0.0274408193661363, -1.0000005010961466, 0.17499829688358215, 0.9999999981787757, 0.06580127694669732, -0.3410665560117501, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5401938586823838, -0.04588207692298429, -0.14525779511233775, 0.5334265085688592, -0.10483061423602534, 0.07927500511357005, -0.08322565120630003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19549600251886146, 0.17989588908609205, 0.03321900319228731]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980501431118577, 0.1421007874172408, 0.5229216746904746, 0.0, -0.02658431568031288, -0.05747198159103363, -2.5550141032293996, -0.15858565418962448, -0.5808404507647364, -1.3727673576968753, -3.0520895642158288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4911254567069497, 0.42071833519784235, 1.79928617618249, -1.0471938394617235, -2.385674963330175, -0.7314405198040996, 0.9573896266296948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728842725984181, -0.44248358922131076, 0.02688599015013237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880205283, -0.1145156828196317, 0.06395161215008299, 0.0, -0.16359777235966208, 0.017570783370011552, -1.0000005011046809, 0.1499979414776177, 0.9999999998701911, 0.07435970213503222, -0.32558611547573035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5528243432898023, -0.046598726831308786, -0.14517587221586284, 0.5553339448763092, -0.10123059844298155, 0.08647060859439241, -0.0908418429019767, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19506729461691788, 0.18523258488020505, 0.032652135331773094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019086785293, 0.13606399813496428, 0.5261810657016347, 0.0, -0.035472835377396775, -0.057101985885221355, -2.605014128284609, -0.15483565910571975, -0.5308404507710939, -1.368904944270376, -3.067949081016235, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46294756611546506, 0.4183410790120704, 1.792050829594656, -1.0182330824384032, -2.3904526312345604, -0.7266530272982114, 0.9523399269391635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6826176217761467, -0.4330062059173643, 0.028430379332107875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880095423, -0.12073578564553024, 0.06518782022320214, 0.0, -0.17777039394167793, 0.007399914116245536, -1.00000050110419, 0.0749999016780947, 0.9999999998728506, 0.0772482685299836, -0.3171903360081307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.563557811829693, -0.04754512371543864, -0.14470693175668006, 0.5792151404664072, -0.09555335808771143, 0.0957498501177645, -0.10099399381062744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19466698355457251, 0.1895476660789295, 0.030887783639510044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023862382987, 0.12982277795756555, 0.5294946501058542, 0.0, -0.043531957664554234, -0.057110529894674356, -2.655014153339869, -0.15108566257591344, -0.4808404507710939, -1.3652633803964829, -3.082522285964115, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4356805662753338, 0.4157580239385849, 1.7851077565307472, -0.9877918440271041, -2.393629089153797, -0.7201146745182879, 0.9453928203124106, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6923502699602505, -0.42393915197121984, 0.029838748765362626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880461195, -0.12482440354797446, 0.06627168808438987, 0.0, -0.16118244574314916, -0.00017088018905999074, -1.0000005011051973, 0.07499993059612628, 1.0, 0.07283127747786261, -0.2914640989576027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5453399968026248, -0.051661101469710376, -0.13886146127817714, 0.6088247682259811, -0.06352915838472939, 0.13076705559846796, -0.13894213253505744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1946529636820768, 0.18134107892288842, 0.02816738866509501]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028637983842, 0.12348623709877309, 0.5328527398750367, 0.0, -0.04969676221172055, -0.057485647706447485, -2.7050141783949404, -0.1510856639697593, -0.4308404507919986, -1.361897389465149, -3.094971635756059, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41044558298583034, 0.4128748517544358, 1.7786892467856021, -0.9557549202216273, -2.3941818789341616, -0.7109142627610385, 0.9355052143242124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7021041457419289, -0.41590859078600234, 0.031094731410392658]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879828718, -0.1267308171758495, 0.06716179538365002, 0.0, -0.1232960909433263, -0.00750235623546257, -1.0000005011014281, -2.7876917302327442e-08, 0.9999999995819053, 0.0673198186266802, -0.24898699583888168, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.504699665790069, -0.05766344368298311, -0.12837019490289894, 0.6407384761095339, -0.011055795607288886, 0.18400823514498735, -0.19775211976396387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.195077515633568, 0.16061122370434996, 0.025119652900600663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033413581114, 0.11725984300068812, 0.5362419192213744, 0.0, -0.05346509209642338, -0.05821348256404178, -2.7550142034502008, -0.15108566396972173, -0.3808404507919988, -1.3589670324368708, -3.1050165137103725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3877605510969789, 0.4096955213135772, 1.7729241862523164, -0.922217272698735, -2.391649727333554, -0.6988078337317745, 0.9222569378761857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.711903327841214, -0.40954104556327225, 0.032154828425129574]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880545577, -0.1245278819616992, 0.0677835869267552, 0.0, -0.07536659769405668, -0.014556697151885964, -1.0000005011052027, 7.515571488957265e-13, 0.9999999999999958, 0.05860714056556331, -0.2008975590862666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45370063777702946, -0.06358660881717078, -0.11530121066571655, 0.6707529504578463, 0.05064303201215177, 0.24212858058528186, -0.26496552896053505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1959836419857026, 0.1273509044546015, 0.021201940294738347]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.194800381891786, 0.11140651526474173, 0.5396456406321406, 0.0, -0.05472175647520017, -0.059232195843190456, -2.805014228505461, -0.15108566396970827, -0.330840450791999, -1.3565871969353567, -3.1126913630238477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3677081904528124, 0.4062750476728567, 1.7678641069457335, -0.8873084625152019, -2.385832343668878, -0.6839122652153853, 0.9054977056595419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.721772988008984, -0.40546319243640266, 0.03299932331538283]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880502625, -0.11706655471892778, 0.06807442821532397, 0.0, -0.02513328757553563, -0.02037426558297347, -1.0000005011052049, 2.6930039876871783e-13, 0.999999999999997, 0.0475967100302808, -0.15349698626950314, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40104721288332945, -0.06840947281441045, -0.10120158613166023, 0.6981762036706615, 0.11634767329352289, 0.29791137032778403, -0.33518464433287654, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1973932033554007, 0.08155706253739231, 0.016889897805065085]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415042964776344, 0.10624086999716453, 0.543045632780374, 0.0, -0.05348699854456831, -0.06045094654852357, -2.855014253560714, -0.15108566397066872, -0.2808404508041338, -1.354804428019382, -3.1180936245074147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.35020072663132, 0.40267658592562, 1.763532413131884, -0.851091450772986, -2.3765030775719227, -0.666426491427131, 0.8850237238372762, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.73172413878826, -0.4038776609292309, 0.03363408450187708]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880451413, -0.103312905351544, 0.0679998429646669, 0.0, 0.024695158612637234, -0.024375014106662304, -1.0000005011050572, -1.92089421119441e-11, 0.9999999997573039, 0.035655378319491046, -0.10804522967133524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35014927642984706, -0.07196923494473477, -0.08663387627699216, 0.724340234844318, 0.18658532193910699, 0.34971547576508616, -0.40947963644531254, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19902301558552038, 0.031710630143435226, 0.012695223729885036]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19350047740374038, 0.10208601244693091, 0.5464253702836711, 0.0, -0.0500554056491182, -0.06177358669528461, -2.905014278615974, -0.1510856639706687, -0.2308404508041338, -1.353593745533974, -3.121540769967444, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.334795790861629, 0.39897602354908296, 1.7598920071795534, -0.8134632686738965, -2.363555862553039, -0.6467319013928798, 0.8607037819043989, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7417455709631614, -0.4043697536173637, 0.03408620694107694]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880461285, -0.08309715100467241, 0.06759475006594273, 0.0, 0.06863185790900211, -0.026452802935220857, -1.0000005011051973, 6.699698549881089e-16, 1.0, 0.02421364970816069, -0.06894290920059078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30809871539382094, -0.07401124753074047, -0.07280811904660889, 0.7525636419817895, 0.2589443003776699, 0.3938918006850227, -0.4863988386575473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004286434980274, -0.00984185376265648, 0.009042448783997115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052515971743, 0.09919621459447991, 0.5497746088744935, 0.0, -0.044743809407597465, -0.06311462718084727, -2.9550143036712315, -0.15108566397393738, -0.18084045080628525, -1.3528928706486967, -3.123336846852577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3209903415746785, 0.3952334020779346, 1.7569151089505652, -0.7741415471294454, -2.346768275172348, -0.625184498628295, 0.8322293043745047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7518268543330414, -0.4065938730473247, 0.034391306373769054]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488045882, -0.05779595704902002, 0.06698477181644778, 0.0, 0.10623192483041466, -0.02682080971125322, -1.0000005011051578, -6.537362009349135e-11, 0.9999999999569708, 0.014017497705543246, -0.03592153770265838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27610898573900977, -0.074852429422967, -0.05953796457976281, 0.7864344308890218, 0.3357517476138206, 0.4309480552916968, -0.5694895505978831, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2016256673975996, -0.044482388599219956, 0.006101988653842297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057291569473, 0.09771681594988851, 0.5530897308860852, 0.0, -0.0378326129635943, -0.06440600603043037, -3.0050143287264848, -0.15108566396806272, -0.13084045080689594, -1.3526246336896657, -3.123729111930007, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3082969862682504, 0.391562832084579, 1.7544032059645278, -0.7327468420860533, -2.3256337929756556, -0.6020119965039805, 0.7989388921336881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7619586078069222, -0.4102619236645109, 0.03458597316747342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880453997, -0.029587972891827918, 0.06630244023183293, 0.0, 0.13822392888006327, -0.025827576991661962, -1.0000005011050692, 1.1749331784800576e-10, 0.9999999999877863, 0.005364739180617806, -0.007845301548598749, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2538671061285619, -0.0734113998671122, -0.05023805972075046, 0.8278941008678415, 0.42268964393384745, 0.46345004248628874, -0.6658082448163329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20263506947761573, -0.07336101234372465, 0.0038933358740873454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062067167086, 0.09768311833415702, 0.5563715143433214, 0.0, -0.029578400160805388, -0.06559781370835066, -3.0550143537817447, -0.15108566396804227, -0.08084045080689617, -1.352709797800101, -3.1229315466599212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29624812924312005, 0.38828587567980505, 1.7515133532901046, -0.6888641628709329, -2.2990742171570946, -0.5771980123146865, 0.7608559862502859, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7721323180897082, -0.41512481737513857, 0.034703972904727945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880477215, -0.0006739523146299699, 0.06563566914472549, 0.0, 0.1650842560557783, -0.023836153558405765, -1.0000005011051971, 4.093820046833613e-13, 0.9999999999999953, -0.0017032822087073227, 0.01595130540171204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24097714050260752, -0.06553912809547843, -0.05779705348846587, 0.8776535843024084, 0.5311915163712216, 0.4962796837858806, -0.7616581176680423, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20347420565572077, -0.09725787421255347, 0.0023599947450904167]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19090066842068107, 0.09905019821720568, 0.559622516332651, 0.0, -0.020251583133576265, -0.0666557903129154, -3.105014378837004, -0.1510856639671973, -0.030840450806902286, -1.3530693915611052, -3.1211788744540523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2844025123609683, 0.38605225882708716, 1.7461341166806055, -0.6422997301764205, -2.2658265565003815, -0.5504230827574887, 0.7183896615413528, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7823396072090592, -0.42094391136383696, 0.0347657581216569]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045019795926, 0.027341597660972963, 0.06502003978659196, 0.0, 0.1865363405445825, -0.02115953209129461, -1.0000005011051905, 1.6899523227346692e-11, 0.9999999999998775, -0.007191875220084972, 0.03505344411737497, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23691233764303435, -0.04467233705435793, -0.10758473218998413, 0.9312886538902485, 0.6649532131342638, 0.5354985911439556, -0.8493264941786643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20414578238701966, -0.11638187977396824, 0.001235704338579088]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071618273126, 0.10177670978088993, 0.5628453353346253, 0.0, -0.010008191778812053, -0.06755713850463801, -3.1550144038921792, -0.15108566396789896, 0.019159549192805186, -1.3536065082394133, -3.118653567873419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2725368957113056, 0.38453371293233773, 1.7384471621046758, -0.5936379938258535, -2.2272284279763612, -0.522335624205453, 0.6724166017760013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925732316328732, -0.4275289296599921, 0.03472065903468458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044758996303, 0.054530231273685024, 0.06445638003948663, 0.0, 0.20486782709528423, -0.01802696383445232, -1.0000005011034976, -1.4033141114487748e-11, 0.9999999999941495, -0.010742333566161255, 0.0505061316126605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2373123329932541, -0.030370917894988088, -0.15373909151859416, 0.9732347270113408, 0.771962570480407, 0.5617491710407155, -0.9194611953070297, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20467248847628142, -0.13170036592310264, -0.0009019817394463239]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076388482106, 0.10574357227851135, 0.5660417576546126, 0.0, -0.00042576089466839565, -0.06829442303081046, -3.2012644289473546, -0.1510856639621717, 0.06540954919226402, -1.3542323562786198, -3.11591463792251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2592387461756797, 0.3834738615738649, 1.7287842128246071, -0.5436379687750676, -2.1843499251465626, -0.4942662776437652, 0.6236381539450436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8028106481204823, -0.43425648000666217, 0.03455544591445554]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045958203951, 0.07933724995242827, 0.06392844639974546, 0.0, 0.1916486176828731, -0.014745690523448884, -0.9250005011035052, 1.1454484291921683e-10, 0.9249999999891767, -0.012516960784131496, 0.05477859901818476, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26596299071251867, -0.02119702716945642, -0.193258985601374, 1.0000005010157158, 0.8575700565959689, 0.5613869312337558, -0.9755689566191522, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20474832975218196, -0.13455100693340136, -0.003304262404580721]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081164078212, 0.11084488526123108, 0.5692152641411549, 0.0, 0.007327081444803023, -0.06891422758095465, -3.24001445400253, -0.15108566396217094, 0.10415954919147422, -1.3548236443389758, -3.113469220037347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24389564605362593, 0.3826857249632519, 1.7174401801441044, -0.4936379437197939, -2.1380471228827242, -0.4674307293897115, 0.5736381539450451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8130290285570152, -0.4405040284177781, 0.034185257773753745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880778517, 0.10202625965439471, 0.06347012973084504, 0.0, 0.15505684678942835, -0.012396091002884031, -0.7750005011035128, 1.5416625098004766e-14, 0.774999999984204, -0.011825761207120965, 0.04890835770325934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3068620024410758, -0.015762732212259954, -0.22688065361005555, 1.000000501105475, 0.9260560452767674, 0.5367109650810742, -0.9999999999999701, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2043676087306583, -0.12495096822231867, -0.0074037628140359805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18830085939674862, 0.1168682998621621, 0.5723735984918562, 0.0, 0.01279488605585831, -0.06949015565604581, -3.267514479057706, -0.1510856639621704, 0.13165954919043577, -1.355295556055603, -3.1116941390594457, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22639404800798923, 0.38206343620151845, 1.7044270009377873, -0.4436379186645256, -2.0890048810716535, -0.44252512835682656, 0.5236381539450461, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8232062897281709, -0.4456495101855262, 0.03356048893964285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880669865, 0.12046829201862037, 0.06316668701402718, 0.0, 0.10935609222110573, -0.011518561501823146, -0.5500005011035205, 1.0285593347541038e-14, 0.5499999999792312, -0.009438234332541996, 0.03550161955802123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35003196091273364, -0.012445775234669245, -0.26026358412634165, 1.0000005011053654, 0.9808448362214114, 0.49811202065769816, -0.9999999999999819, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354522342311293, -0.1029096353549623, -0.012495376682217854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.187650907146763, 0.12349070696850292, 0.575530926732498, 0.0, 0.015875769056676658, -0.07009857410633885, -3.2800145041138236, -0.1510856639619281, 0.14415954918915228, -1.3556044392466584, -3.110780610866699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20678927323091031, 0.38145448726057296, 1.6900504329166228, -0.393637893605721, -2.039004881071841, -0.41995974399263125, 0.4736381539454505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8333223339433692, -0.449070888338172, 0.03267152049044358]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044999712342, 0.13244814212681633, 0.06314656481283405, 0.0, 0.06161766001636698, -0.012168369005860841, -0.2500005011223463, 4.846041807285645e-12, 0.24999999997433026, -0.006177663821108001, 0.018270563854934467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3920954955415783, -0.012178978818909237, -0.2875313604232904, 1.0000005011760922, 0.9999999999962499, 0.45130768728390613, -0.9999999999919122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2023208843039665, -0.06842756305291622, -0.01777936898398549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095490224208, 0.1303059818083584, 0.578709596447737, 0.0, 0.01663740539542849, -0.07079335890312408, -3.279348617111691, -0.15108566396190268, 0.1433262158547493, -1.3557531566458456, -3.1108328465955637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.18518989723312684, 0.38070151043865647, 1.674827226995007, -0.34363787239074856, -1.989004881071854, -0.3999369843270981, 0.4236381539454852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8433600970483742, -0.4501459080461137, 0.031530233574934854]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044890418355, 0.13630549679710965, 0.06357339430478097, 0.0, 0.015232726775036641, -0.01389569593570463, 0.013317740042652182, 5.084029732821355e-13, -0.016666666688059273, -0.0029743479837431807, -0.0010447145772944123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.43198751995566914, -0.015059536438330285, -0.30446411843231347, 1.0000004242994487, 0.9999999999997422, 0.4004551933106626, -0.9999999999993061, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007552621001006, -0.021500394158834236, -0.0228257383101745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100265822452, 0.13716782503642297, 0.5819414810463058, 0.0, 0.015622662698062803, -0.07158909666787702, -3.2676865852172723, -0.1510856639619363, 0.13138177142430832, -1.3556264374294271, -3.1118264350361655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16482978366483125, 0.37956727677911706, 1.6605101123009882, -0.2948878689479938, -1.9390048810727891, -0.38320267563393423, 0.3736381539456568, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8533331710492935, -0.4491320139890995, 0.029839529773247796]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880351208, 0.13723686456129133, 0.06463769197137753, 0.0, -0.020294853947313757, -0.015914755295059032, 0.23324063788837107, -6.723347370973023e-13, -0.23888888860881952, 0.0025343843283717675, -0.019871768812037185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40720227136591186, -0.022684673190788124, -0.2863422938803785, 0.9750000688550795, 0.9999999999812937, 0.33468617386327815, -0.9999999999965685, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19946148001838562, 0.020277881140283848, -0.033814076033741196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18570105059554876, 0.14372000985997885, 0.5852616088199726, 0.0, 0.013150080016791667, -0.07247482681912906, -3.246826533544618, -0.15108566396397757, 0.11017806894184964, -1.3552536464253246, -3.113673881772124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14731632679496365, 0.37730029947682714, 1.6508490803594336, -0.2511378748513695, -1.8927548810250436, -0.3706853076590909, 0.3271660452713667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8632601662738979, -0.4463858952467008, 0.02755433778903355]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999041253515484, 0.13104369647111783, 0.06640255547333526, 0.0, -0.04945165362542271, -0.01771460302504093, 0.4172010334530901, -4.0825890786404623e-11, -0.4240740496491734, 0.0074558200820498185, -0.0369489347191731, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3502691373973523, -0.0453395460457983, -0.1932206388310925, 0.8749997134115084, 0.9250000009549093, 0.2503473594968669, -0.9294421734858019, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853990449208828, 0.054922374847974006, -0.04570383968428495]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18505109835132671, 0.1495111131536685, 0.5887013217648692, 0.0, 0.00931219129786175, -0.0734210099581803, -3.2182616806552238, -0.15108566396396783, 0.0812583168731341, -1.3547750322338903, -3.1162672465180634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1328210203207374, 0.37434308384091103, 1.6455594497755093, -0.21613790695268945, -1.8540048809286176, -0.3616218961841422, 0.2879718279226149, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.873158245191225, -0.442204125368704, 0.024838751974921722]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884440905, 0.11582206587379303, 0.06879425889793392, 0.0, -0.07675777437859833, -0.01892366278102456, 0.5712970577878788, 1.9500473059854678e-13, -0.5783950413743107, 0.009572283828689267, -0.05186729491878928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28990612948452515, -0.05914431271832189, -0.10579261167848765, 0.6999993579736011, 0.7750000019285248, 0.1812682294989748, -0.7838843469750373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19796157834654132, 0.08363539755993613, -0.05431171628223651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18440114610098793, 0.15414407269932823, 0.5922847927776022, 0.0, 0.004127325710146613, -0.07438421725731753, -3.183465468653156, -0.1510856639636442, 0.046122515218160964, -1.354367038965555, -3.1195149135950384, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12078338944013996, 0.37121588888835955, 1.6419956491561358, -0.19363795682445784, -1.8265048807835136, -0.3550175377881328, 0.25980550189940127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.883041798944669, -0.43683829991992523, 0.02193868311631353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045006775784, 0.09265919091319452, 0.0716694202546576, 0.0, -0.10369731175430275, -0.0192641459827447, 0.6959242400413602, 6.4723970762956335e-12, -0.7027160330994626, 0.008159865366703163, -0.06495334153949786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2407526176119486, -0.0625438990510294, -0.07127601238746689, 0.44999900254446545, 0.5500000029021404, 0.13208716792018851, -0.5633265204642727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19767107506888132, 0.10731650897557556, -0.05800137717216389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18375119384291677, 0.15732942807231187, 0.5960270238503697, 0.0, -0.0023616147181740096, -0.07531734882974532, -3.1436778726233734, -0.1510856639629031, 0.006013873894185555, -1.3541933031256093, -3.123265085874298, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10995913409493915, 0.3680666995102423, 1.6407153122466238, -0.17988802446905186, -1.8140048805897255, -0.3502158021940072, 0.24498336322442604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8929219161656519, -0.43053012581329686, 0.019114919880067693]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045161422964, 0.06370710745967303, 0.07484462145534933, 0.0, -0.12977880856641244, -0.01866263144855585, 0.7957519205956515, 1.4822292710075692e-11, -0.8021728264795082, 0.0034747167989180117, -0.07500344558519137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21648510690401612, -0.06298378756234504, -0.025606738190238537, 0.2749986471083416, 0.2500000038757602, 0.0960347118825112, -0.29644277349950443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1976023444196566, 0.12616348213256767, -0.05647526472491666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18310124150925075, 0.1589889611753551, 0.5999337936781227, 0.0, -0.00984731799743496, -0.07617358642091679, -3.1026488864346318, -0.15108566396100356, -0.03531761227217421, -1.3543383854722173, -3.1277285057152535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09983094535420313, 0.36506538386402926, 1.6407601284466957, -0.1711381098793262, -1.8148382118118953, -0.34667186046993215, 0.24235030700496213, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9028056123666762, -0.4234714369026071, 0.01651140412187688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046673320499, 0.033190662060864594, 0.07813539655506205, 0.0, -0.14971406558521902, -0.01712475182342931, 0.8205797237748332, 3.799090597542977e-11, -0.8266297233271953, -0.0029016469321622267, -0.0892683968191105, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20256377481472054, -0.060026312924260486, 0.0008963240014389778, 0.17499829161692027, -0.01666662444339634, 0.07087883448150187, -0.05266112438927842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19767392402048758, 0.14117377821379615, -0.05207031516381623]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1824512892652273, 0.15915939644494007, 0.6040022486202019, 0.0, -0.01790119568347799, -0.07694366735720332, -3.064128510086931, -0.15108566396100354, -0.07412194328091834, -1.3548016861352943, -3.1333542967049053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08974399180899639, 0.3622112885232253, 1.6428104144171176, -0.16363821307305126, -1.826782654497037, -0.3441091903026668, 0.2488243667568404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9126966482492623, -0.4158144144853017, 0.014217011760813062]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880469067, 0.003408705391698987, 0.08136909884158368, 0.0, -0.16107755372086058, -0.015401618725730402, 0.7704075269540149, 4.046905280882585e-16, -0.7760866201748824, -0.009266013261538563, -0.11251581979303481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20173907090413462, -0.05708190681607927, 0.041005719408437384, 0.14999793612549894, -0.23888885370283033, 0.05125340334530691, 0.1294811950375653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.197820717651723, 0.1531404483461079, -0.04588784722127638]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18180133702120382, 0.1579836902397271, 0.6082239844852447, 0.0, -0.026245477880351354, -0.07765637687954342, -3.031866743580271, -0.1510856639610035, -0.1066491191320468, -1.3554931543420097, -3.140331227004298, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07958225519360303, 0.3595102128394174, 1.6466750999640751, -0.1598882172868466, -1.8479863567346548, -0.3423665152106241, 0.2626293353429637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9225967014108053, -0.4076801011764562, 0.012242447282070938]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880469665, -0.023514124104259182, 0.08443471730085615, 0.0, -0.16688564393746724, -0.014254190446802208, 0.6452353301331967, 4.3893720018571743e-16, -0.6505435170225695, -0.01382936413430796, -0.13953860598785225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2032347323078672, -0.054021513676158386, 0.07729371093914962, 0.07499991572409334, -0.42407404475235866, 0.03485350184085309, 0.27609937172246535, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19800106323085867, 0.1626862661769106, -0.03949128957484249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18115138465868108, 0.15564678986916028, 0.6125871981160778, 0.0, -0.03361419240013659, -0.07836283251325987, -3.0096135869123235, -0.15108566395456785, -0.12914913982615003, -1.3563246227167198, -3.1475371302524815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07033204439736407, 0.35662631523658256, 1.656104185056394, -0.1561382222029459, -1.8769061085970973, -0.34143627720905445, 0.2800152127652186, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9325117905050209, -0.39969057515731043, 0.01055997406833761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999047250454683, -0.04673800741133668, 0.08726427261666053, 0.0, -0.1473742903957047, -0.014129112674329083, 0.44506313335895087, 1.287132596842939e-10, -0.45000041388206435, -0.016629367494202383, -0.14411806496367263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.18500421592477906, -0.05767795205669744, 0.18858170184637846, 0.0749999016780138, -0.5783950372488509, 0.01860476003139278, 0.34771754844509944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19830178188431102, 0.15979052038291505, -0.03364946427466657]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18050143249818038, 0.15238286092135125, 0.6170735685025275, 0.0, -0.039042785036414715, -0.0791166074452899, -3.001119040082996, -0.15108566395905232, -0.1378720053635739, -1.3572409674664012, -3.1540043553793686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06278847247649953, 0.3533160146345854, 1.6748476696820527, -0.15238822711904093, -1.9120419100866872, -0.34127662330276953, 0.29723199902385944, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9424451545427063, -0.39246829759872076, 0.009133325242966839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043210014247, -0.06527857895618058, 0.08972740772899394, 0.0, -0.10857185272556252, -0.015075498640600326, 0.1698909365865478, -8.968913603425124e-11, -0.1744573107484777, -0.01832689499362691, -0.12934450253773833, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15087143841729078, -0.06620601203994364, 0.37486969251317437, 0.07499990167810085, -0.7027160297917996, 0.003193078125698903, 0.3443357251728169, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1986672807537077, 0.14444555117179345, -0.028532976507415438]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17985148023812256, 0.1485040403757502, 0.6216570530857805, 0.0, -0.04212970094835467, -0.07995169277133968, -3.005290251050999, -0.1510856639581898, -0.13394898939747776, -1.3582234656051229, -3.159235973536804, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.057432194132922526, 0.34962387823871066, 1.7017172401933713, -0.1523882287556444, -1.9510224762068111, -0.34166623669419177, 0.31052969413526527, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9523982029141851, -0.38663617873502326, 0.007918215737823633]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045201156086, -0.07757641091202078, 0.09166969166505873, 0.0, -0.0617383182387991, -0.016701706520995615, -0.08342421936006261, 1.725052272299186e-11, 0.07846031932192304, -0.019649962774433247, -0.10463236314870206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1071255668715402, -0.07384272791749483, 0.5373914102263719, -3.2732069110696926e-08, -0.7796113224024789, -0.007792267828444251, 0.26595390222807846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906096742957533, 0.11664237727394976, -0.0243021901028641]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920152799410063, 0.14438950370246345, 0.6263050232459871, 0.0, -0.04280571278238718, -0.08087688725592981, -3.0200162601910017, -0.15108566395818984, -0.11954146316905666, -1.3592873687775122, -3.1630579394084886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05439232928331262, 0.34567531255408446, 1.7352128966024263, -0.1523882287556445, -1.9908180868349037, -0.34239832711491036, 0.31615829809943224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9623710680396644, -0.38281743798443224, 0.006883760537404866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880438454, -0.08229073346573497, 0.0929594032041331, 0.0, -0.013520236680650208, -0.01850388969180274, -0.2945201828000522, -1.2056196451885986e-15, 0.288150524568422, -0.02127806344778866, -0.07643931743369124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06079729699219813, -0.0789713136925239, 0.6699131281810976, -1.984127331124936e-15, -0.7959122125618534, -0.014641808414372117, 0.11257207928333998, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19945730250958782, 0.07637481501182036, -0.020689104008375345]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1785515757431032, 0.14049180633214745, 0.6309805330169114, 0.0, -0.04108261173395056, -0.0818770162320404, -3.043537934474317, -0.1510856639578668, -0.09641780671766334, -1.3604621121243403, -3.165397535989083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.053658225782037536, 0.3415828861955776, 1.7740094217296576, -0.1523882287551262, -2.0288188547174086, -0.34327649876449906, 0.31161045425027684, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9723623061551029, -0.3815074393136128, 0.006002802492612629]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045019948276, -0.0779539474063201, 0.09351019541848467, 0.0, 0.03446202096873247, -0.020002579522211583, -0.4704334856663087, 6.46073483916983e-12, 0.4624731290278664, -0.023494866936561935, -0.046791931611883227, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014682070025501676, -0.08184852717013741, 0.775930502544628, 1.036613310613156e-11, -0.7600153576501024, -0.01756343299177417, -0.09095687698310861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19982476230876808, 0.026199973416388304, -0.017619160895844733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1779016233977662, 0.1373136043554086, 0.6356456482204245, 0.0, -0.03721676254498572, -0.08291730352673327, -3.074355273900223, -0.15108566395214434, -0.06605081515808248, -1.3617583954219048, -3.166435467390029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0549240149231531, 0.3374144189867764, 1.817046641831272, -0.15238822874598326, -2.064083672791269, -0.3442069198242152, 0.2988910361871185, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9823654777091959, -0.382288255145447, 0.005251187109685319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046906740402, -0.06356403953477706, 0.09330230407026224, 0.0, 0.07731698377929677, -0.020805745893857277, -0.6163467885181212, 1.1444887293409058e-10, 0.6073398311916174, -0.025925665951291362, -0.02075862801891857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025315782822311367, -0.08336934417602423, 0.8607444020322879, 1.8285895541423434e-10, -0.705296361477212, -0.018608421194322655, -0.25438836126316683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006343108186034, -0.015616316636683765, -0.015032307658546209]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1772516710495929, 0.13529048128252258, 0.6402713836342976, 0.0, -0.03149499701051951, -0.08395031620918555, -3.11100914544, -0.1510856639462402, -0.02987127014059504, -1.3631774725600079, -3.16633910806168, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.057858352002869484, 0.33320247265458536, 1.8634764179124828, -0.15238822873660748, -2.096487574646692, -0.3451427537055695, 0.28023137361792533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9923761497353961, -0.3848116208574997, 0.004605653662711748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046963465384, -0.04046246145772013, 0.09251470827746201, 0.0, 0.11443531068932403, -0.02066025364904566, -0.7330774307955384, 1.1808274346496299e-10, 0.7235909003497487, -0.028381542762063686, 0.001927186566978354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.058686741594327574, -0.0842389266438206, 0.9285955216242128, 1.8751557595464868e-10, -0.6480780371084631, -0.018716677627086887, -0.3731932513838633, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021344052400455, -0.05046731424105442, -0.012910668939471426]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1766017188055696, 0.13471901453230187, 0.645231549819708, 0.0, -0.02416965084878169, -0.08492661174638531, -3.152270363464285, -0.1510856639462402, 0.010908203198714495, -1.3647106046236785, -3.165242001480579, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06217135434159315, 0.32895968187741137, 1.9126202387774514, -0.15238822873660746, -2.12626565705343, -0.3460676703930643, 0.2573788185876828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0023912548109384, -0.38878735328224806, 0.004044283910718682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880466324, -0.011429335004414138, 0.09920332370820686, 0.0, 0.14650692323475642, -0.019525910743995213, -0.8252243604856998, -5.1800227045744044e-17, 0.8155894667861907, -0.03066264127341375, 0.02194213162201805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08626004677447328, -0.08485581554348026, 0.9828764172993703, 4.288595310145001e-16, -0.5955616481347529, -0.018498333749895728, -0.4570511006048501, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200302101510847, -0.07951464849496764, -0.011227395039861325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517665611328, 0.13574270242782435, 0.6502725913472744, 0.0, -0.01571113510471196, -0.08580388757662322, -3.194388927973078, -0.15108566394621728, 0.05253760485984613, -1.3663368532289746, -3.1628907517415876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06761102310516666, 0.3247122015295923, 1.9626202638327115, -0.15238822873657057, -2.153531210980476, -0.3469689344484492, 0.2315539474836294, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0124086287532215, -0.39396481303968484, 0.003547424423011781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044888736022, 0.020473757910449652, 0.10082083055132941, 0.0, 0.16917031488139464, -0.017545516604757973, -0.8423712901758613, 4.585464562307299e-13, 0.8325880332226328, -0.0325249721059218, 0.04702499477982379, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10879337527147032, -0.08494960695638139, 1.0000005011052027, 7.377710022999099e-13, -0.5453110785409144, -0.018025281107697775, -0.5164974220810683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20034747884565973, -0.1035491951487355, -0.00993718975413802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181430335368, 0.1383746540950873, 0.6551860938037658, 0.0, -0.006670975387808682, -0.0865813985623583, -3.2336148389663792, -0.15108566394543793, 0.09126693484279993, -1.3679888723883138, -3.158985354312172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07391614828210855, 0.3204913820097959, 2.0126202888879714, -0.1523882287353417, -2.1784636034234555, -0.34785074761133405, 0.20368800209272797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0224266368471195, -0.40010418388757907, 0.0030973259999944884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045155582176, 0.05263903334525896, 0.0982700491298277, 0.0, 0.18080319433806555, -0.015550219714701807, -0.7845182198660242, 1.55868540518478e-11, 0.774586599659076, -0.03304038318678298, 0.07810794858831407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1261025035388378, -0.08441639039592783, 1.000000501105197, 2.457773304398776e-11, -0.4986478488595889, -0.01763626325769817, -0.5573189078180284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036016187796218, -0.12278741695788474, -0.009001968460345853]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17465186205932903, 0.14251602070874636, 0.6598925422847217, 0.0, 0.0016030793331443458, -0.08729477854882496, -3.266198096444189, -0.15108566394543785, 0.12334619314757589, -1.3695512368190794, -3.154453088644374, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07982756443999056, 0.3163277536121052, 2.0626203139432313, -0.15238822873534155, -2.2042448429181474, -0.34895761940997483, 0.17709901113784765, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.032443057977591, -0.40658000956213863, 0.002693140832566091]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880492921, 0.08282733227318091, 0.09412896961911733, 0.0, 0.16548109441906056, -0.014267599729333242, -0.651665149556187, 1.7500498659875483e-15, 0.6415851660955192, -0.03124728861531467, 0.09064531335596208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11822832315764034, -0.08327256795381392, 1.0000005011051973, 2.8383014400603007e-15, -0.5156247898938344, -0.02213743597281518, -0.5317798190976062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032842260942893, -0.1295165134911911, -0.008083703348567946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019098149044, 0.14795532408776924, 0.6644006998709707, 0.0, 0.008095903915653874, -0.08799923597904404, -3.288388700406509, -0.15108566394541567, 0.14502537977418914, -1.3709455261515713, -3.1501995021533333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08431833677887605, 0.31225207180356557, 2.1126203389984903, -0.1523882287353194, -2.233520273561294, -0.3504622645705228, 0.15433358252726875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.042456506313181, -0.4127667813847632, 0.0023398861434476845]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044888492819, 0.10878606758045761, 0.09016315172498066, 0.0, 0.1298564916501906, -0.014089148604381528, -0.4438120792464024, 4.432760145763378e-13, 0.4335837325322651, -0.0278857866498374, 0.08507172982080496, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08981544677770986, -0.08151363617079282, 1.0000005011051796, 4.4313343872401245e-13, -0.5855086128629368, -0.03009290321095999, -0.4553085722115776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002689667118008, -0.12373543645249158, -0.007065093782368125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335195754928173, 0.15381470375484052, 0.6687619356737848, 0.0, 0.011801112131179157, -0.08876287277435958, -3.2964366508533414, -0.1510856639441679, 0.1525544947226688, -1.372414743598762, -3.1466749970209817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08641114859130924, 0.30877731245587253, 2.1626203640537502, -0.15238822873338168, -2.266608007001135, -0.35360112425363094, 0.1355596659586425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0524691736195775, -0.41803336723260776, 0.0025991644053059266]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045312453526, 0.1171875933414259, 0.08722471605628192, 0.0, 0.07410416431050565, -0.015272735906310873, -0.16095900893664555, 2.4955491240236406e-11, 0.15058229896959346, -0.02938434894381268, 0.07049010264702758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04185623624866385, -0.0694951869538606, 1.0000005011051951, 3.87543158782191e-11, -0.6617546687968169, -0.0627771936621623, -0.3754783313725254, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025334612792828, -0.10533171695689127, 0.0051855652371648395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1727020052837514, 0.15910990520794183, 0.6730436904063931, 0.0, 0.01209259324338477, -0.0896312812213857, -3.2918932762257014, -0.15108566394292017, 0.14778315393122798, -1.3742420597597076, -3.144056162404082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0854943869559228, 0.3064072814326638, 2.21262038910901, -0.15238822873145386, -2.3027641636516325, -0.35951741926289627, 0.12002811706564168, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0624831991850114, -0.4217429079490254, 0.004043300761445533]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045310606465, 0.10590402906202619, 0.08563509465216454, 0.0, 0.005829622244112265, -0.017368168940522337, 0.09086749255279558, 2.4954726898402533e-11, -0.0954268158288161, -0.036546323218912664, 0.052376692337988966, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01833523270772871, -0.04740062046417382, 1.0000005011051945, 3.855647347949171e-11, -0.7231231330099523, -0.11832590018530695, -0.31063097786001637, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028051130867994, -0.07419081432835296, 0.028882727122792128]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205303926846, 0.16312336010316328, 0.6773196311605819, 0.0, 0.008783371322250575, -0.09061576647714656, -3.2768571307026684, -0.15108566394289397, 0.13280317030149538, -1.376541255578462, -3.1424264675070432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0813678154984397, 0.30533278267816627, 2.2626204141642705, -0.1523882287314128, -2.3417751578713353, -0.3685733362431661, 0.10734078415195589, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0724928138095362, -0.4232563577129999, 0.006892786772233863]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044889659032, 0.08026909790442899, 0.08551881508377562, 0.0, -0.0661844384226839, -0.019689705115217185, 0.30072291046066424, 5.240079563609482e-13, -0.2995996725946518, -0.04598391637508785, 0.032593897940776495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08253142914966197, -0.021489975089950826, 1.0000005011052069, 8.207976542219979e-13, -0.7802198843940573, -0.18111833960539717, -0.2537466582737159, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001922924904937, -0.030268995279489373, 0.05698972021576661]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17140210079523688, 0.16536182465487986, 0.6816685111025065, 0.0, 0.0020567013753800927, -0.09169630736544777, -3.253077009433474, -0.1510856639428935, 0.1093171303644079, -1.3792675060886193, -3.1417628975388854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07417716494466262, 0.3055003045196396, 2.3126204392195304, -0.15238822873141206, -2.383588298044554, -0.3805404671278764, 0.09732319781768035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0824850270606277, -0.42258996612219607, 0.011011199443797946]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880631723, 0.04476929103433167, 0.08697759883849168, 0.0, -0.13453339893740962, -0.02161081776602424, 0.4756024253838869, 9.612942048149176e-15, -0.46972079874174955, -0.05452501020314621, 0.013271399363154142, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.14381301107554165, 0.003350436829466962, 1.0000005011051976, 1.5096879011949583e-14, -0.8362628034643698, -0.23934261769420637, -0.20035172668551063, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19984426502182973, 0.013327831816076247, 0.08236825343128162]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205301877607, 0.16597805396681378, 0.6861642962710915, 0.0, -0.006561983311071809, -0.09155121450957437, -3.2220529124181203, -0.1510856639417128, 0.07870047172017502, -1.380856228691764, -3.1413022629186855, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06767243529439816, 0.3056433195789616, 2.3588704642752227, -0.15613822873145153, -2.4290388101832234, -0.3982879836460423, 0.09372535806350568, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.092449911859682, -0.4203617084734724, 0.015847921693943487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044470784137, 0.01232458623867859, 0.089915703371702, 0.0, -0.172373693729038, 0.0029018571174679944, 0.6204819403070778, 2.3614081654452418e-11, -0.6123331728846577, -0.031774452062897446, 0.009212692404001237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.13009459300528914, 0.0028603011864401593, 0.9250005011138476, -0.07500000000078957, -0.9090102427733874, -0.354950330363317, -0.07195679509730563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1992976959810858, 0.0445651529744743, 0.09673444500291083]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1727020052627469, 0.16483509539357782, 0.6910185546790882, 0.0, -0.015990952294651556, -0.09041189029842443, -3.185233634805837, -0.15108566394170986, 0.04227578579109506, -1.3814752736639797, -3.140326395507318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06364309611568393, 0.305322022330296, 2.3976204893313477, -0.16738822873153122, -2.474376694287344, -0.42099077343716496, 0.10029726488805064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1023838633031842, -0.41719153632183137, 0.021207949239884102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879416596, -0.022859171464718893, 0.0970851681599346, 0.0, -0.18857937967159488, 0.02278648422299878, 0.7363855522456624, 5.865245912684931e-14, -0.7284937185815993, -0.012380899444311241, 0.019517348227347162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08058678357428453, -0.0064259449733132575, 0.7750005011224975, -0.22500000000159404, -0.906757682082405, -0.4540557958224535, 0.13143813649089936, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1986790288700425, 0.06340344303282006, 0.10720055091881234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335195775792278, 0.161950159038252, 0.6963155062539931, 0.0, -0.025491194441480652, -0.08873697501568004, -3.143803003667016, -0.15108566394242376, 0.001136042593015557, -1.3815751538398173, -3.1383886906313436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06242968942107733, 0.30412610489531816, 2.425120516279411, -0.18801322875407267, -2.5158519503678174, -0.4476022411171592, 0.11557367176515676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1122924593252814, -0.413701070222391, 0.026916337110555653]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999049903517846, -0.05769872710651673, 0.10593903149809614, 0.0, -0.1900048429365819, 0.03349830565488787, 0.8286126227764188, -1.4278057764907079e-11, -0.8227948639615901, -0.0019976035167508926, 0.038754097519486864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024268133892132088, -0.02391834869955691, 0.5500005389612634, -0.41250000045082885, -0.8295051216094694, -0.5322293535998845, 0.3055281375421222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19817192044194573, 0.06980932198880781, 0.11416775741343098]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019100036723, 0.15757954132765753, 0.7020264352714224, 0.0, -0.03436451796271941, -0.08686124373677767, -3.1015110167607336, -0.1510856639440033, -0.04096876069478934, -1.3815074613106897, -3.1356306586780898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06399777559145882, 0.3017863503198967, 2.438598205715731, -0.2164507287715678, -2.549714578447051, -0.47733155212195744, 0.13646331089789604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1221922513892382, -0.41051360896180855, 0.03278264048542176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044914990392, -0.08741235421188942, 0.11421858034858519, 0.0, -0.1774664704247751, 0.037514625578047286, 0.8458397381256497, -3.1590924565482646e-11, -0.8420960657560979, 0.00135385058255385, 0.055160639065074665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03136172340762981, -0.04679509150842894, 0.26955378872640356, -0.5687500003499022, -0.6772525615846705, -0.5945862200959646, 0.4177927826547855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979958412791336, 0.06374922521164865, 0.11732606749732216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17465186223889276, 0.15217779009200227, 0.7080645301015452, 0.0, -0.04190972713234761, -0.08499100456380453, -3.0621076432519163, -0.15108566405548138, -0.0802886573801937, -1.381444211849322, -3.132475788215136, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06832190880551685, 0.2983788269683103, 2.4401762912569205, -0.2512007287240646, -2.572214580367877, -0.5094102594425518, 0.15975870935092604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1321115499245507, -0.40825390906272213, 0.03862268339322451]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044704409362, -0.10803502471310493, 0.1207618966024565, 0.0, -0.15090418339256406, 0.03740478345946296, 0.7880674701763424, -2.22956136916465e-09, -0.7863979337080872, 0.0012649892273525654, 0.06309740925906894, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08648266428116053, -0.06815046703172797, 0.03156171082379433, -0.6949999990499367, -0.4500000384165206, -0.6415741464118883, 0.46590796906059984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1983859707062493, 0.04519399798172852, 0.11680085815605497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181448304938, 0.14634295930537133, 0.7143282920502034, 0.0, -0.04767542417300177, -0.08324706248963396, -3.029342883140532, -0.15108566405548787, -0.11307364746329827, -1.3814082355969337, -3.129141117566607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07560509253619208, 0.29427251145015076, 2.4313545435803565, -0.2910007286860957, -2.5797145822880476, -0.543008486057172, 0.18387218976289643, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1420894047205166, -0.4075478983837941, 0.04427090055689298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044883132263, -0.11669661573261857, 0.1252752389731627, 0.0, -0.11531394081308308, 0.03487884148341147, 0.6552952022276859, -1.297887904950337e-13, -0.6556998016620915, 0.0007195250477670915, 0.06669341297059006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1456636746135045, -0.0821263103631912, -0.17643495353127728, -0.7959999992406224, -0.1500000384034142, -0.6719645322924045, 0.4822696082394078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1995570959193191, 0.014120213578560345, 0.11296434327336935]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517667270293, 0.14087616500899, 0.7207192700049359, 0.0, -0.05130059984749168, -0.08168098803432443, -3.006966736280589, -0.15108566405617405, -0.13557373182378663, -1.3809871155732667, -3.1256297962518595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08629524612955392, 0.28974991959045465, 2.4134506214256293, -0.33484072865550796, -2.5747145839025842, -0.57676709254455, 0.20874871215779198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1518833814699454, -0.4087201747639428, 0.049477045622971234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879598493, -0.10933588592762669, 0.12781955909464854, 0.0, -0.07250351348979833, 0.031321489106190405, 0.4475229371988535, -1.3723230004060078e-11, -0.4500016872097671, 0.008422400473339534, 0.07022642629494587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21380307186723668, -0.09045183719392172, -0.35807844309454434, -0.8767999993882443, 0.09999996770926722, -0.6751721297475612, 0.4975304478979107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1958795349885746, -0.02344552760297345, 0.10412290132156508]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17660171897112145, 0.1371032577843417, 0.7271252862803065, 0.0, -0.05202247430501683, -0.0803487408300558, -2.998729202612335, -0.1510856640564177, -0.14403891068743035, -1.3809205315903337, -3.121898840886219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10145746395477852, 0.284965226253537, 2.3872806863021534, -0.38191272863063047, -2.5592979186230647, -0.6086425360107686, 0.23512557828638722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1608688115279318, -0.4114969829055082, 0.053616119994558245]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881843128, -0.07545814449296599, 0.12812032550741165, 0.0, -0.014437489150502879, 0.02664494408537261, 0.16475067336508165, -4.873332958880133e-12, -0.16930357727287448, 0.0013316796586589621, 0.07461910731280615, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.303244356504492, -0.09569386673835342, -0.5233987024695144, -0.9414399995024506, 0.3083333055903922, -0.6375088693243703, 0.5275373225719047, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17970860115972706, -0.05553616283130822, 0.08278148743174023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17725167121510715, 0.13592737364801435, 0.7333770629482129, 0.0, -0.049468003962240686, -0.07926698365761067, -3.0031145909034858, -0.1510856640570343, -0.1399238074040001, -1.3818584670012264, -3.117869833464093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12164618385704976, 0.28017313325093046, 2.354344738214693, -0.4315703286105022, -2.5361992750932227, -0.6372767155407535, 0.26385179988899937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1686842500957415, -0.4156522710266188, 0.056098934597024135]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879713921, -0.023517682726546987, 0.1250355333581288, 0.0, 0.05108940685552287, 0.021635143448902737, -0.08770776582301631, -1.2331939099049948e-11, 0.08230206566860537, -0.018758708217856336, 0.0805801484425198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4037743980454249, -0.09584186005213002, -0.6587189617492026, -0.993151999597435, 0.4619728705968341, -0.5726835905996981, 0.5745244320522428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15630877135619414, -0.08310576242221249, 0.04965629204931778]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17790162345912786, 0.13769689362482335, 0.7392633232944548, 0.0, -0.04371842423540572, -0.07841277358030474, -3.0180190811444625, -0.15108566405703752, -0.12532870746021035, -1.3841065954728933, -3.113547267588901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14675051944424197, 0.27593732192142706, 2.3159959797447707, -0.4815703536657623, -2.5080429251008076, -0.6617620986593467, 0.2954239602154801, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1754018473332655, -0.4209487288336699, 0.05684630806134782]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880414092, 0.03539039953617991, 0.1177252069248379, 0.0, 0.1149915945366993, 0.017084201546118623, -0.2980898048195306, -6.445816007531437e-14, 0.2919019988757949, -0.0449625694333392, 0.0864513175038396, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5020867117438443, -0.0847162265900678, -0.7669751693984501, -1.0000005011052018, 0.5631269998483031, -0.48970766237186375, 0.6314432065296146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13435194475047968, -0.10592915614102259, 0.014947469286473773]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17855157570323288, 0.1423494925849366, 0.7445973520771563, 0.0, -0.035109914849150214, -0.0777350048902328, -3.0416894896324176, -0.15108566405708915, -0.10196011125436293, -1.387718041016077, -3.108985778246317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1763296994073591, 0.2729225936182874, 2.2733169729693983, -0.5315703787211625, -2.4772889303575556, -0.681607983107226, 0.3302611997514402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1812739922654643, -0.42716524600644146, 0.05603868894754244]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904488210067, 0.09305197920226482, 0.10668057565402905, 0.0, 0.17217018772511017, 0.013555373801438909, -0.4734081697591004, -1.0324159940635262e-12, 0.46737192411694856, -0.07222891086367339, 0.09122978685168114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5915835992623424, -0.06029456606279274, -0.8535801355074448, -1.0000005011080058, 0.6150798948650421, -0.396917688957587, 0.6967447907192018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11744289864397377, -0.12433034345543047, -0.016152382276107678]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920152794721542, 0.14958969662156446, 0.7492739091409042, 0.0, -0.024055180118689012, -0.07716654240149338, -3.072625799413134, -0.151085664057092, -0.07128199803723775, -1.3926214387484985, -3.1042318552042554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2099806070937234, 0.2717567146424505, 2.2271737675490533, -0.5815704037765583, -2.4457527007007562, -0.6966307442407192, 0.3686513401802233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1865984702089254, -0.4341167818967145, 0.05394697708368154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879650567, 0.14480408073255746, 0.09353114127495879, 0.0, 0.22109469460922404, 0.011369249774788256, -0.6187261956143226, -5.725003471137484e-14, 0.6135622643425034, -0.09806795464843032, 0.09507846084122676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.6730181537272859, -0.02331757951673811, -0.922864108406897, -1.0000005011079167, 0.6307245931359834, -0.3004552226698653, 0.7678028085756611, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10648955886922284, -0.13903071780546067, -0.04183423727721784]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1798514801912255, 0.15902906566373926, 0.7532830800827253, 0.0, -0.010982790770819588, -0.07663287104534652, -3.1092312362341192, -0.15108566405710275, -0.034869412993651, -1.3987108332966032, -3.099270164945047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24722205061270702, 0.27298174906857214, 2.17825920321281, -0.6315704288321814, -2.414560436063433, -0.7068340582870763, 0.4103981923796951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1916516473830405, -0.4416525452904486, 0.05083977875677709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880201654, 0.18878738084349583, 0.0801834188364215, 0.0, 0.26144778695738846, 0.010673427122937238, -0.7321087364197056, -2.147618283924008e-13, 0.7282517008717351, -0.12178789096209228, 0.09923380518416146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.7448288703796723, 0.024500688522433103, -0.978291286724871, -1.0000005011124615, 0.6238452927464607, -0.20406628092714274, 0.8349370439894361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10106354348230442, -0.15071526787468248, -0.062143966538089096]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18050143243529132, 0.17027750381196718, 0.7566953026312148, 0.0, 0.003673181971210783, -0.07606326841160532, -3.149212726614908, -0.1510856640572582, 0.0050019223459289094, -1.4058864712950043, -3.0939796643121436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2874618301685328, 0.2769764097851253, 2.128259178157986, -0.6815704538877064, -2.3845785124451475, -0.7123880454785564, 0.45536910542929737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1966608891125206, -0.4496525542768724, 0.046942196070602446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881316648, 0.2249687629645586, 0.06824445096978903, 0.0, 0.2931194548406074, 0.011392052674824082, -0.7996298076157756, -3.109222367056565e-12, 0.7974267067915982, -0.14351275996802088, 0.10581001265806782, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8047955911165143, 0.0798932143310627, -1.0000005010964745, -1.0000005011105, 0.59963847236571, -0.11107974382960066, 0.899418260992045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10018483458959851, -0.16000017972847572, -0.07795165372349284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1811513846793199, 0.1829947553831078, 0.7596321401344559, 0.0, 0.0193960581976295, -0.07540808841377789, -3.188820270556529, -0.15108566405725962, 0.04458200798271322, -1.4140597521860399, -3.0879947017322937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3301418237284822, 0.28395807786954924, 2.07825915310273, -0.731570478943008, -2.3564988728709744, -0.7135729757885216, 0.5033458358685953, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.201800231774993, -0.45802312668937334, 0.04242334301339836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904488057193, 0.2543450314228124, 0.05873675006482335, 0.0, 0.31445752452837433, 0.013103599956548818, -0.7921508788324167, -2.8410509147961003e-14, 0.7916017127356862, -0.16346561782071173, 0.11969925159699979, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8535998711989885, 0.13963336168847892, -1.0000005011051212, -1.0000005011060302, 0.5615927914834594, -0.02369860619930428, 0.9595346087859589, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10278685324944778, -0.16741144825001897, -0.09037706114408176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1818013369233457, 0.1969167425552046, 0.7622344074955548, 0.0, 0.035766371029200675, -0.07466006815323989, -3.22430386805902, -0.15108566405725996, 0.08012084391673846, -1.423146828808112, -3.0809864019469644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.37479227488307315, 0.2939673995850642, 2.028259128047653, -0.7815705039982425, -2.330630970808783, -0.71078288328739, 0.55334583586862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2072025858081896, -0.46669201841220415, 0.03739458730645981]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880516392, 0.2784397434419362, 0.052045347221978885, 0.0, 0.32740625663142353, 0.014960405210759897, -0.7096719500498208, -6.521892815837001e-15, 0.7107767186805047, -0.18174153244144117, 0.1401659957065854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8930090230918182, 0.2001864343102987, -1.0000005011015374, -1.0000005011046906, 0.51735804124383, 0.05580185002263219, 1.0000000000004932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10804708066393481, -0.17337783445661573, -0.10057511413877109]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18245128916722209, 0.21183086953647284, 0.7646396646831926, 0.0, 0.0524763495314135, -0.07384824097046697, -3.2519135191262616, -0.15108566405727045, 0.10786843015187739, -1.4329999739671921, -3.0727403927227694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42036563384484343, 0.3060577211974452, 1.981091308902783, -0.8315705290533837, -2.309521591134529, -0.7053035051402812, 0.6033458358686082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2129372417230304, -0.47560523918677233, 0.03194623932790946]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044877527574, 0.2982825396253648, 0.04810514375275424, 0.0, 0.33419957004425654, 0.01623654365545846, -0.5521930213448287, -2.0986415905868122e-13, 0.5549517247027784, -0.19706290318160427, 0.1649201844838996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.9114671792354057, 0.24180643224761939, -0.9433563828974036, -1.0000005011028246, 0.42218759348507884, 0.10958756294217628, 0.9999999999997661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11469311829681787, -0.17826441549136418, -0.10896695957100706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18310124141125184, 0.22758443401029846, 0.7669658449566188, 0.0, 0.0694526525569448, -0.07300626366440441, -3.267899224622042, -0.15108566405728063, 0.12407476676796537, -1.4434851796994796, -3.063342494099787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46608008696175574, 0.31924305320879015, 1.9393510807323524, -0.8815705541086492, -2.2950692021910535, -0.6984067766938797, 0.653345835868597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2190548450883782, -0.48472192459455565, 0.026141215310764566]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880595235, 0.3150712894765124, 0.04652360546852429, 0.0, 0.33952606051062584, 0.016839546121251135, -0.3197141099156157, -2.035544000805935e-13, 0.3241267323217597, -0.2097041146457514, 0.18795797245965243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.9142890623382459, 0.2637066402268998, -0.8348045634086119, -1.0000005011053104, 0.2890477788695127, 0.13793456892802824, 0.999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12235206730695616, -0.18233370815566632, -0.11610048034289783]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18375119364440953, 0.24401333951134288, 0.7693052654245798, 0.0, 0.08617309644124832, -0.07229498616478056, -3.276010984457859, -0.15108566418202574, 0.13248985369620608, -1.454569156417389, -3.0538739121415275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510055367209955, 0.33140436099869, 1.9067884434470768, -0.9315705791529495, -2.290629034657913, -0.6926463774923567, 0.7033458358217826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2254721728141764, -0.4934249128701134, 0.020083289649944956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904466315395, 0.32857811002088855, 0.046788409359219414, 0.0, 0.3344088776860703, 0.014225549992476934, -0.16223519671633924, -2.4949023335305603e-09, 0.1683017385648144, -0.22167953435818924, 0.1893716391651844, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8795056049639868, 0.24322615579799664, -0.651252745705514, -1.0000005008860064, 0.08880335066280498, 0.11520798403046185, 0.9999999990637111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1283465545159625, -0.17405976551115585, -0.1211585132163922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18402162815265266, 0.2602693828641821, 0.7717298633609453, 0.0, 0.10115450876979075, -0.07203522220195482, -3.279998798606076, -0.15108566459251002, 0.13686364605532478, -1.4651628916581865, -3.0453359109430003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5485496770021581, 0.3422195339595048, 1.882933189685166, -0.977820604186797, -2.2929087696225645, -0.6871353850333461, 0.7495958357293222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2315636007595263, -0.5010997474676454, 0.014397462345241169]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005408690164862766, 0.3251208670567842, 0.04849195872731077, 0.0, 0.29962824657084863, 0.0051952792565145775, -0.07975628296433276, -8.209685482198641e-09, 0.08747584718237404, -0.21187470481595078, 0.17076002397054307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.7698861958440597, 0.21630345921629596, -0.47710507523821716, -0.9250005006769478, -0.045594699293030144, 0.11021984918021112, 0.9249999981507918, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12182855890699898, -0.15349669195064058, -0.11371654609407572]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1839660606307883, 0.2756258749361232, 0.7741909908396435, 0.0, 0.1135571857514478, -0.07233743302177859, -3.2819936739435875, -0.1514275973541771, 0.1391869211947469, -1.4741217506511974, -3.0382482848786023, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5795517802231369, 0.3516989381885014, 1.8659885815775683, -1.0165706292127579, -2.2982230069284384, -0.6813759421199589, 0.7883458360126491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2367183624031646, -0.5073037980153204, 0.009699486358135126]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011113504372871359, 0.307129841438822, 0.049222549573963506, 0.0, 0.2480535396331409, -0.0060442163964752015, -0.03989750675023332, -0.0068386552333414485, 0.046465502788442255, -0.17917717986021847, 0.14175252128795865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.6200420644195777, 0.1895880845799324, -0.33889216215195384, -0.7750005005192183, -0.10628474611748055, 0.11518885826774523, 0.7750000056665367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10309523287276692, -0.12408101095350153, -0.09395951974212087]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18383843214265974, 0.2895451019372624, 0.7765353888760588, 0.0, 0.1232384155537244, -0.07304605805138052, -3.2830066241068687, -0.15214830224717277, 0.1404721237640992, -1.4809836883612761, -3.0326736951669555, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6029328184120373, 0.3598480719742292, 1.8541160753355093, -1.044329174557169, -2.3040199154760015, -0.6754264003294851, 0.8182018784289025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2407288886913488, -0.5120676292499943, 0.006144015859052955]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0025525697625713587, 0.278384540022784, 0.046887960728305145, 0.0, 0.19362459604553203, -0.014172500592038707, -0.0202590032656203, -0.014414097859913556, 0.025704051387046133, -0.13723875420157283, 0.11149179423293398, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4676207637780063, 0.16298267571455632, -0.23745012484118194, -0.5551709068882206, -0.11593817095126543, 0.11899083580947649, 0.5971208483250672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08021052576368295, -0.09527662469347689, -0.07110940998164345]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18371275250461674, 0.30166417253169414, 0.778707428450579, 0.0, 0.13046412692613102, -0.07396215042611672, -3.2835290108569946, -0.15314328313358036, 0.141224485733525, -1.485810649274088, -3.028448463225928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6196728042889283, 0.3666645189753038, 1.845777536782371, -1.0621855742121162, -2.3089676238541714, -0.6696029359195457, 0.8398843838531204, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2436664025974984, -0.5156064125956614, 0.003634735583843041]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002513592760859904, 0.24238141188863518, 0.04344079149040617, 0.0, 0.14451422744813247, -0.018321847494723917, -0.010447735002521106, -0.019899617728151787, 0.01504723938851575, -0.09653921825623427, 0.08450463882055195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33479971753782145, 0.13632894002149207, -0.16677077106276694, -0.3571279930989445, -0.09895416756339574, 0.11646928819878878, 0.4336501084843575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.058750278122992355, -0.07077566691334293, -0.050185605504198275]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18360795704237837, 0.3117955034757106, 0.7805590516178845, 0.0, 0.13566924655406928, -0.07492436931637118, -3.283804705930197, -0.1542731884251925, 0.1416933224669047, -1.4889356157184528, -3.0253303662877746, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6311536643163875, 0.37219186194219256, 1.8398293678117, -1.072576236145607, -2.312586388148183, -0.6642308706198838, 0.8549224942300372, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2457141404754046, -0.5181772718134344, 0.0019715227747025676]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002095909244767307, 0.2026266188803291, 0.037032463346109816, 0.0, 0.10410239255876516, -0.019244377805089453, -0.005513901464048984, -0.02259810583224268, 0.009376734667593868, -0.06249932888729732, 0.062361938763060544, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22961720054918275, 0.11054685933777585, -0.11896337941342239, -0.2078132386698147, -0.07237528588023441, 0.10744130599323604, 0.30076220753833555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040954757558126095, -0.05141718435546044, -0.033264256182809454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1835275900637907, 0.3199216904239934, 0.7820595888521741, 0.0, 0.1393116010646722, -0.07582729400770906, -3.283956305748153, -0.15541643137687242, 0.14200205638908517, -1.4907741427124896, -3.023075379756437, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6387375861914906, 0.37653751652333434, 1.8354854291778415, -1.0779206722204324, -2.3148821938996207, -0.6595308292893728, 0.8649520402851358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.247079227374476, -0.5200165860545145, 0.0009367785374041974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001607339571752801, 0.16252373896565536, 0.030010744685790295, 0.0, 0.07284709021205835, -0.018058493826757456, -0.003031996359117991, -0.022864859033598316, 0.006174678443609671, -0.0367705398807391, 0.04509973062675102, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15167843750206145, 0.08691309162283524, -0.08687877267716698, -0.1068887214965054, -0.04591611502875118, 0.09400082661022059, 0.200590921101974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027301737981424795, -0.036786284821601324, -0.020694884745967403]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1834695269057793, 0.3261709192390962, 0.7830887140845092, 0.0, 0.1417993681514609, -0.07661460819669193, -3.2840455076083397, -0.15648683692091078, 0.14221345575610359, -1.4917173782945368, -3.0214702922319665, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.643577612829679, 0.3798577488667566, 1.8322327949121966, -1.0801491810445512, -2.316085858530731, -0.6555991282023448, 0.8714044367514686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2479503631261804, -0.5213187383230194, 0.0003379965770590836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011612631602278675, 0.12498457630205637, 0.02058250464670325, 0.0, 0.049755341735774394, -0.015746283779657304, -0.0017840372037389955, -0.021408110880767228, 0.004227987340368557, -0.01886471164094053, 0.03210175048940624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09680053276376781, 0.06640464686844516, -0.06505268531289751, -0.044570176482374144, -0.024073292622204465, 0.0786340217405597, 0.12904792932665443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017422715034088317, -0.026043045370098716, -0.011975639206902278]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18342967008403432, 0.3307749417841999, 0.7836680385440494, 0.0, 0.143464478565032, -0.07726559258404059, -3.284103002854, -0.1574338414462765, 0.1423613541076298, -1.4920849997217835, -3.0203421693754815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6465667230857132, 0.38233086629476615, 1.8297461990354478, -1.0806299380368327, -2.3164944115261896, -0.6524318442295359, 0.875410568911046, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2484814446036618, -0.5222341640065341, 2.3226286910602966e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0007971364348996466, 0.09208045090207409, 0.011586489190803706, 0.0, 0.03330220827142194, -0.013019687746973162, -0.001149904913208196, -0.01894009050731424, 0.002957967030523964, -0.007352428544935554, 0.02256245712970329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.059782205120684224, 0.04946234856019059, -0.0497319175349762, -0.009615139845631678, -0.008171059909167767, 0.06334567945617779, 0.08012264319154756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010621629549628074, -0.01830851367029275, -0.006295405802969612]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1834036529740797, 0.334020963038557, 0.7839287782569468, 0.0, 0.1445608347215669, -0.07778203451555002, -3.2841437210751527, -0.15823561922046073, 0.1424656081204051, -1.4921146107533023, -3.0195570764009627, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6483549329266043, 0.38413301891198803, 1.827819714252681, -1.080251114683641, -2.31638709896749, -0.649960431899801, 0.8778072461642858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.248789033240762, -0.5228750177384924, -0.00011821021719431629]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0005203421990924129, 0.06492042508714126, 0.005214794257947626, 0.0, 0.021927123130697723, -0.010328838630188686, -0.0008143644230532267, -0.016035555483684356, 0.002085080255506097, -0.0005922206303753058, 0.015701859490374875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.035764196817821836, 0.036043052344438005, -0.03852969565533501, 0.007576467063832144, 0.002146251173997509, 0.049428246594698334, 0.047933545064798855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0061517727420049816, -0.012817074639166965, -0.002828730082098385]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18338757973737052, 0.3362077350864409, 0.783996589935374, 0.0, 0.14527398297417238, -0.07817806417005463, -3.2841747320480144, -0.1588906287355294, 0.142538979033575, -1.4919695597240903, -3.0190146192566187, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6493926834672351, 0.3854222235984978, 1.8263191269562384, -1.0795433901192968, -2.315989273982879, -0.6480837745618142, 0.879183980517305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.248956447401717, -0.5233228524512259, -0.00016173726153491207]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003214647341836887, 0.04373544095767847, 0.001356233568543082, 0.0, 0.014262965052109562, -0.007920593090092156, -0.0006202194572320772, -0.013100190301373122, 0.0014674182633978925, 0.002901020584240151, 0.010849142886876821, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020755010812615503, 0.025784093730195752, -0.030011745928851086, 0.01415449128688585, 0.007956499692219251, 0.03753314675973629, 0.027534687060381233, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003348283219099396, -0.008956694254668555, -0.0008705408868119155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833782895592516, 0.3376123823199131, 0.7839534119960576, 0.0, 0.1457346006108684, -0.07847310357867418, -3.2841993335108457, -0.15940994113696103, 0.14259027395186555, -1.4917539593648532, -3.0186414388226552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6499788946862083, 0.3863307194669248, 1.8251518663611956, -1.0787943652683476, -2.3154640632570134, -0.6466916488423651, 0.8799390677265504, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490403005675041, -0.5236359232832056, -0.0001556170402208232]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00018580356237870348, 0.02809294466944282, -0.0008635587863289867, 0.0, 0.009212352733920792, -0.0059007881723911115, -0.0004920292566229249, -0.010386248028632828, 0.0010258983658110467, 0.004312007184741031, 0.00746360867926863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01172422437946425, 0.018169917368539894, -0.02334521190085568, 0.014980497018981716, 0.010504214517312966, 0.027842514388983455, 0.015101744184909584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016770633157432893, -0.006261416639594555, 0.00012240442628177702]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833733874113519, 0.3384703147674239, 0.7838553234792257, 0.0, 0.1460318681804236, -0.0786874455201064, -3.284219117704473, -0.15981122054937766, 0.14262582340148963, -1.4915286111041632, -3.018385057003743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6503039246654709, 0.3869635108615828, 1.8242495341121394, -1.0781386816338103, -2.314918252792128, -0.6456794614066003, 0.8803312371019563, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490772394179737, -0.5238552959244377, -0.00012870995865658087]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.804295799399034e-05, 0.017158648950216713, -0.001961770336637787, 0.0, 0.005945351391104147, -0.004286838828644372, -0.00039568387255076924, -0.008025588248332624, 0.0007109889924814144, 0.004506965213799725, 0.005127636378245034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006500599585253516, 0.012655827893160198, -0.018046644981122892, 0.013113672690743974, 0.010916209297704867, 0.020243748715297247, 0.00784338750811712, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007387770093907497, -0.004387452824642356, 0.0005381416312848467]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833711610957024, 0.3389671531937855, 0.7837391159720067, 0.0, 0.1462249820954502, -0.07883976670638937, -3.2842349681914467, -0.1601144451605627, 0.1426502429520146, -1.491324900325474, -3.0182086093760616, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6504840334498744, 0.3874006196860896, 1.823558482743354, -1.07762221190819, -2.314413932083169, -0.644955979551123, 0.8805219546054766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490898201849965, -0.5240096320436542, -9.688935398549742e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.452631299021533e-05, 0.009936768527232149, -0.0023241501443800735, 0.0, 0.003862278300532218, -0.0030464237256594365, -0.0003170097394683431, -0.006064492223700689, 0.0004883910104990615, 0.004074215573785519, 0.0035289525536256364, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0036021756880694317, 0.008742176490135431, -0.013821027375709909, 0.010329394512407762, 0.010086414179181746, 0.014469637109544724, 0.003814350070406129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002516153404558213, -0.0030867223843307557, 0.0006364120934216687]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833704558340642, 0.33923964962580055, 0.7836271609957393, 0.0, 0.14635231577309238, -0.07894622022229704, -3.284247503543484, -0.16033933991921395, 0.14266688879345205, -1.4911553234162143, -3.0180866432926536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6505871561088624, 0.3877010626879867, 1.8230350548685343, -1.0772444475641927, -2.313981080676113, -0.644446200846774, 0.8806077169351076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490911748440372, -0.5241187943418757, -6.787095843431326e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4105232763898814e-05, 0.005449928640301458, -0.0022390995253505517, 0.0, 0.0025466735528434873, -0.002129070318153288, -0.0002507070407423788, -0.004497895173025094, 0.00033291682874891086, 0.0033915381851977546, 0.002439321668162359, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020624531797600702, 0.00600886003794276, -0.010468557496391633, 0.007555286879945618, 0.008657028141118767, 0.010195574086981393, 0.0017152465926219317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7093180815913254e-05, -0.002183245964429059, 0.000580367911023683]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18337053162700073, 0.33938210006866304, 0.7835302587172076, 0.0, 0.14643821416366967, -0.07901991799308448, -3.284257250147277, -0.1605037981030579, 0.1426781727592407, -1.4910215445663788, -3.018001800509428, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6506510491866041, 0.387907221814751, 1.8226432168733302, -1.0769843791899039, -2.313628617116843, -0.644091141792743, 0.8806433328626165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.249088427523313, -0.5241964858753997, -4.4597254673075766e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000" }, - "execution_count": 8, + "execution_count": 22, "metadata": {}, "output_type": "execute_result" } @@ -557,7 +721,10 @@ " name='MaxMal2')\n", "gs.add_default_end_motion_conditions()\n", "gs.motion_goals.allow_all_collisions()\n", - "gs.execute()" + "gs.execute()\n", + "\n", + "# EXERCISE:\n", + "# 1.Comment the BaseArmWeightScaling and MaxManipulabilityLinWeight Goals to observe the resulting motions when the cost function is not augmented." ], "metadata": { "collapsed": false, From 4199592166462d40d2213695e76fb1c64b63b13b Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 8 Aug 2024 15:29:25 +0200 Subject: [PATCH 16/43] edited feature function goals --- src/giskardpy/casadi_wrapper.py | 12 ++ src/giskardpy/casadi_wrapper.pyi | 4 + src/giskardpy/goals/feature_functions.py | 211 +++++++++-------------- test/test_integration_pr2.py | 45 ++--- 4 files changed, 107 insertions(+), 165 deletions(-) diff --git a/src/giskardpy/casadi_wrapper.py b/src/giskardpy/casadi_wrapper.py index 3490c520b1..8e5f99734a 100644 --- a/src/giskardpy/casadi_wrapper.py +++ b/src/giskardpy/casadi_wrapper.py @@ -2247,3 +2247,15 @@ def is_constant(expr): def det(expr): return Expression(ca.det(expr.s)) + + +def distance_projected_on_vector(point1, point2, vector): + dist = point1 - point2 + projection = dot(dist, vector) + return projection + + +def distance_vector_projected_on_plane(point1, point2, normal_vector): + dist = point1 - point2 + projection = dist - dot(dist, normal_vector) * normal_vector + return projection diff --git a/src/giskardpy/casadi_wrapper.pyi b/src/giskardpy/casadi_wrapper.pyi index 7ddc207531..b29e9f5125 100644 --- a/src/giskardpy/casadi_wrapper.pyi +++ b/src/giskardpy/casadi_wrapper.pyi @@ -910,3 +910,7 @@ def is_false(expr: Expression) -> bool: ... def is_constant(expr: Expression) -> bool: ... def det(expr: Expression) -> Expression: ... + +def distance_projected_on_vector(point1: Point3, point2: Point3, vector: Vector3) -> Expression: ... + +def distance_vector_projected_on_plane(point1: Point3, point2:Point3, normal_vector: Vector3) -> Vector3: ... \ No newline at end of file diff --git a/src/giskardpy/goals/feature_functions.py b/src/giskardpy/goals/feature_functions.py index 978d063f6b..fae7610690 100644 --- a/src/giskardpy/goals/feature_functions.py +++ b/src/giskardpy/goals/feature_functions.py @@ -17,91 +17,96 @@ class FeatureFunctionGoal(Goal): def __init__(self, tip_link: str, root_link: str, - world_feature: Union[PointStamped, Vector3Stamped], - robot_feature: Union[PointStamped, Vector3Stamped], - name: Optional[str] = None + controlled_feature: Union[PointStamped, Vector3Stamped], + reference_feature: Union[PointStamped, Vector3Stamped], + name: Optional[str] = None, root_group: Optional[str] = None, + tip_group: Optional[str] = None, ): - self.root = god_map.world.search_for_link_name(root_link, None) - self.tip = god_map.world.search_for_link_name(tip_link, None) + self.root = god_map.world.search_for_link_name(root_link, root_group) + self.tip = god_map.world.search_for_link_name(tip_link, tip_group) if name is None: - name = f'{self.__class__.__name__}/{self.root}/{self.tip}' - super().__init__(name) - world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) - root_world_feature = god_map.world.transform_msg(self.root, world_feature) - robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) - tip_robot_feature = god_map.world.transform_msg(self.tip, robot_feature) + self.name = f'{self.__class__.__name__}/{self.root}/{self.tip}' + else: + self.name = name + super().__init__(self.name) + reference_feature.header.frame_id = god_map.world.search_for_link_name(reference_feature.header.frame_id, + None) + root_reference_feature = god_map.world.transform_msg(self.root, reference_feature) + controlled_feature.header.frame_id = god_map.world.search_for_link_name(controlled_feature.header.frame_id, + None) + tip_controlled_feature = god_map.world.transform_msg(self.tip, controlled_feature) root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) - if type(robot_feature) == PointStamped: - self.root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) - god_map.debug_expression_manager.add_debug_expression('root_P_robot_feature', - self.root_P_robot_feature, + if isinstance(controlled_feature, PointStamped): + self.root_P_controlled_feature = root_T_tip.dot(cas.Point3(tip_controlled_feature)) + god_map.debug_expression_manager.add_debug_expression('root_P_controlled_feature', + self.root_P_controlled_feature, color=ColorRGBA(r=1, g=0, b=0, a=1)) - elif type(robot_feature) == Vector3Stamped: - self.root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) - god_map.debug_expression_manager.add_debug_expression('root_V_robot_feature', - self.root_V_robot_feature, + elif isinstance(controlled_feature, Vector3Stamped): + self.root_V_controlled_feature = root_T_tip.dot(cas.Vector3(tip_controlled_feature)) + god_map.debug_expression_manager.add_debug_expression('root_V_controlled_feature', + self.root_V_controlled_feature, color=ColorRGBA(r=1, g=0, b=0, a=1)) - if type(world_feature) == PointStamped: - self.root_P_world_feature = cas.Point3(root_world_feature) - god_map.debug_expression_manager.add_debug_expression('root_P_world_feature', - self.root_P_world_feature, + if isinstance(reference_feature, PointStamped): + self.root_P_reference_feature = cas.Point3(root_reference_feature) + god_map.debug_expression_manager.add_debug_expression('root_P_reference_feature', + self.root_P_reference_feature, color=ColorRGBA(r=0, g=1, b=0, a=1)) - if type(world_feature) == Vector3Stamped: - self.root_V_world_feature = cas.Vector3(root_world_feature) - god_map.debug_expression_manager.add_debug_expression('root_V_world_feature', - self.root_V_world_feature, + if isinstance(reference_feature, Vector3Stamped): + self.root_V_reference_feature = cas.Vector3(root_reference_feature) + god_map.debug_expression_manager.add_debug_expression('root_V_reference_feature', + self.root_V_reference_feature, color=ColorRGBA(r=0, g=1, b=0, a=1)) -class PerpendicularFeatureFunction(FeatureFunctionGoal): +class AlignPerpendicular(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, - world_feature: Vector3Stamped, - robot_feature: Vector3Stamped, + tip_normal: Vector3Stamped, + reference_normal: Vector3Stamped, name: str = None, weight: int = WEIGHT_BELOW_CA, max_vel: float = 0.2, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, start_condition: cas.Expression = cas.TrueSymbol, hold_condition: cas.Expression = cas.FalseSymbol, - end_condition: cas.Expression = cas.TrueSymbol + end_condition: cas.Expression = cas.FalseSymbol ): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name) + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_normal, + controlled_feature=tip_normal, name=name, root_group=root_group, tip_group=tip_group) - expr = cas.dot(self.root_V_world_feature[:3], self.root_V_robot_feature[:3]) + expr = cas.dot(self.root_V_reference_feature[:3], self.root_V_controlled_feature[:3]) task = self.create_and_add_task() task.add_equality_constraint(reference_velocity=max_vel, equality_bound=0 - expr, weight=weight, task_expression=expr, - name=f'{name}_constraint') + name=f'{self.name}_constraint') self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) -class HeightFeatureFunction(FeatureFunctionGoal): +class HeightGoal(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, - world_feature: PointStamped, - robot_feature: PointStamped, + tip_point: PointStamped, + reference_point: PointStamped, lower_limit: float, upper_limit: float, name: str = None, weight: int = WEIGHT_BELOW_CA, max_vel: float = 0.2, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, start_condition: cas.Expression = cas.TrueSymbol, hold_condition: cas.Expression = cas.FalseSymbol, - end_condition: cas.Expression = cas.TrueSymbol + end_condition: cas.Expression = cas.FalseSymbol ): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name) + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, + controlled_feature=tip_point, name=name, root_group=root_group, tip_group=tip_group) - distance = self.root_P_robot_feature - self.root_P_world_feature - - height_vector = cas.Vector3([0, 0, 1]) - - projection = cas.dot(distance, height_vector) - expr = projection + expr = cas.distance_projected_on_vector(self.root_P_controlled_feature, self.root_P_reference_feature, + cas.Vector3([0, 0, 1])) task = self.create_and_add_task() task.add_inequality_constraint(reference_velocity=max_vel, @@ -109,36 +114,32 @@ def __init__(self, tip_link: str, root_link: str, lower_error=lower_limit - expr, weight=weight, task_expression=expr, - name=f'{name}_constraint') + name=f'{self.name}_constraint') self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) -class DistanceFeatureFunction(FeatureFunctionGoal): +class DistanceGoal(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, - world_feature: PointStamped, - robot_feature: PointStamped, + tip_point: PointStamped, + reference_point: PointStamped, lower_limit: float, upper_limit: float, name: str = None, weight: int = WEIGHT_BELOW_CA, max_vel: float = 0.2, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, start_condition: cas.Expression = cas.TrueSymbol, hold_condition: cas.Expression = cas.FalseSymbol, - end_condition: cas.Expression = cas.TrueSymbol + end_condition: cas.Expression = cas.FalseSymbol ): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name) - - # distance between the two feature points - distance = self.root_P_robot_feature - self.root_P_world_feature + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, + controlled_feature=tip_point, name=name, root_group=root_group, tip_group=tip_group) - # normal vector defining the x-y plane - height_vector = cas.Vector3([0, 0, 1]) - - # project the distance vector onto the x-y plane and calculate its length - projection = cas.norm(distance - cas.dot(distance, height_vector) * height_vector) - expr = projection - projected_vector = distance - cas.dot(distance, height_vector) * height_vector + projected_vector = cas.distance_vector_projected_on_plane(self.root_P_controlled_feature, + self.root_P_reference_feature, + cas.Vector3([0, 0, 1])) + expr = cas.norm(projected_vector) task = self.create_and_add_task() task.add_inequality_constraint(reference_velocity=max_vel, @@ -146,92 +147,36 @@ def __init__(self, tip_link: str, root_link: str, lower_error=lower_limit - expr, weight=weight, task_expression=expr, - name=f'{name}_constraint') + name=f'{self.name}_constraint') + # An extra constraint that makes the execution more stable task.add_inequality_constraint_vector(reference_velocities=[max_vel] * 3, lower_errors=[0, 0, 0], upper_errors=[0, 0, 0], weights=[weight] * 3, task_expression=projected_vector[:3], - names=['dsf', 'sdf', 'fdg']) - # god_map.debug_expression_manager.add_debug_expression('distance-expr', expr) + names=[f'{self.name}_extra1', f'{self.name}_extra2', f'{self.name}_extra3']) self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) -class PointingFeatureFunction(Goal): - def __init__(self, tip_link: str, root_link: str, - world_feature: PointStamped, - robot_feature: Vector3Stamped, - name: str = None, - weight: int = WEIGHT_BELOW_CA, - max_vel: float = 0.2, - start_condition: cas.Expression = cas.TrueSymbol, - hold_condition: cas.Expression = cas.FalseSymbol, - end_condition: cas.Expression = cas.TrueSymbol - ): - self.root_link = god_map.world.search_for_link_name(root_link, None) - self.tip_link = god_map.world.search_for_link_name(tip_link, None) - if name is None: - name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' - super().__init__(name) - - self.add_constraints_of_goal(Pointing(tip_link=tip_link, - goal_point=world_feature, - root_link=root_link, - pointing_axis=robot_feature, - max_velocity=max_vel, - weight=weight, - name=name, - start_condition=start_condition, - hold_condition=hold_condition, - end_condition=end_condition)) - - -class AlignFeatureFunction(Goal): - def __init__(self, tip_link: str, root_link: str, - world_feature: Vector3Stamped, - robot_feature: Vector3Stamped, - name: str = None, - weight: int = WEIGHT_BELOW_CA, - max_vel: float = 0.2, - start_condition: cas.Expression = cas.TrueSymbol, - hold_condition: cas.Expression = cas.FalseSymbol, - end_condition: cas.Expression = cas.TrueSymbol - ): - self.root_link = god_map.world.search_for_link_name(root_link, None) - self.tip_link = god_map.world.search_for_link_name(tip_link, None) - if name is None: - name = f'{self.__class__.__name__}/{self.root_link}/{self.tip_link}' - super().__init__(name) - - self.add_constraints_of_goal(AlignPlanes(root_link=root_link, - tip_link=tip_link, - goal_normal=world_feature, - tip_normal=robot_feature, - reference_velocity=max_vel, - weight=weight, - name=name, - start_condition=start_condition, - hold_condition=hold_condition, - end_condition=end_condition)) - - -class AngleFeatureFunction(FeatureFunctionGoal): +class AngleGoal(FeatureFunctionGoal): def __init__(self, tip_link: str, root_link: str, - world_feature: Vector3Stamped, - robot_feature: Vector3Stamped, + tip_vector: Vector3Stamped, + reference_vector: Vector3Stamped, lower_angle: float, upper_angle: float, name: str = None, weight: int = WEIGHT_BELOW_CA, max_vel: float = 0.2, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, start_condition: cas.Expression = cas.TrueSymbol, hold_condition: cas.Expression = cas.FalseSymbol, - end_condition: cas.Expression = cas.TrueSymbol + end_condition: cas.Expression = cas.FalseSymbol ): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name) + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_vector, + controlled_feature=tip_vector, name=name, root_group=root_group, tip_group=tip_group) - expr = cas.angle_between_vector(self.root_V_world_feature, self.root_V_robot_feature) + expr = cas.angle_between_vector(self.root_V_reference_feature, self.root_V_controlled_feature) task = self.create_and_add_task() task.add_inequality_constraint(reference_velocity=max_vel, @@ -239,5 +184,5 @@ def __init__(self, tip_link: str, root_link: str, lower_error=lower_angle - expr, weight=weight, task_expression=expr, - name=f'{name}_constraint') + name=f'{self.name}_constraint') self.connect_monitors_to_all_tasks(start_condition, hold_condition, end_condition) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index b71590fad6..8050dbf846 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -43,9 +43,7 @@ from utils_for_tests import compare_poses, publish_marker_vector, \ GiskardTestWrapper, pr2_urdf from giskardpy.goals.weight_scaling_goals import MaxManipulabilityLinWeight, BaseArmWeightScaling -from giskardpy.goals.feature_functions import DistanceFeatureFunction, PointingFeatureFunction, \ - PerpendicularFeatureFunction, HeightFeatureFunction, AlignFeatureFunction -from giskardpy.monitors.feature_monitors import HeightFeatureMonitor + # scopes = ['module', 'class', 'function'] pocky_pose = {'r_elbow_flex_joint': -1.29610152504, @@ -4659,11 +4657,11 @@ def test_feature_perpendicular(self, zero_pose: PR2TestWrapper): robot_feature.header.frame_id = zero_pose.r_tip robot_feature.vector.x = 1 - zero_pose.motion_goals.add_motion_goal(motion_goal_class='PerpendicularFeatureFunction', + zero_pose.motion_goals.add_motion_goal(motion_goal_class='AlignPerpendicular', root_link='map', tip_link=zero_pose.r_tip, - world_feature=world_feature, - robot_feature=robot_feature) + reference_normal=world_feature, + tip_normal=robot_feature) zero_pose.add_default_end_motion_conditions() zero_pose.execute() @@ -4677,11 +4675,11 @@ def test_feature_angle(self, zero_pose: PR2TestWrapper): robot_feature.header.frame_id = zero_pose.r_tip robot_feature.vector.z = 1 - zero_pose.motion_goals.add_motion_goal(motion_goal_class='AngleFeatureFunction', + zero_pose.motion_goals.add_motion_goal(motion_goal_class='AngleGoal', root_link='map', tip_link=zero_pose.r_tip, - world_feature=world_feature, - robot_feature=robot_feature, + reference_vector=world_feature, + tip_vector=robot_feature, lower_angle=0.6, upper_angle=0.9) @@ -4695,11 +4693,11 @@ def test_feature_height(self, zero_pose: PR2TestWrapper): robot_feature = PointStamped() robot_feature.header.frame_id = zero_pose.r_tip - zero_pose.motion_goals.add_motion_goal(motion_goal_class='HeightFeatureFunction', + zero_pose.motion_goals.add_motion_goal(motion_goal_class='HeightGoal', root_link='map', tip_link=zero_pose.r_tip, - world_feature=world_feature, - robot_feature=robot_feature, + reference_point=world_feature, + tip_point=robot_feature, lower_limit=1, upper_limit=2) @@ -4713,11 +4711,11 @@ def test_feature_distance(self, zero_pose: PR2TestWrapper): robot_feature = PointStamped() robot_feature.header.frame_id = zero_pose.r_tip - zero_pose.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction', + zero_pose.motion_goals.add_motion_goal(motion_goal_class='DistanceGoal', root_link='map', tip_link=zero_pose.r_tip, - world_feature=world_feature, - robot_feature=robot_feature, + reference_point=world_feature, + tip_point=robot_feature, lower_limit=2, upper_limit=2, max_vel=0.3 @@ -4726,23 +4724,6 @@ def test_feature_distance(self, zero_pose: PR2TestWrapper): zero_pose.add_default_end_motion_conditions() zero_pose.execute() - def test_feature_pointing(self, zero_pose: PR2TestWrapper): - world_feature = PointStamped() - world_feature.header.frame_id = 'map' - - robot_feature = Vector3Stamped() - robot_feature.header.frame_id = zero_pose.r_tip - robot_feature.vector.x = 1 - - zero_pose.motion_goals.add_motion_goal(motion_goal_class='PointingFeatureFunction', - root_link='map', - tip_link=zero_pose.r_tip, - world_feature=world_feature, - robot_feature=robot_feature, - ) - - zero_pose.add_default_end_motion_conditions() - zero_pose.execute() # kernprof -lv py.test -s test/test_integration_pr2.py From f39193748577766f7ed6655053900f77a87dd86c Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 8 Aug 2024 15:43:14 +0200 Subject: [PATCH 17/43] edited fetaure monitors --- src/giskardpy/monitors/feature_monitors.py | 82 ++++++++++------------ 1 file changed, 39 insertions(+), 43 deletions(-) diff --git a/src/giskardpy/monitors/feature_monitors.py b/src/giskardpy/monitors/feature_monitors.py index 9bd2fb1e73..bbbaf893b5 100644 --- a/src/giskardpy/monitors/feature_monitors.py +++ b/src/giskardpy/monitors/feature_monitors.py @@ -12,8 +12,8 @@ class FeatureMonitor(ExpressionMonitor): def __init__(self, tip_link: str, root_link: str, - world_feature: Union[PointStamped, Vector3Stamped], - robot_feature: Union[PointStamped, Vector3Stamped], + reference_feature: Union[PointStamped, Vector3Stamped], + controlled_feature: Union[PointStamped, Vector3Stamped], name: Optional[str] = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol): @@ -21,94 +21,90 @@ def __init__(self, self.root = god_map.world.search_for_link_name(root_link, None) self.tip = god_map.world.search_for_link_name(tip_link, None) - world_feature.header.frame_id = god_map.world.search_for_link_name(world_feature.header.frame_id, None) - root_world_feature = god_map.world.transform_msg(self.root, world_feature) - robot_feature.header.frame_id = god_map.world.search_for_link_name(robot_feature.header.frame_id, None) - tip_robot_feature = god_map.world.transform_msg(self.tip, robot_feature) + reference_feature.header.frame_id = god_map.world.search_for_link_name(reference_feature.header.frame_id, None) + root_reference_feature = god_map.world.transform_msg(self.root, reference_feature) + controlled_feature.header.frame_id = god_map.world.search_for_link_name(controlled_feature.header.frame_id, + None) + tip_controlled_feature = god_map.world.transform_msg(self.tip, controlled_feature) root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) - if type(robot_feature) == PointStamped: - self.root_P_robot_feature = root_T_tip.dot(cas.Point3(tip_robot_feature)) - elif type(robot_feature) == Vector3Stamped: - self.root_V_robot_feature = root_T_tip.dot(cas.Vector3(tip_robot_feature)) + if isinstance(controlled_feature, PointStamped): + self.root_P_controlled_feature = root_T_tip.dot(cas.Point3(tip_controlled_feature)) + elif isinstance(controlled_feature, Vector3Stamped): + self.root_V_controlled_feature = root_T_tip.dot(cas.Vector3(tip_controlled_feature)) - if type(world_feature) == PointStamped: - self.root_P_world_feature = cas.Point3(root_world_feature) - if type(world_feature) == Vector3Stamped: - self.root_V_world_feature = cas.Vector3(root_world_feature) + if isinstance(reference_feature, PointStamped): + self.root_P_reference_feature = cas.Point3(root_reference_feature) + if isinstance(reference_feature, Vector3Stamped): + self.root_V_reference_feature = cas.Vector3(root_reference_feature) class HeightFeatureMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, - world_feature: PointStamped, - robot_feature: PointStamped, + reference_point: PointStamped, + tip_point: PointStamped, lower_limit: float, upper_limit: float, name: Optional[str] = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, + controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition) - distance = self.root_P_robot_feature - self.root_P_world_feature - - height_vector = cas.Vector3([0, 0, 1]) - - projection = cas.dot(distance, height_vector) - expr = cas.logic_and(cas.greater(projection, lower_limit), cas.less(projection, upper_limit)) + distance = cas.distance_projected_on_vector(self.root_P_reference_feature, self.root_P_controlled_feature, + cas.Vector3([0, 0, 1])) + expr = cas.logic_and(cas.greater(distance, lower_limit), cas.less(distance, upper_limit)) self.expression = expr class PerpendicularFeatureMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, - world_feature: Vector3Stamped, - robot_feature: Vector3Stamped, + reference_normal: Vector3Stamped, + tip_normal: Vector3Stamped, threshold: float = 0.01, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, ): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_normal, + controlled_feature=tip_normal, name=name, stay_true=stay_true, start_condition=start_condition) - expr = cas.dot(self.root_V_world_feature[:3], self.root_V_robot_feature[:3]) + expr = cas.dot(self.root_V_reference_feature[:3], self.root_V_controlled_feature[:3]) self.expression = cas.less_equal(cas.abs(expr), threshold) class DistanceFeatureMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, - world_feature: PointStamped, - robot_feature: PointStamped, + reference_point: PointStamped, + tip_point: PointStamped, lower_limit: float, upper_limit: float, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, ): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, + controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition) - distance_vector = self.root_P_robot_feature - self.root_P_world_feature - height_vector = cas.Vector3([0, 0, 1]) - projection = cas.norm(distance_vector - cas.dot(distance_vector, height_vector) * height_vector) + projection = cas.norm( + cas.distance_vector_projected_on_plane(self.root_P_controlled_feature, self.root_P_reference_feature, + cas.Vector3([0, 0, 1]))) self.expression = cas.logic_and(cas.greater(projection, lower_limit), cas.less(projection, upper_limit)) -#TODO: PointingAt monitor and VectorAligned monitor already exist - class AngleFeatureMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, - world_feature: Vector3Stamped, - robot_feature: Vector3Stamped, + referenec_vector: Vector3Stamped, + tip_vector: Vector3Stamped, lower_limit: float, upper_limit: float, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, ): - super().__init__(tip_link=tip_link, root_link=root_link, world_feature=world_feature, - robot_feature=robot_feature, name=name, stay_true=stay_true, start_condition=start_condition) + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=referenec_vector, + controlled_feature=tip_vector, name=name, stay_true=stay_true, start_condition=start_condition) - expr = cas.angle_between_vector(self.root_V_world_feature, self.root_V_robot_feature) + expr = cas.angle_between_vector(self.root_V_reference_feature, self.root_V_controlled_feature) self.expression = cas.logic_and(cas.greater(expr, lower_limit), cas.less(expr, upper_limit)) From bd05b35d92cffe9adf60116ef891742c7064e5bb Mon Sep 17 00:00:00 2001 From: malte Date: Fri, 9 Aug 2024 08:03:39 +0200 Subject: [PATCH 18/43] angle monitor test --- scripts/giskard_examples.ipynb | 6 +++--- src/giskardpy/monitors/feature_monitors.py | 4 ++-- test/test_integration_pr2.py | 12 ++++++++++-- 3 files changed, 15 insertions(+), 7 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index ec5ed81560..4d53ee1e8c 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -91,7 +91,7 @@ }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 27, "outputs": [], "source": [ "def reset_giskard():\n", @@ -125,9 +125,9 @@ " base_pose.pose.orientation.w = 1\n", " done2 = gs.monitors.add_set_seed_odometry(base_pose=base_pose)\n", " gs.motion_goals.allow_all_collisions()\n", - " gs.monitors.add_end_motion(start_condition=done and done2)\n", + " gs.monitors.add_end_motion(start_condition=f'{done} and {done2}')\n", " gs.execute()\n", - " gs.clear_motion_goals_and_monitors()" + " gs.clear_motion_goals_and_monitors()\n" ], "metadata": { "collapsed": false, diff --git a/src/giskardpy/monitors/feature_monitors.py b/src/giskardpy/monitors/feature_monitors.py index bbbaf893b5..d0e059e4a0 100644 --- a/src/giskardpy/monitors/feature_monitors.py +++ b/src/giskardpy/monitors/feature_monitors.py @@ -95,7 +95,7 @@ def __init__(self, tip_link: str, root_link: str, class AngleFeatureMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, - referenec_vector: Vector3Stamped, + reference_vector: Vector3Stamped, tip_vector: Vector3Stamped, lower_limit: float, upper_limit: float, @@ -103,7 +103,7 @@ def __init__(self, tip_link: str, root_link: str, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, ): - super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=referenec_vector, + super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_vector, controlled_feature=tip_vector, name=name, stay_true=stay_true, start_condition=start_condition) expr = cas.angle_between_vector(self.root_V_reference_feature, self.root_V_controlled_feature) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 8050dbf846..486f275fe3 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -4682,8 +4682,16 @@ def test_feature_angle(self, zero_pose: PR2TestWrapper): tip_vector=robot_feature, lower_angle=0.6, upper_angle=0.9) - - zero_pose.add_default_end_motion_conditions() + mon = zero_pose.monitors.add_monitor(monitor_class='AngleFeatureMonitor', + lower_limit=0.6, + upper_limit=0.9, + root_link='map', + tip_link=zero_pose.r_tip, + reference_vector=world_feature, + tip_vector=robot_feature, + name='angleMonitor') + zero_pose.monitors.add_end_motion(mon) + # zero_pose.add_default_end_motion_conditions() zero_pose.execute() def test_feature_height(self, zero_pose: PR2TestWrapper): From b90190099cb594f0fbad925987a9b547f810dea4 Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 12 Aug 2024 09:37:10 +0200 Subject: [PATCH 19/43] added python interface and test config --- .github/workflows/ci_standalone.yml | 1 + src/giskardpy/monitors/feature_monitors.py | 42 ++-- .../python_interface/python_interface.py | 238 ++++++++++++++++++ test/test_integration_pr2.py | 91 +++---- 4 files changed, 315 insertions(+), 57 deletions(-) diff --git a/.github/workflows/ci_standalone.yml b/.github/workflows/ci_standalone.yml index 25727acd73..567c2c98ee 100644 --- a/.github/workflows/ci_standalone.yml +++ b/.github/workflows/ci_standalone.yml @@ -55,6 +55,7 @@ jobs: test3: test/test_integration_pr2.py::TestWorldManipulation test4: test/test_integration_pr2.py::TestManipulability::test_manip1 test5: test/test_integration_pr2.py::TestWeightScaling + test6: test/test_integration_pr2.py::TestFeatureFunctions pr2_part2: needs: [ build_dependencies ] uses: ./.github/workflows/reusable_robot_ci.yml diff --git a/src/giskardpy/monitors/feature_monitors.py b/src/giskardpy/monitors/feature_monitors.py index d0e059e4a0..41b1876ae1 100644 --- a/src/giskardpy/monitors/feature_monitors.py +++ b/src/giskardpy/monitors/feature_monitors.py @@ -14,12 +14,14 @@ def __init__(self, tip_link: str, root_link: str, reference_feature: Union[PointStamped, Vector3Stamped], controlled_feature: Union[PointStamped, Vector3Stamped], + root_group: Optional[str] = None, + tip_group: Optional[str] = None, name: Optional[str] = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol): super().__init__(name=name, stay_true=stay_true, start_condition=start_condition) - self.root = god_map.world.search_for_link_name(root_link, None) - self.tip = god_map.world.search_for_link_name(tip_link, None) + self.root = god_map.world.search_for_link_name(root_link, root_group) + self.tip = god_map.world.search_for_link_name(tip_link, tip_group) reference_feature.header.frame_id = god_map.world.search_for_link_name(reference_feature.header.frame_id, None) root_reference_feature = god_map.world.transform_msg(self.root, reference_feature) @@ -39,72 +41,84 @@ def __init__(self, self.root_V_reference_feature = cas.Vector3(root_reference_feature) -class HeightFeatureMonitor(FeatureMonitor): +class HeightMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, reference_point: PointStamped, tip_point: PointStamped, lower_limit: float, upper_limit: float, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, name: Optional[str] = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, - controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition) + controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition, + root_group=root_group, tip_group=tip_group) - distance = cas.distance_projected_on_vector(self.root_P_reference_feature, self.root_P_controlled_feature, + distance = cas.distance_projected_on_vector(self.root_P_controlled_feature, self.root_P_reference_feature, cas.Vector3([0, 0, 1])) - expr = cas.logic_and(cas.greater(distance, lower_limit), cas.less(distance, upper_limit)) + expr = cas.logic_and(cas.greater_equal(distance, lower_limit), cas.less_equal(distance, upper_limit)) self.expression = expr -class PerpendicularFeatureMonitor(FeatureMonitor): +class PerpendicularMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, reference_normal: Vector3Stamped, tip_normal: Vector3Stamped, threshold: float = 0.01, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_normal, - controlled_feature=tip_normal, name=name, stay_true=stay_true, start_condition=start_condition) + controlled_feature=tip_normal, name=name, stay_true=stay_true, start_condition=start_condition, + root_group=root_group, tip_group=tip_group) expr = cas.dot(self.root_V_reference_feature[:3], self.root_V_controlled_feature[:3]) self.expression = cas.less_equal(cas.abs(expr), threshold) -class DistanceFeatureMonitor(FeatureMonitor): +class DistanceMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, reference_point: PointStamped, tip_point: PointStamped, lower_limit: float, upper_limit: float, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, - controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition) + controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition, + root_group=root_group, tip_group=tip_group) - projection = cas.norm( + distance = cas.norm( cas.distance_vector_projected_on_plane(self.root_P_controlled_feature, self.root_P_reference_feature, cas.Vector3([0, 0, 1]))) - self.expression = cas.logic_and(cas.greater(projection, lower_limit), cas.less(projection, upper_limit)) + self.expression = cas.logic_and(cas.greater_equal(distance, lower_limit), cas.less_equal(distance, upper_limit)) -class AngleFeatureMonitor(FeatureMonitor): +class AngleMonitor(FeatureMonitor): def __init__(self, tip_link: str, root_link: str, reference_vector: Vector3Stamped, tip_vector: Vector3Stamped, lower_limit: float, upper_limit: float, + root_group: Optional[str] = None, + tip_group: Optional[str] = None, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_vector, - controlled_feature=tip_vector, name=name, stay_true=stay_true, start_condition=start_condition) + controlled_feature=tip_vector, name=name, stay_true=stay_true, start_condition=start_condition, + root_group=root_group, tip_group=tip_group) expr = cas.angle_between_vector(self.root_V_reference_feature, self.root_V_controlled_feature) self.expression = cas.logic_and(cas.greater(expr, lower_limit), cas.less(expr, upper_limit)) diff --git a/src/giskardpy/python_interface/python_interface.py b/src/giskardpy/python_interface/python_interface.py index bb79123b44..06427aefa2 100644 --- a/src/giskardpy/python_interface/python_interface.py +++ b/src/giskardpy/python_interface/python_interface.py @@ -37,6 +37,8 @@ from giskardpy.monitors.overwrite_state_monitors import SetOdometry, SetSeedConfiguration from giskardpy.monitors.payload_monitors import Print, Sleep, SetMaxTrajectoryLength, PayloadAlternator from giskardpy.utils.utils import kwargs_to_json, get_all_classes_in_package +from giskardpy.goals.feature_functions import AlignPerpendicular, HeightGoal, AngleGoal, DistanceGoal +from giskardpy.monitors.feature_monitors import PerpendicularMonitor, AngleMonitor, HeightMonitor, DistanceMonitor class WorldWrapper: @@ -1305,6 +1307,138 @@ def add_cartesian_position_straight(self, end_condition=end_condition, **kwargs) + def add_align_perpendicular(self, + reference_normal: Vector3Stamped, + tip_link: str, + tip_normal: Vector3Stamped, + root_link: str, + tip_group: str = None, + root_group: str = None, + reference_velocity: Optional[float] = None, + weight: Optional[float] = None, + name: Optional[str] = None, + start_condition: str = '', + hold_condition: str = '', + end_condition: str = '', + **kwargs: goal_parameter): + + self.add_motion_goal(motion_goal_class=AlignPerpendicular.__name__, + tip_normal=tip_normal, + reference_normal=reference_normal, + tip_link=tip_link, + root_link=root_link, + tip_group=tip_group, + root_group=root_group, + max_vel=reference_velocity, + weight=weight, + name=name, + start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, + **kwargs) + + def add_height(self, + reference_point: PointStamped, + tip_point: PointStamped, + tip_link: str, + root_link: str, + lower_limit: float, + upper_limit: float, + tip_group: str = None, + root_group: str = None, + reference_velocity: Optional[float] = None, + weight: Optional[float] = None, + name: Optional[str] = None, + start_condition: str = '', + hold_condition: str = '', + end_condition: str = '', + **kwargs: goal_parameter): + + self.add_motion_goal(motion_goal_class=HeightGoal.__name__, + tip_point=tip_point, + reference_point=reference_point, + tip_link=tip_link, + root_link=root_link, + lower_limit=lower_limit, + upper_limit=upper_limit, + tip_group=tip_group, + root_group=root_group, + max_vel=reference_velocity, + weight=weight, + name=name, + start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, + **kwargs) + + def add_distance(self, + reference_point: PointStamped, + tip_point: PointStamped, + tip_link: str, + root_link: str, + lower_limit: float, + upper_limit: float, + tip_group: str = None, + root_group: str = None, + reference_velocity: Optional[float] = None, + weight: Optional[float] = None, + name: Optional[str] = None, + start_condition: str = '', + hold_condition: str = '', + end_condition: str = '', + **kwargs: goal_parameter): + + self.add_motion_goal(motion_goal_class=DistanceGoal.__name__, + tip_point=tip_point, + reference_point=reference_point, + tip_link=tip_link, + root_link=root_link, + lower_limit=lower_limit, + upper_limit=upper_limit, + tip_group=tip_group, + root_group=root_group, + max_vel=reference_velocity, + weight=weight, + name=name, + start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, + **kwargs) + + def add_angle(self, + reference_vector: Vector3Stamped, + tip_link: str, + tip_vector: Vector3Stamped, + root_link: str, + lower_angle: float, + upper_angle: float, + tip_group: str = None, + root_group: str = None, + reference_velocity: Optional[float] = None, + weight: Optional[float] = None, + name: Optional[str] = None, + start_condition: str = '', + hold_condition: str = '', + end_condition: str = '', + **kwargs: goal_parameter): + + self.add_motion_goal(motion_goal_class=AngleGoal.__name__, + tip_vector=tip_vector, + reference_vector=reference_vector, + tip_link=tip_link, + root_link=root_link, + lower_angle=lower_angle, + upper_angle=upper_angle, + tip_group=tip_group, + root_group=root_group, + max_vel=reference_velocity, + weight=weight, + name=name, + start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, + **kwargs) + class MonitorWrapper: _monitors: List[Monitor] @@ -1686,6 +1820,110 @@ def add_payload_alternator(self, start_condition=start_condition, mod=mod) + def add_vectors_perpendicular(self, + root_link: str, + tip_link: str, + reference_normal: Vector3Stamped, + tip_normal: Vector3Stamped, + name: Optional[str] = None, + start_condition: str = '', + root_group: Optional[str] = None, + tip_group: Optional[str] = None, + threshold: float = 0.01) -> str: + """ + True if tip_normal of tip_link is perpendicular to goal_normal within threshold. + """ + return self.add_monitor(monitor_class=PerpendicularMonitor.__name__, + name=name, + root_link=root_link, + tip_link=tip_link, + reference_normal=reference_normal, + tip_normal=tip_normal, + start_condition=start_condition, + root_group=root_group, + tip_group=tip_group, + threshold=threshold) + + def add_angle(self, + root_link: str, + tip_link: str, + reference_vector: Vector3Stamped, + tip_vector: Vector3Stamped, + lower_angle: float, + upper_angle: float, + name: Optional[str] = None, + start_condition: str = '', + root_group: Optional[str] = None, + tip_group: Optional[str] = None) -> str: + """ + True if angle between tip_vector and reference_vector is within lower and upper angle. + """ + return self.add_monitor(monitor_class=AngleMonitor.__name__, + name=name, + root_link=root_link, + tip_link=tip_link, + reference_vector=reference_vector, + tip_vector=tip_vector, + lower_limit=lower_angle, + upper_limit=upper_angle, + start_condition=start_condition, + root_group=root_group, + tip_group=tip_group) + + def add_height(self, + root_link: str, + tip_link: str, + reference_point: PointStamped, + tip_point: PointStamped, + lower_limit: float, + upper_limit: float, + name: Optional[str] = None, + start_condition: str = '', + root_group: Optional[str] = None, + tip_group: Optional[str] = None) -> str: + """ + True if distance along the z-axis of root_link between tip_point and reference_point + is within lower and upper limit. + """ + return self.add_monitor(monitor_class=HeightMonitor.__name__, + name=name, + root_link=root_link, + tip_link=tip_link, + reference_point=reference_point, + tip_point=tip_point, + lower_limit=lower_limit, + upper_limit=upper_limit, + start_condition=start_condition, + root_group=root_group, + tip_group=tip_group) + + def add_distance(self, + root_link: str, + tip_link: str, + reference_point: PointStamped, + tip_point: PointStamped, + lower_limit: float, + upper_limit: float, + name: Optional[str] = None, + start_condition: str = '', + root_group: Optional[str] = None, + tip_group: Optional[str] = None) -> str: + """ + True if distance between tip_point and reference_point on the plane (that has the z-axis of + root_link as a normal vector) is within lower and upper limit. + """ + return self.add_monitor(monitor_class=DistanceMonitor.__name__, + name=name, + root_link=root_link, + tip_link=tip_link, + reference_point=reference_point, + tip_point=tip_point, + lower_limit=lower_limit, + upper_limit=upper_limit, + start_condition=start_condition, + root_group=root_group, + tip_group=tip_group) + class GiskardWrapper: last_feedback: MoveFeedback = None diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 486f275fe3..809e2add8c 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -44,7 +44,6 @@ GiskardTestWrapper, pr2_urdf from giskardpy.goals.weight_scaling_goals import MaxManipulabilityLinWeight, BaseArmWeightScaling - # scopes = ['module', 'class', 'function'] pocky_pose = {'r_elbow_flex_joint': -1.29610152504, 'r_forearm_roll_joint': -0.0301682323805, @@ -4657,13 +4656,16 @@ def test_feature_perpendicular(self, zero_pose: PR2TestWrapper): robot_feature.header.frame_id = zero_pose.r_tip robot_feature.vector.x = 1 - zero_pose.motion_goals.add_motion_goal(motion_goal_class='AlignPerpendicular', - root_link='map', - tip_link=zero_pose.r_tip, - reference_normal=world_feature, - tip_normal=robot_feature) + zero_pose.motion_goals.add_align_perpendicular(root_link='map', + tip_link=zero_pose.r_tip, + reference_normal=world_feature, + tip_normal=robot_feature) + mon = zero_pose.monitors.add_vectors_perpendicular(root_link='map', + tip_link=zero_pose.r_tip, + reference_normal=world_feature, + tip_normal=robot_feature) - zero_pose.add_default_end_motion_conditions() + zero_pose.monitors.add_end_motion(mon) zero_pose.execute() def test_feature_angle(self, zero_pose: PR2TestWrapper): @@ -4675,23 +4677,20 @@ def test_feature_angle(self, zero_pose: PR2TestWrapper): robot_feature.header.frame_id = zero_pose.r_tip robot_feature.vector.z = 1 - zero_pose.motion_goals.add_motion_goal(motion_goal_class='AngleGoal', - root_link='map', - tip_link=zero_pose.r_tip, - reference_vector=world_feature, - tip_vector=robot_feature, - lower_angle=0.6, - upper_angle=0.9) - mon = zero_pose.monitors.add_monitor(monitor_class='AngleFeatureMonitor', - lower_limit=0.6, - upper_limit=0.9, - root_link='map', - tip_link=zero_pose.r_tip, - reference_vector=world_feature, - tip_vector=robot_feature, - name='angleMonitor') + zero_pose.motion_goals.add_angle(root_link='map', + tip_link=zero_pose.r_tip, + reference_vector=world_feature, + tip_vector=robot_feature, + lower_angle=0.6, + upper_angle=0.9) + mon = zero_pose.monitors.add_angle(lower_angle=0.6, + upper_angle=0.9, + root_link='map', + tip_link=zero_pose.r_tip, + reference_vector=world_feature, + tip_vector=robot_feature, + name='angleMonitor') zero_pose.monitors.add_end_motion(mon) - # zero_pose.add_default_end_motion_conditions() zero_pose.execute() def test_feature_height(self, zero_pose: PR2TestWrapper): @@ -4701,15 +4700,20 @@ def test_feature_height(self, zero_pose: PR2TestWrapper): robot_feature = PointStamped() robot_feature.header.frame_id = zero_pose.r_tip - zero_pose.motion_goals.add_motion_goal(motion_goal_class='HeightGoal', - root_link='map', - tip_link=zero_pose.r_tip, - reference_point=world_feature, - tip_point=robot_feature, - lower_limit=1, - upper_limit=2) + zero_pose.motion_goals.add_height(root_link='map', + tip_link=zero_pose.r_tip, + reference_point=world_feature, + tip_point=robot_feature, + lower_limit=1, + upper_limit=1) + mon = zero_pose.monitors.add_height(root_link='map', + tip_link=zero_pose.r_tip, + reference_point=world_feature, + tip_point=robot_feature, + lower_limit=0.999, + upper_limit=1.001) - zero_pose.add_default_end_motion_conditions() + zero_pose.monitors.add_end_motion(mon) zero_pose.execute() def test_feature_distance(self, zero_pose: PR2TestWrapper): @@ -4719,21 +4723,22 @@ def test_feature_distance(self, zero_pose: PR2TestWrapper): robot_feature = PointStamped() robot_feature.header.frame_id = zero_pose.r_tip - zero_pose.motion_goals.add_motion_goal(motion_goal_class='DistanceGoal', - root_link='map', - tip_link=zero_pose.r_tip, - reference_point=world_feature, - tip_point=robot_feature, - lower_limit=2, - upper_limit=2, - max_vel=0.3 - ) + zero_pose.motion_goals.add_distance(root_link='map', + tip_link=zero_pose.r_tip, + reference_point=world_feature, + tip_point=robot_feature, + lower_limit=2, + upper_limit=2) + mon = zero_pose.monitors.add_distance(root_link='map', + tip_link=zero_pose.r_tip, + reference_point=world_feature, + tip_point=robot_feature, + lower_limit=1.998, + upper_limit=2.002) - zero_pose.add_default_end_motion_conditions() + zero_pose.monitors.add_end_motion(mon) zero_pose.execute() - - # kernprof -lv py.test -s test/test_integration_pr2.py # time: [1-9][1-9]*.[1-9]* s # import pytest From 5857b6ca8ba2ab4dd5c78b0c90575e5ba326bc65 Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 12 Aug 2024 09:55:47 +0200 Subject: [PATCH 20/43] changed distance threshold for qpalm to solve distance goal --- test/test_integration_pr2.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 809e2add8c..0978b14ecd 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -4733,8 +4733,8 @@ def test_feature_distance(self, zero_pose: PR2TestWrapper): tip_link=zero_pose.r_tip, reference_point=world_feature, tip_point=robot_feature, - lower_limit=1.998, - upper_limit=2.002) + lower_limit=1.99, + upper_limit=2.01) zero_pose.monitors.add_end_motion(mon) zero_pose.execute() From 27f84aa6d8884775c3285edcf165bb2890448656 Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 12 Aug 2024 13:13:37 +0200 Subject: [PATCH 21/43] notebook updates --- scripts/giskard_examples.ipynb | 399 +++++++++++++++++--------------- src/giskardpy/goals/pointing.py | 4 - 2 files changed, 212 insertions(+), 191 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 4d53ee1e8c..021a67d225 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,56 +2,16 @@ "cells": [ { "cell_type": "code", - "execution_count": 1, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Set parameter ServerPassword\n", - "Set parameter ServerTimeout to value 10\n", - "Set parameter TokenServer to value \"134.102.206.102\"\n", - "[/unnamed]: Found these qp solvers: ['gurobi', 'qpalm', 'qpSWIFT']\n" - ] - } - ], + "execution_count": 7, + "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", - "import numpy as np\n", - "import pytest\n", "import rospy\n", - "from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, QuaternionStamped, Pose, Vector3\n", - "from nav_msgs.msg import Path\n", - "from numpy import pi\n", - "from shape_msgs.msg import SolidPrimitive\n", + "from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, Vector3\n", "from tf.transformations import quaternion_from_matrix, quaternion_about_axis\n", - "\n", - "import giskardpy.utils.tfwrapper as tf\n", - "from giskard_msgs.msg import WorldBody, CollisionEntry, WorldGoal, GiskardError\n", - "from giskardpy.configs.behavior_tree_config import StandAloneBTConfig\n", - "from giskardpy.configs.giskard import Giskard\n", - "from giskardpy.configs.iai_robots.pr2 import PR2CollisionAvoidance, PR2StandaloneInterface, WorldWithPR2Config\n", - "from giskardpy.configs.qp_controller_config import SupportedQPSolver, QPControllerConfig\n", - "from giskardpy.goals.base_traj_follower import FollowNavPath\n", - "from giskardpy.goals.cartesian_goals import RelativePositionSequence\n", - "from giskardpy.goals.caster import Circle, Wave\n", - "from giskardpy.goals.collision_avoidance import CollisionAvoidanceHint\n", - "from giskardpy.goals.goals_tests import DebugGoal, CannotResolveSymbol\n", - "from giskardpy.goals.joint_goals import JointVelocityLimit, UnlimitedJointGoal\n", - "from giskardpy.monitors.set_prediction_horizon import SetQPSolver\n", - "from giskardpy.goals.tracebot import InsertCylinder\n", - "from giskardpy.god_map import god_map\n", - "from giskardpy.model.better_pybullet_syncer import BetterPyBulletSyncer\n", - "from giskardpy.model.collision_world_syncer import CollisionWorldSynchronizer\n", - "from giskardpy.model.utils import make_world_body_box, hacky_urdf_parser_fix\n", - "from giskardpy.model.world import WorldTree\n", - "from giskardpy.data_types import PrefixName\n", - "from giskardpy.tasks.task import WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE\n", - "from giskardpy.python_interface.old_python_interface import OldGiskardWrapper\n", - "from giskardpy.utils.utils import launch_launchfile, suppress_stderr, resolve_ros_iris\n", - "from giskardpy.utils.math import compare_points\n", "from giskardpy.goals.weight_scaling_goals import MaxManipulabilityLinWeight, BaseArmWeightScaling\n", - "from copy import deepcopy" + "from copy import deepcopy\n", + "from giskard_msgs.msg import WorldBody, CollisionEntry, WorldGoal, GiskardError" ], "metadata": { "collapsed": false, @@ -76,7 +36,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 22, "outputs": [], "source": [ "# Launch the giskardpy PR2 standalone launch file before this\n", @@ -91,7 +51,7 @@ }, { "cell_type": "code", - "execution_count": 27, + "execution_count": 4, "outputs": [], "source": [ "def reset_giskard():\n", @@ -172,17 +132,8 @@ }, { "cell_type": "code", - "execution_count": 8, - "outputs": [ - { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995223908, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044781599804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990447611174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044740634857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985671730117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044823788993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2025998089584906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044823788988, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976119968005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134408695, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966568205893, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961792324837, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2058495701644378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952240562724, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20714947464681668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20779942688800612, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20844937912919556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.209099331370385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20974928361157444, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21039923585276388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21104918809395332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21169914033514275, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2123490925763322, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21299904481752163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21364899705871107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2142989492999005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21494890154108995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2155988537822794, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624880602346883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21689875826465826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2175487105058477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21819866274703714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21884861498822658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21949856722941602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22014851947060546, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2207984717117949, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22144842395298434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22209837619417377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2227483284353632, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22339828067655265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2240482329177421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22469818515893153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22534813740012097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2259980896413104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22664804188249985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22729799412368928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22794794636487872, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22859789860606816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2292478508472576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22989780308844704, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23054775532963648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23119770757082592, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23184765981201536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2324976120532048, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23314756429439423, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23379751653558367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2344474687767731, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23509742101796255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.235747373259152, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23639732550034143, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23704727774153087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2376972299827203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23834718222390974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23899713446509918, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23964708670628862, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24029703894747806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2409469911886675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24159694342985694, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24224689567104637, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2428968479122358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24354680015342525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2441967523946147, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24484670463580413, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24549665687699357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.246146609118183, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24679656135937245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24744651360056188, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24809646584175132, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24874641808294076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2493963703241302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25004632256531967, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25069627480650913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2513462270476986, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25199617928888807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25264613153007753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.253296083771267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25394603601245647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25459598825364593, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2552459404948354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25589589273602487, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25654584497721433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2571957972184038, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25784574945959327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25849570170078273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2591456539419722, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25979560618316166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26044555842435113, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2610955106655406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26174546290673006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26239541514791953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.263045367389109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26369531963029846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26434527187148793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2649952241126774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26564517635386686, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26629512859505633, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2669450808362458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26759503307743526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26824498531862473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2688949375598142, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26954488980100366, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27019484204219313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2708447942833826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27149474652457206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27214469876576153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.272794651006951, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27344460324814046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2740945554893299, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2747445077305194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27539445997170886, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2760444122128983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2766943644540878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27734431669527726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2779942689364667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2786442211776562, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27929417341884566, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2799441256600351, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2805940779012246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28124403014241406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2818939823836035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.282543934624793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28319388686598246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2838438391071719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2844937913483614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28514374358955086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2857936958307403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2864436480719298, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28709360031311926, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2877435525543087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2883935047954982, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28904345703668766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2896934092778771, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904482378899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2903433615190666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0" - }, - "execution_count": 8, - "metadata": {}, - "output_type": "execute_result" - } - ], + "execution_count": 5, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -190,7 +141,7 @@ "joint_monitor = gs.monitors.add_joint_position(goal_state=joint_goal)\n", "gs.motion_goals.add_joint_position(goal_state=joint_goal)\n", "gs.monitors.add_end_motion(start_condition=joint_monitor)\n", - "gs.execute()" + "assert gs.execute().error.code == GiskardError.SUCCESS" ], "metadata": { "collapsed": false, @@ -213,15 +164,18 @@ }, { "cell_type": "code", - "execution_count": 9, + "execution_count": 7, "outputs": [ { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995224128082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.003749999998426497, 0.0037500000000161406, -0.0037499999999998975, -0.14999999999982933, 0.0009726135623061073, -0.10000999999993533, 0.003749999999999878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529551367, -0.0006253905029042516, -0.0006250000000005031]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825616084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999996852993, 0.07500000000009105, -0.07499999999999783, 3.413413898528338e-12, 0.019452271246122144, 1.2934985057206626e-12, 0.07499999999999801, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059102733, -0.012507810058085031, -0.012500000000000719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999044865274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.010874000462810094, 0.014999999121785897, -0.014999999999929904, -0.15000000000052507, 0.00249685109396703, -0.10001000000022002, 0.014999999999935657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.002494915898464792, -0.0025050721386444116, -0.002499999999906253]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044904931787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1424800092876719, 0.2249999824353951, -0.22499999999860015, -1.3914817577019912e-11, 0.030484750633218455, -5.693777305049226e-12, 0.22499999999871556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0374061329101931, -0.0375936327148032, -0.0374999999999795]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985673060278, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.019214385627334598, 0.03214772656204189, -0.03562499999935418, -0.15000000000054162, 0.004003912303603865, -0.10001000000023216, 0.03562499999940766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005911945269440533, -0.005962921582434169, -0.005937499999840859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881507441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1668077032904901, 0.3429545488051197, -0.4124999999884855, -3.3086328286054907e-13, 0.030141224192736706, -2.427690312094603e-13, 0.4124999999894401, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06834058741951482, -0.06915698887579515, -0.06874999999869214]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2025998089745868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.027332611693070694, 0.05225635205961038, -0.06406249999670444, -0.15000000000063227, 0.00509351329647851, -0.1000100000002995, 0.06406249999708183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010600654477185504, -0.010752838725563377, -0.010677083330842652]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487968028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.16236452131472193, 0.40217250995136977, -0.5687499999470049, -1.8132440942715141e-12, 0.021792019857492892, -1.3466319672723584e-12, 0.5687499999534835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09377418415489941, -0.09579834286258415, -0.09479166662003588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2032497612186043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.03465601580721158, 0.07338202302242261, -0.09881249999420641, -0.15000000000064317, 0.005562151157030444, -0.10001000000030755, 0.09881249999494346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016296158549235513, -0.016639097200595834, -0.016468749995204174]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880350157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1464680822828177, 0.4225134192562447, -0.6949999999500392, -2.1797790610805456e-13, 0.009372757211038677, -1.6105727900585533e-13, 0.6949999999572325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11391008144100016, -0.11772516950064911, -0.1158333332872304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134620561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04107639227844112, 0.09452901507328197, -0.13861249997290648, -0.15000000000198216, 0.005347532109568132, -0.10001000000140058, 0.13861249995264174, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022774491634322096, -0.023423890671478025, -0.023102083324553664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869035943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.12840752942459085, 0.42293984101718723, -0.7959999995740012, -2.677979323697273e-11, -0.004292380949246234, -2.1860605853446573e-11, 0.7959999991539658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12956666170173162, -0.1356958694176438, -0.1326666665869898]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966570582583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04666118591631699, 0.11525153479943673, -0.18245249994872562, -0.15000000000228894, 0.004470968152595306, -0.10001000000169422, 0.18245249991166518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029855627973834894, -0.030949331744835305, -0.030408749986253168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044875394872, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.11169587275751738, 0.4144503945230952, -0.8767999995163827, -6.1357932112318646e-12, -0.01753127913945652, -5.8727073376287276e-12, 0.8767999991804688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14162272679025595, -0.1505088214671456, -0.1461333332339901]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961794978372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05152178527779883, 0.1353647889149822, -0.22952449992876367, -0.15000000000234268, 0.0029953253590808606, -0.10001000000174005, 0.2295244998783314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03739517881513101, -0.03908896828573813, -0.0382540833152034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879157857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09721198722963685, 0.402265082310909, -0.9414399996007609, -1.0748467169952566e-12, -0.029512855870288908, -9.167461066347978e-13, 0.9414399993333245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15079101682592239, -0.16279273081805654, -0.15690666657900465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966648689288, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05576265608289525, 0.15399602312200017, -0.2791820999128309, -0.1500000000017874, 0.0010285471017613223, -0.10001000000065693, 0.2791820998517253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04527752908108162, -0.047741235841549406, -0.04653034997789501]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999029257817154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08481741610192829, 0.3726246841403596, -0.9931519996813443, 1.1105360308673324e-11, -0.039335565146390764, 2.166230133870735e-11, 0.993151999467878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15764700531901213, -0.17304535111622546, -0.16552533325383217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20389971424308817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05942678249747326, 0.17116549308609977, -0.32918212496676713, -0.15000000000206704, -0.001336658350849851, -0.10001000000106844, 0.3291820998507171, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05341021492784108, -0.05682436098581435, -0.055151363307386986]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044876094263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07328252829156022, 0.3433893992819922, -1.0000005010787243, -5.592900813623596e-12, -0.04730410905222346, -8.230135473705073e-12, 0.9999999999798355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16265371693518918, -0.1816625028852989, -0.1724202665898396]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976199901068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06254927332067894, 0.18720822280178823, -0.3791821500200128, -0.15000000000220307, -0.0040210550792610135, -0.10001000000208868, 0.3791820998487869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.061719348735855044, -0.06627236474911988, -0.06404817396991841]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488154993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.062449816464113767, 0.32085459431376934, -1.000000501064914, -2.720657585222056e-12, -0.053687934568223246, -2.0404835988778344e-11, 0.9999999999613957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16618267616027926, -0.18896007526611042, -0.17793621325062856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980975502256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06530334246783995, 0.20274448077030074, -0.42918217507376827, -0.150000000002362, -0.006981139353238399, -0.10169702523622634, 0.42918209984579514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07014591555267684, -0.07603190914626919, -0.07316562249855446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879762176, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05508138294321995, 0.31072515937025036, -1.0000005010751092, -3.178670627095961e-12, -0.059201685479547704, -0.03374050468275326, 0.9999999999401649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16853133633643577, -0.1951908879429861, -0.18234897057272118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985751100356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06790328523509014, 0.21824311964802745, -0.47918220012370066, -0.1500000000023791, -0.010200549301847222, -0.10666265915696402, 0.479182099845268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07864278700313587, -0.0860597960924229, -0.0824595813214565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880380298, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05199885534500379, 0.30997277755453384, -1.0000005009986477, -3.419628306111715e-13, -0.06438819897217644, -0.09931267841475351, 0.9999999999894567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1699374290091808, -0.20055773892307413, -0.18587917645804092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999052667752, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0698257236356248, 0.23421513254549522, -0.525432225169826, -0.1500000000023803, -0.017429254760860668, -0.1153266305046296, 0.5257753718839405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08717232125632797, -0.09632097536722978, -0.09189474837977776]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884567195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.038448768010693184, 0.31944025794935554, -0.9250005009225063, -2.4558949901505577e-14, -0.14457410918026892, -0.17327942695331155, 0.9318654407734511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17059068506384195, -0.20522358549613762, -0.18870334116642523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995302277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07072955470746402, 0.2508652922059786, -0.5641822502121976, -0.1500000000023839, -0.024917259070361825, -0.12713418211536878, 0.5652119159618963, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09570443891067591, -0.10678695264977467, -0.10144288202640352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880103793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018076621436784384, 0.3330031932096672, -0.7750005008474314, -7.163789731263766e-14, -0.1497600861900231, -0.23615103221478356, 0.7887308815591166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17064235308695888, -0.20931954565089778, -0.19096267293251507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000000007787679, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07051671251909349, 0.268156085445879, -0.5916822752530768, -0.15000000000252947, -0.030483560079777795, -0.1410550519159715, 0.5937417320800253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10421508353998447, -0.11743451382759128, -0.11108138894132084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880041834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004256843767410735, 0.3458158647980082, -0.5500005008175851, -2.9113963874629762e-12, -0.11132602018831939, -0.2784173960120548, 0.5705963223625797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17021289258617123, -0.21295122355633223, -0.19277013829834663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935004853499577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06914440590006907, 0.2860034411792493, -0.6041823002928683, -0.1500000000025775, -0.034551304873879134, -0.15604040622717463, 0.6076148202386424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11268499205073444, -0.12824470059199697, -0.12079219447249467]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875442563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027446132380488278, 0.3569471146674063, -0.2500005007958297, -9.603601719665634e-13, -0.08135489588202678, -0.2997070862240625, 0.2774617631723428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16939817021499945, -0.21620373528811399, -0.1942161106234766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009629126512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06662506364786523, 0.3043069196152068, -0.6033489878269833, -0.15000000000261468, -0.0377013785949796, -0.17129104770331385, 0.6079257270381646, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12109871381632487, -0.1392019864674616, -0.1305608388964588]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044874612967, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0503868450440767, 0.3660695687191493, 0.016666249317699444, -7.435904150903004e-13, -0.0630014744220093, -0.3050128295227844, 0.006218135990444407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1682744353118084, -0.21914571750929274, -0.19537288847928289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980501440472577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06301180850687928, 0.3229607227779738, -0.5914045607766345, -0.15000000000275565, -0.0404202259926186, -0.18633468310182805, 0.5969348160408071, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12944382915393812, -0.15029361321615042, -0.14037575443354122]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880148077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07226510281971905, 0.37307606325533976, 0.23888854100697743, -2.8192075957799583e-12, -0.05437694795278004, -0.300872707970284, -0.21981821994715087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16690230675226528, -0.22183253497377647, -0.19629831074164802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019180376744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05835369809320081, 0.3418781576483917, -0.5702008715717964, -0.15000000000280575, -0.042984091717350646, -0.2009783937928531, 0.5765257235469713, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1377103272166334, -0.16150905591226594, -0.1502276868616847]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869805191, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0931622082735693, 0.37834869740835814, 0.42407378409676216, -1.0021247626099497e-12, -0.05127731449464091, -0.2928742138205009, -0.40818184987671735, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1653299612539053, -0.2243088539223104, -0.19703864856286932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023955960436, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05283808113905355, 0.3608647472264093, -0.541281130567749, -0.15000000000280686, -0.049142975769148396, -0.2151847073040153, 0.5504484495566567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14589011117262793, -0.17283959141676142, -0.1601092328042018]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044883261575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11031233908294522, 0.37973179156035275, 0.5783948200809502, -2.2256829060496475e-14, -0.12317768103595497, -0.28412627022324377, -0.5215454798062913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16359567911989042, -0.22661071008990966, -0.19763091885034242]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028731554044, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0468828881752113, 0.37881810371212465, -0.5083953377571927, -0.15000000000280925, -0.05955011904709216, -0.22854789099420542, 0.5224529940698626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1539766048967487, -0.18427795010648435, -0.17001446955819063]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044881278357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11910385927684494, 0.3590671297143069, 0.6577158562111252, -4.777915898499416e-14, -0.20814286555887532, -0.26726367380380267, -0.559909109735883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16172987448241521, -0.2287671737944585, -0.19810473507977652]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033507151394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.039489176492562186, 0.39434308050261524, -0.47401288993818014, -0.15000000000280894, -0.07605884905722497, -0.24014598372470913, 0.49628935708658883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1619644405443123, -0.19581803469267806, -0.17993865896138403]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880529788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1478742336529823, 0.31049953580981204, 0.6876489563802516, 6.001150630434665e-15, -0.3301746002026562, -0.23196185461007457, -0.5232727396654748, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597567129512723, -0.23080169172387394, -0.19848378806386788]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19480038282762216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.02912803671121529, 0.40700369900793454, -0.4347193541259278, -0.15000000000282587, -0.10106612406230406, -0.24950232708356584, 0.47570753856798886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16984921049433546, -0.2074546931553055, -0.1898780104834433]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487783569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2072227956269379, 0.25321237010638586, 0.785870716245046, -3.383971651076609e-13, -0.5001455001015817, -0.1871268671771344, -0.4116363703719989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15769539900046325, -0.23273316925254883, -0.19878703044118534]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415043058362855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.015160346642552938, 0.41691035843029217, -0.39128452547647374, -0.15000000000282784, -0.13178511024205766, -0.256619368591889, 0.4624542279061011, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17762727049736116, -0.2191835353580724, -0.19982949170094993]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879871994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27935380137324706, 0.19813318844715294, 0.8686965729890815, -3.967496378540561e-14, -0.6143797235950719, -0.1423408301664627, -0.26506621323775525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555612000605141, -0.23457684405533777, -0.19902962435013272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1935004783396239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0010544919765346963, 0.4244440260482049, -0.34478616097160525, -0.15000000000306368, -0.16836029912447867, -0.2623223432269921, 0.45640264438867295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18542523778181494, -0.2303918611023138, -0.20979067667094325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880092969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.32429677238175264, 0.1506733523582546, 0.92996729009737, -4.717020045662648e-12, -0.7315037776484199, -0.11405949270206249, -0.12103167034856235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15595934568907588, -0.22416651488482797, -0.19922369939986634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052609584238, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.017990172499795433, 0.43002769747145114, -0.29745313055942657, -0.15000000000306685, -0.20962045022955575, -0.2673301636176097, 0.45645726789410673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19338851010814545, -0.240470959076024, -0.2197596246463134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875630292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3387136104652147, 0.11167342846492416, 0.9466606082435739, -6.305298277255488e-14, -0.8252030221015414, -0.1001564078123521, 0.0010924701086751226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15926544652661026, -0.20158195947420426, -0.1993789595074029]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057385268532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.034633937661149736, 0.43408397522487135, -0.2509924394712505, -0.15000000000307334, -0.254628571111664, -0.2720775054129418, 0.4612372135474278, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20168110604227568, -0.2488164766271966, -0.22973478302476968]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904486314135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3328753032270861, 0.08112555506840465, 0.929213821763521, -1.2973782201901264e-13, -0.9001624176421646, -0.0949468359066419, 0.09559891306642167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16585191868260477, -0.166910351023452, -0.19950316756912542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062160885408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05038109109233241, 0.43698377827011203, -0.2062769560467902, -0.1500000000030303, -0.3026350678164349, -0.27680439306808935, 0.46963702328319196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21048551165906207, -0.25482878655505964, -0.23971490972753168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487662466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.31494306862365334, 0.05799606090481324, 0.894309668489206, 8.61057110298199e-13, -0.9601299340954177, -0.09453775310295114, 0.16799619471528346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17608811233572796, -0.12024619855726101, -0.19960253405524014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1909006693655404, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06480739276910497, 0.4390182074893643, -0.16374552838281367, -0.15000000000310118, -0.352635067796133, -0.28165835998037597, 0.48107232232329783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21985108412303236, -0.2585072145199832, -0.2496990110867917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044866273417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28852603353545125, 0.04068858438504559, 0.8506285532795304, -1.4178771870427743e-12, -0.9999999995939625, -0.0970793382457321, 0.2287059808021172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18731144927940593, -0.07356855929847182, -0.19968202718520056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071712154568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0778639865331052, 0.4403986943985648, -0.12341388476288026, -0.15000000000342525, -0.40263506778443214, -0.28661976031327846, 0.4947352979582852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22971747857223404, -0.2602663301864443, -0.2596862921686938]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879894287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2611318752800045, 0.027609738184010073, 0.8066328723986682, -6.481603995935989e-12, -0.9999999997659831, -0.09922800665805001, 0.2732595126997477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1973278889840334, -0.03518231332922182, -0.19974562163804244]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076487878388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08960632613335213, 0.4412786820272664, -0.08518470788416493, -0.15000000000342903, -0.45263506778363916, -0.29165174474811223, 0.5100567329315848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24003079304811664, -0.2604512344466754, -0.26967611703273203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044855235719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2348467920049388, 0.017599752574031128, 0.7645835375743064, -7.556952870580749e-14, -0.9999999999841401, -0.10063968869667546, 0.30642869946599255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626628951765177, -0.00369808520462251, -0.19979649728076374]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081263595057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10012538049733546, 0.4417707391744566, -0.048900642422342884, -0.15000000002090327, -0.502635058468305, -0.2967397921520137, 0.5266874660851547, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2507430585638294, -0.25934918989534483, -0.2796679768159551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044856666147, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21038108727966653, 0.009841142943803444, 0.7256813092364408, -3.494851173489374e-10, -0.9999998136933174, -0.10176094807802873, 0.33261466307139687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21424531031425448, 0.02204089102661109, -0.19983719566446229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1883008603919477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10954847526776193, 0.4419571883966162, -0.014367997310744396, -0.1500000000211803, -0.5526350580449824, -0.301882594912368, 0.5443458263067931, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26180919034589345, -0.25720781352688615, -0.2896614646336549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880057178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18846189540852917, 0.0037289844431916365, 0.6906529022319696, -5.540833742186225e-12, -0.9999999915335459, -0.10285605520708724, 0.3531672044327671, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22132263564128063, 0.04282752736917327, -0.1998697563539953]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090814794783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1179706381381946, 0.4418935075813233, 0.016964069596627884, -0.15000000002149855, -0.6011411559440306, -0.3069730171706668, 0.562211777117165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2731800344558688, -0.2542627868713367, -0.29965625483496033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879997514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684432574086534, -0.0012736163058581565, 0.6266413381474456, -6.365140340883624e-12, -0.9701219579809645, -0.10180844516597544, 0.3573190162074384, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2274168821995075, 0.05890053311098942, -0.19989580402610851]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095590393237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12525915448078667, 0.441634097401911, 0.04134555911688437, -0.15000000002160307, -0.6444033522273456, -0.311744073252931, 0.5787944038885866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28481413906839403, -0.2507023858354849, -0.3096520869762748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880308914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14577032685184171, -0.005188203588245912, 0.48762979040512955, -2.0907089903838952e-12, -0.8652439256662979, -0.09542112164528489, 0.3316525354284317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2326820922505048, 0.0712080207170367, -0.19991664282628832]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100365980284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1313513205464919, 0.44124386808255134, 0.05502647125002504, -0.1500000000215953, -0.6786716468949271, -0.3159972693498794, 0.5932267019823172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.296676588895923, -0.24667702213022927, -0.31964875268938886]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488259057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12184332131410458, -0.007804586387193758, 0.27361824266281354, 1.551690204954065e-13, -0.6853658933516314, -0.08506392193896672, 0.28864596187461183, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2372489965505798, 0.08050727410511217, -0.19993331426228184]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18570105288280192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.136339795663082, 0.44078078485635436, 0.05678283755996691, -0.15000000002383843, -0.7001960410986275, -0.31967707647770316, 0.6054562781240743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3087380042495055, -0.24230687045644275, -0.3296460832366151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999015540018491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09976950233180201, -0.009261664523939889, 0.035127326198837294, -4.4862169923335214e-11, -0.4304878840740096, -0.073596142556476, 0.24459152283514315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24122830707164972, 0.08740303347573053, -0.1999466109445247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1850511006577185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1403739775991099, 0.4402826726247442, 0.04822745343402488, -0.1500000000248627, -0.7070023962496585, -0.3227923508163898, 0.615743208675111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32097365668102484, -0.23768794898686268, -0.3396439476590971]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044501668429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08068363872055852, -0.00996224463220329, -0.17110768251884048, -2.048503143121075e-11, -0.13612710302062075, -0.06230548677373299, 0.2057386110207331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2447130486303871, 0.09237842939160111, -0.1999572884496409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18440114841725014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14361877299200565, 0.43976236018285114, 0.030859130217651836, -0.15000000007348846, -0.7014558226299935, -0.325386575019998, 0.6244399697182978, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3333623537966084, -0.23289685232547214, -0.34964223930107513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044809367193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06489590785791459, -0.010406248837861082, -0.347366464327461, -9.725154651936012e-10, 0.11093147239330017, -0.05188448407216407, 0.17393522086373578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24777394231167094, 0.09582193322781084, -0.1999658328395606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1837511961730274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14627042200302473, 0.4392113408282703, 0.006404764233721889, -0.15000000007347383, -0.6860884467169129, -0.32756334470320386, 0.6319844357652927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34588706173631506, -0.22799509062665366, -0.35964087261484745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884454658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05303298022038146, -0.011020387091616967, -0.489087319678599, 2.9241916106869966e-13, 0.30734751826161155, -0.04353539366411645, 0.1508893209398978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25049415879413317, 0.09803523397636962, -0.19997266627544694]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1831012439345092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14862707827098026, 0.43860818028500903, -0.02173736102535413, -0.15000000014852674, -0.6646502246800632, -0.3295430435189884, 0.6391345243792194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3585326942824072, -0.22303158384386015, -0.3696397804257587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904477036431, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04713312535911083, -0.012063210865225656, -0.5628425051815203, -1.5010581625509328e-09, 0.42876444073699455, -0.039593976315690504, 0.14300177227853184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25291265092184284, 0.09927013565586996, -0.19997815621822487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18245129169918597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15098847092079548, 0.4379392198459649, -0.04981810865727518, -0.15000000026691218, -0.640891128792935, -0.3315558760481963, 0.6466499899032134, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37128685024476943, -0.21804557905289973, -0.379638908852616]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044706464295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04722785299630441, -0.013379208780883091, -0.561614952638421, -2.3677085608208317e-09, 0.4751819177425639, -0.04025665058415828, 0.1503093104798807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25508311924724514, 0.09972009581920824, -0.19998256853714594]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1818013394551751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15361201681855424, 0.43720934477050205, -0.07408748067813539, -0.1500000002671049, -0.6185611590246747, -0.3337869304114391, 0.6551798549509213, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3841390359567358, -0.2130684844543532, -0.3896382065770143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880217258, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05247091795517526, -0.014597501509257033, -0.4853874404172041, -3.854006702048701e-12, 0.4465993953652055, -0.0446210872648559, 0.17059730095415865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2570437142393276, 0.09954189197093079, -0.1999859544879673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18115138721169452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15662255869767946, 0.4364369383321497, -0.0920694808987948, -0.15000000027445468, -0.6014103142061942, -0.3362952775264959, 0.6649603634477795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.397080345227432, -0.20812544943908332, -0.39963753810742575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869611545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.060210837582504284, -0.015448128767046605, -0.3596400044131882, -1.469960216966954e-10, 0.34301689636960914, -0.05016694230113629, 0.19561016993716446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2588261854139236, 0.09886070030539758, -0.19998663060822866]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1805014350126715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16008291407614098, 0.4356489459658702, -0.10314522137853752, -0.15000000032117652, -0.5931885821525483, -0.33908849694302806, 0.6760465483809904, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4101032854431277, -0.2032366709928696, -0.4096370032096144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043980460383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0692071075692303, -0.0157598473255898, -0.22151480959485437, -9.344371551251991e-10, 0.16443464107291708, -0.05586438833064317, 0.22172369866421882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2604588043139138, 0.09777556892427441, -0.19998930204377258]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1798514827691054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16401294489847063, 0.4348714362378778, -0.10753469435180923, -0.15000000032734015, -0.5975871337098351, -0.34215296203903756, 0.6883404490796959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42320155524855735, -0.19841840351592052, -0.41963654416424745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044871322005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0786006164465928, -0.015550194559849573, -0.08778945946543423, -1.2327224208445614e-10, -0.08797103114573582, -0.06128930192019008, 0.2458780139741103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26196539610859304, 0.09636534953898135, -0.1999908190926619]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920153096651503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16842268819552575, 0.43412433950386115, -0.1055752963965853, -0.15000000033161018, -0.6125025899562251, -0.34549028722149383, 0.7016691044491477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4363694132846129, -0.19368356624971556, -0.42963617662216164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999036051807536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08819486594110235, -0.014941934680332796, 0.03918795910447867, -8.540031090567923e-11, -0.2983091249278011, -0.06674650364912567, 0.2665731073890347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2633571607211105, 0.0946967453240995, -0.1999926491582839]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17855157872250568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17331802755472506, 0.4334179287139158, -0.0975812186810684, -0.15000000033179423, -0.6361821365552746, -0.34911534860963317, 0.7158289013827932, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4496018800625285, -0.18904253417637906, -0.43963580915140527]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880187185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09790678718398627, -0.014128215798906118, 0.15988155431033824, -3.6808962678137926e-12, -0.4735909319809897, -0.07250122776278717, 0.28319593867291154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2646493355583121, 0.09282064146672975, -0.19999265058487298]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1779016264791473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17869609412867896, 0.43275193474447343, -0.08392009559487104, -0.15000000034070904, -0.667125762956517, -0.3530451215191956, 0.7305939301272426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46289473446551743, -0.18450371494238038, -0.449635500706733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044867167265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10756133147907815, -0.013319879388847785, 0.27322246172394715, -1.7829622625670783e-10, -0.6188725280248493, -0.07859545819124866, 0.2953005748889871, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2658570880597793, 0.09077638467997386, -0.19999383110655497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17725167440045553, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.18453115721617097, 0.43211523433246785, -0.06524891141117733, -0.15000000034465547, -0.7038806581320318, -0.35727900048734473, 0.7456873303840093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4762442785668876, -0.18007389979051477, -0.4596351940869579]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999041573835425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11670126174984043, -0.012734008240111524, 0.37342368367387413, -7.892855084053905e-11, -0.7350979035102958, -0.08467757936298281, 0.30186800513533224, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2669908820274035, 0.08859630303731199, -0.1999938676044979]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17660172216076417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19079802755817085, 0.4314907022762652, -0.04215205093421874, -0.15000000034476055, -0.7452845739857905, -0.3618144847762589, 0.7608675803120775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48964721418125357, -0.17575857342243134, -0.46963488782734575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044793826978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12533740683999753, -0.012490641124053342, 0.4619372095391718, -2.1019064209754778e-12, -0.8280783170751729, -0.09070968577828255, 0.30360499856136425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2680587122873189, 0.08630652736166854, -0.19999387480775682]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517699244491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19745101062421855, 0.4308566390532984, -0.015492942956834833, -0.15000000034476255, -0.7900402369587985, -0.3666237761353134, 0.77586579024628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5031005933238065, -0.17156218657241754, -0.47963458157272865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044726300965, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13305966132095415, -0.012681264459336034, 0.5331821595476781, -4.0180088471313993e-14, -0.8951132594601598, -0.09618582718108987, 0.2999641986840513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26906758285105886, 0.08392773700027627, -0.19999387490765777]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181768817774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20429869235524203, 0.43018921136363203, 0.011561347760489393, -0.15000000034476443, -0.8343976472426254, -0.37152096901653797, 0.7900397479780699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5166017544224925, -0.16748836223703867, -0.4896342753243602]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044725427596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13695363462046975, -0.013348553793327129, 0.5410858143464845, -3.7792526309170664e-14, -0.8871482056765386, -0.09794385762449165, 0.28347915463579826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27002322197371964, 0.08147648670757757, -0.19999387503263136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1746518654441957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21106084470780176, 0.4294803101746147, 0.0352608928338347, -0.15000000034517985, -0.8746068060921408, -0.37619829009713696, 0.8026129679991686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5301482652130773, -0.16354005805248029, -0.4996339690953167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879640693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13524304705119453, -0.014178023780347321, 0.473990901466906, -8.30845163949667e-12, -0.8041831769903062, -0.09354642161197935, 0.2514644004219742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27093021581169674, 0.07896608369116766, -0.19999387541912966]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019132011054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21749362887568768, 0.42874615824902884, 0.05185571625630446, -0.15000000035758476, -0.9069177194520512, -0.38035397080865707, 0.8130482911599413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5437378890087027, -0.1597197019726948, -0.5096336628697844]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044861806194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12865568335771865, -0.014683038511717254, 0.33189646844939513, -2.4809823421677747e-10, -0.6462182671982093, -0.0831136142304018, 0.20870646321545439, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2717924759125063, 0.07640712159570982, -0.1999938754893533]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335196100720662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22347858144976765, 0.4280164038517146, 0.057595844541327545, -0.15000000035872857, -0.9275803879420003, -0.38380293119513265, 0.8212329860775145, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.55736854367625, -0.1560292951668711, -0.5196333570732884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043877975163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11969905148159951, -0.014595087946284972, 0.11480256570046177, -2.287588752736056e-11, -0.4132533697989808, -0.06897920772951133, 0.16369389835146378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.272613093350947, 0.07380813611647408, -0.19999388407008045]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17270200876325248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22903896123748255, 0.4273127643816033, 0.05281121453470389, -0.15000000035912384, -0.9337932462575385, -0.38651038616964434, 0.8274220686663509, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5710384625195986, -0.15247060578652985, -0.5296330516281241]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879083075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11120759575429769, -0.014072789402225436, -0.09569260013247319, -7.90507323970248e-12, -0.12425716631076489, -0.054149099490233436, 0.12378165177672848, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2733983768669711, 0.0711737876068251, -0.19999389109671545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205657711464, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23424798762539437, 0.42664004522457366, 0.03911764779982529, -0.15000000037087663, -0.9278394097171462, -0.388504668153933, 0.8319573036278338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5847456086236841, -0.1490449097966328, -0.5396327464411657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043722756851, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10418052775823633, -0.013454383140593051, -0.273871334697572, -2.3505569851564733e-10, 0.11907673080784495, -0.03988563968577311, 0.090704699229657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2741429220817115, 0.0685139197979413, -0.19999389626082975]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.171402104293002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23923205457061464, 0.4259849324500342, 0.018436482219367036, -0.15000000038710556, -0.9121962383179879, -0.38989717997876316, 0.8352322850001218, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5984882262442217, -0.14575337320288173, -0.5496324508246603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045682252472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09968133890440528, -0.013102255490789031, -0.413623311609165, -3.2457882062231604e-10, 0.3128634279831657, -0.027850236496603883, 0.06549962744575973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27485235241075223, 0.06583073187502111, -0.19999408766989268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1707521520575697, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24422583156991662, 0.42532246530660345, -0.00555031856739973, -0.15000000039537445, -0.8906137167302688, -0.39094491140178245, 0.8378212028767753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6122646120201827, -0.14259697251217773, -0.5596321903973148]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044708646441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09987553998603985, -0.013249342868614945, -0.47973601573533525, -1.6537752932253542e-10, 0.43165043175438333, -0.020954628460386107, 0.0517783575330693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27552771551922034, 0.0631280138140797, -0.19999479145309051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1701021998135605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24946920468951667, 0.42463385227151207, -0.0290929572713701, -0.1500000003954848, -0.8668418448440921, -0.391918157720855, 0.8402813655859216, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6260731200792969, -0.1395765383470203, -0.5696319299797198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880183804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10486746239200077, -0.013772260701827965, -0.4708527740794074, -2.2072549929455032e-12, 0.4754374377235345, -0.019464926381450327, 0.04920325418292578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2761701611822855, 0.06040868330314855, -0.19999479164810025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16945224757237884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.25516944595905977, 0.4239162479926318, -0.04844312282407755, -0.15000000043275608, -0.8446306110731324, -0.3930446651772077, 0.8431031605815192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6399121558868406, -0.1366927854017676, -0.5796316852796015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044823633524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11400482539086217, -0.014352085577606042, -0.387003311054149, -7.454253047135546e-10, 0.44422467541919314, -0.022530149127054505, 0.056435899911953635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27678071615087274, 0.057675058905053825, -0.19999510599763426]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1688022953287255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26148853125727184, 0.4231836791111797, -0.060789854106602766, -0.15000000043759532, -0.8277300140474624, -0.3944924301177664, 0.8466983395970097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6537801601809091, -0.13394633015859936, -0.5896314532712005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044873066662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12638170596424136, -0.01465137762904124, -0.24693462565050434, -9.678469925604596e-11, 0.3380119405133998, -0.028955298811174205, 0.07190358030980874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2773600858813717, 0.05492910486336483, -0.19999535983197894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16815234297802745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2684807220246036, 0.4224558112324561, -0.06527087640309061, -0.15000000044036302, -0.8198900525499863, -0.39630701670632307, 0.8512295378511465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6676756117913564, -0.13133771393422394, -0.5996312235102744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999047013961484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13984381534663498, -0.01455735757447166, -0.08962044592975674, -5.5353837964381035e-11, 0.15679922994952317, -0.03629173177113289, 0.09062396508273715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2779090322089457, 0.05217232448750808, -0.19999540478147848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16750239073409937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27614697321489, 0.42174948917047583, -0.06193103118282252, -0.15000000044160214, -0.8245069658850457, -0.39848145497101634, 0.8567077699898648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6815969967026524, -0.1288673997502389, -0.6096309937908481]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878561702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15332502380572785, -0.014126441239606031, 0.06679690440536179, -2.4782191290981817e-11, -0.09233826670118767, -0.043488765293864876, 0.10956464277436537, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27842769822592073, 0.049406283679700846, -0.19999540561147325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1668524384899788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2844465507766662, 0.4210712187078201, -0.051505170525520734, -0.15000000044159464, -0.8394566359819176, -0.40097652166045167, 0.8629874285847511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6955429647403144, -0.1265358978511637, -0.6196308100153683]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882411426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16599155123552348, -0.013565409253114235, 0.20851721314603572, 1.4991957751880736e-13, -0.29899340193743756, -0.04990133378870636, 0.12559317189772634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2789193607532412, 0.04663003798150395, -0.19999632449040627]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16620248624597564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2933122644070877, 0.420415030496474, -0.03515432002112065, -0.1500000004418532, -0.8626926246928943, -0.4037341684422625, 0.8698200492138377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7095119089558011, -0.1243434784644009, -0.6296306274970043]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880063123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17731427260842994, -0.0131237642269218, 0.32701701008800155, -5.170628356396471e-12, -0.4647197742195341, -0.05515293563621632, 0.13665241258173166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27937888430973296, 0.04384838773525608, -0.1999963496327175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16555253391705643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3026181788739974, 0.41976420895689087, -0.014978721143549367, -0.1500000004418538, -0.891460497569343, -0.4066365402930106, 0.8768026569294196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.723502369979279, -0.12229046517566407, -0.6396304449791188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046578384271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18611828933819452, -0.013016430791661975, 0.40351197755142554, -1.2462032528120356e-14, -0.5753574575289726, -0.05804743701496184, 0.13965215431163894, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2798092204695588, 0.04106026577473655, -0.19999634964229177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16490258171661942, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3121654776012759, 0.41910003045659716, 0.005768785606304252, -0.1500000010063125, -0.922012071867307, -0.4094790751062277, 0.8833874117322497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7375128954617187, -0.12037714548959577, -0.6496302625646709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044008740433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19094597454556977, -0.01328357000587474, 0.41495013499707234, -1.1289173866109095e-08, -0.6110314859592819, -0.05685069626434171, 0.13169509605660054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2802105096487961, 0.03826639372136595, -0.19999635171104427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16425262949838296, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3217501446312281, 0.4184137763516962, 0.023756242031074543, -0.15000000100699085, -0.9505973482429387, -0.4120344603183687, 0.889079025091563, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7515420490451525, -0.11860378060434715, -0.6596300808050813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044364729578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19169334059904425, -0.01372508209801955, 0.3597491284954058, -1.3566967215285644e-11, -0.5717055275126331, -0.051107704242819414, 0.11383226718626614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2805830716686754, 0.035467297704972534, -0.19999636480820776]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16360267725436375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3312160963493463, 0.4177101509579465, 0.036441879827668465, -0.1500000010070652, -0.9734663268738926, -0.4141099510282917, 0.8935656432049074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.765588387967712, -0.1169705968368372, -0.6696298990489231]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880384279, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1893190343623644, -0.01407250787499421, 0.2537127559318784, -1.4870587345468537e-12, -0.4573795726190772, -0.0415098141984595, 0.08973236226688744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28092677845118896, 0.032663675350198915, -0.1999963648768364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16295272503000652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34045122145829243, 0.41700320072593433, 0.04199829933138077, -0.1500000012604679, -0.98686937459093, -0.41554827645050274, 0.8966911639083539, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.779650480775944, -0.11547779865077691, -0.6796297173345924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044487144661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18470250217892253, -0.014139004640243704, 0.11112839007424605, -5.0680535637459815e-09, -0.2680609543407494, -0.028766508444221496, 0.0625104140689295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2812418561646397, 0.029855963721205997, -0.19999636571338647]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1623027728560306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34940779051471443, 0.4163070350890156, 0.03963894085804336, -0.15000000216132275, -0.9887506532601159, -0.4162627949531472, 0.8984580034112469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7937269090741327, -0.11412555641960652, -0.6896295357220649]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043479518585, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17913138112844024, -0.013923312738374397, -0.04718716946674814, -1.8017097340678524e-08, -0.03762557338371636, -0.014290370052889648, 0.03533679005785974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2815285659637734, 0.027044844623407754, -0.19999636774944918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1616528206248878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3581518793422042, 0.41562502524976, 0.03040854207971421, -0.1500000023266479, -0.9811168629168205, -0.41630805453785746, 0.8990774586984458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8078162020289991, -0.11291408594252392, -0.6996293542013194]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044622855765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17488177654979614, -0.013640196785111983, -0.18460797556658298, -3.3065028712482224e-09, 0.15267580686590637, -0.000905191694204931, 0.012389105743977936, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2817858590973277, 0.02422940954165209, -0.19999636958509107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16100286860474192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.36683814399089076, 0.41494932978245186, 0.016791047158609428, -0.15000000233139915, -0.9672604094286987, -0.4158573868782251, 0.8988949537723698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8219169783238547, -0.11184347849608633, -0.7096291726825542]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999040402917607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1737252929737304, -0.0135139093461632, -0.27234989842209567, -9.502527628821921e-11, 0.27712906976243656, 0.009013353192647712, -0.0036500985215188533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2820155258971129, 0.021412148928751623, -0.1999963696246956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16035291636084198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.37565199692650764, 0.4142681915220035, 0.0017704865311310557, -0.15000000233297325, -0.9509312760383858, -0.4151295764964091, 0.8982852091036574, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8360278130418554, -0.11091386318945841, -0.7196290871132098]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877998677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17627705871233754, -0.01362276520896731, -0.30041121254956743, -3.148181310187109e-11, 0.32658266780625916, 0.01455620763632064, -0.012194893374249496, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2822166943600131, 0.01859230613255855, -0.19999828861311156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597029641054135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38477356728157597, 0.413573864833353, -0.011751701041473297, -0.15000000233447416, -0.9358684895014033, -0.414339180377886, 0.8976053179857624, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8501472410013078, -0.11012540169420493, -0.7296290015439164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045108569954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18243140710136713, -0.013886533773010225, -0.27044375145208704, -3.001811950312277e-11, 0.3012557307396483, 0.01580792237046159, -0.013597822357900403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.282388559189048, 0.015769229905069737, -0.19999828861413183]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15905301186612078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3943368375518594, 0.4128662350367365, -0.0216176214153116, -0.15000000239470182, -0.9246739086281888, -0.41364298228573787, 0.8971290144816123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8642738498644776, -0.10947816784407297, -0.7396289159888139]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044785854006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1912654054056681, -0.014152595932330626, -0.19731840747676604, -1.2045532684839895e-09, 0.2238916174642921, 0.013923961842962605, -0.009526070083000996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2825321772633965, 0.012944677002639349, -0.1999982888979484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15840305962283643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4044110203318332, 0.41215062586806545, -0.02671711065464472, -0.1500000024040879, -0.9186368863218698, -0.4131173882028494, 0.8970071123576946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8784062257347984, -0.10897222992276581, -0.7496288304344958]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044865686753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20148365559947534, -0.014312183373420013, -0.10198978478666233, -1.877212490486867e-10, 0.12074044612637919, 0.010511881657769598, -0.002438042478354072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2826475174064151, 0.010118758426143043, -0.1999982889136382]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1577531073795327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4150009398790707, 0.41143282726694963, -0.026980896743165308, -0.15000000241320874, -0.9178303362352256, -0.41276157757055115, 0.8972580567428706, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8925429552865868, -0.10860763845610524, -0.7596287448809615]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044866074807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2117983909447511, -0.014355972022315864, -0.005275721770411815, -1.8241671742023178e-10, 0.016131001732883385, 0.007116212645965018, 0.005018887703520919, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28273459103576676, 0.0072918293332112916, -0.19999828892931584]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1571031552310847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42606057332026326, 0.41071544382001746, -0.023162411784850838, -0.1500000024172626, -0.9213909734385273, -0.41251651291158736, 0.897786530768351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9066826395283155, -0.10838444412318145, -0.7696286593278352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999042968959765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22119266882385127, -0.01434766893864394, 0.07636969916628941, -8.107725467604547e-11, -0.07121274406603273, 0.004901293179276219, 0.0105694805096089, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28279368483457484, 0.0044638866584759684, -0.19999828893747326]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15645320299499907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4375125887474659, 0.4099971824867863, -0.01651819588450112, -0.1500000025175087, -0.9278917672140191, -0.41228946009830386, 0.8984228252051683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9208239241721221, -0.10830259038966102, -0.7796285737965195]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044721712429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22904030854405294, -0.014365226664622758, 0.13288431800699432, -2.004921525197925e-09, -0.13001587550983743, 0.00454105626567, 0.012725888736344181, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28282569287613213, 0.001637074670408717, -0.1999982893736866]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15580325075262905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4492691490475536, 0.40927445246525385, -0.008478541292157178, -0.1500000025383453, -0.9357159754064021, -0.411976559107681, 0.8989690144961375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9349653347446999, -0.10836216460543051, -0.7896284882699679]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044847400273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23513120600175405, -0.014454600430649008, 0.16079309184687887, -4.1673232323514666e-10, -0.15648416384765856, 0.006258019812457218, 0.010923785819384938, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28282821145155623, -0.001191484315389929, -0.19999828946896772]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1551532985148693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46076131544665866, 0.40901940151850263, -0.0006917309894316666, -0.1500000026006494, -0.9424039884510108, -0.4128829364921251, 0.8984783134747968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9490961824832114, -0.10857105562200238, -0.7995380570906596]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044755194974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22984332798210136, -0.005101018935023901, 0.15573620605451022, -1.2460820955087846e-09, -0.13376026089217463, -0.01812754768888189, -0.009814020426814092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2826169547702303, -0.004177820331437487, -0.19819137641383358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555145238280864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47096715224414104, 0.4106079014453873, 0.005696702386158525, -0.15177230053417393, -0.947791859057749, -0.414470402709686, 0.8979476120693357, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9623315073122183, -0.10889833642320842, -0.8087322802605562]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007224506264341943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20411673594964805, 0.031769998537693356, 0.12776866751180382, -0.035445958670490066, -0.1077574121347639, -0.03174932435121752, -0.010614028109221452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647064965801379, -0.006545616024120793, -0.18388446339793205]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559622285363817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.47935611938647094, 0.4135600558680854, 0.01039157724486683, -0.15507830959517818, -0.9521240364140472, -0.4161240576463237, 0.897959088412057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9737875128557731, -0.10928345774917339, -0.8165861577807516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00895409416590626, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1677793428465979, 0.059043088453962486, 0.09389749717416611, -0.06612018122008523, -0.0866435471259647, -0.0330730987327541, 0.00022952685442462033, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22912011087109677, -0.007702426519299421, -0.15707755040390856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15626972429192462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.48583971617289884, 0.4170186538535224, 0.013574255442026166, -0.15907263807012129, -0.9556288292022793, -0.41753373643148595, 0.89858277425084, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9825816991430995, -0.10964764272810736, -0.8225806362586835]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006149915110858642, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12967193572855762, 0.06917195970873892, 0.06365356394318669, -0.0798865694988621, -0.07009585576464157, -0.02819357570324453, 0.012473716775659595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17588372574652622, -0.00728369957867929, -0.11988956955863715]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15646031271119484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.49062116893678387, 0.42033676314481344, 0.015578696220181416, -0.16303111141273574, -0.9584747093524285, -0.41861206895941794, 0.8996635203797246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9883718736968895, -0.10969375634680667, -0.8269125185940361]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000" - }, - "execution_count": 9, - "metadata": {}, - "output_type": "execute_result" + "ename": "AssertionError", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[7], line 21\u001B[0m\n\u001B[1;32m 18\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 19\u001B[0m \u001B[38;5;66;03m# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\u001B[39;00m\n\u001B[1;32m 20\u001B[0m \u001B[38;5;66;03m# gs.add_default_end_motion_conditions()\u001B[39;00m\n\u001B[0;32m---> 21\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m \u001B[38;5;241m1\u001B[39m\n", + "\u001B[0;31mAssertionError\u001B[0m: " + ] } ], "source": [ @@ -243,9 +197,9 @@ "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01,\n", " orientation_threshold=0.01)\n", "gs.monitors.add_end_motion(pose_monitor)\n", - "# in the case that there is nos specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum\n", + "# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\n", "# gs.add_default_end_motion_conditions()\n", - "gs.execute()" + "assert gs.execute().error.code == GiskardError.SUCCESS" ], "metadata": { "collapsed": false, @@ -268,17 +222,8 @@ }, { "cell_type": "code", - "execution_count": 10, - "outputs": [ - { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995224128082, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.003749999998426497, 0.0037500000000161406, -0.0037499999999998975, -0.14999999999982933, 0.0009726135623061073, -0.10000999999993533, 0.003749999999999878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092529551367, -0.0006253905029042516, -0.0006250000000005031]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825616084, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999996852993, 0.07500000000009105, -0.07499999999999783, 3.413413898528338e-12, 0.019452271246122144, 1.2934985057206626e-12, 0.07499999999999801, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492185059102733, -0.012507810058085031, -0.012500000000000719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999044865274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.010874000462810094, 0.014999999121785897, -0.014999999999929904, -0.15000000000052507, 0.00249685109396703, -0.10001000000022002, 0.014999999999935657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.002494915898464792, -0.0025050721386444116, -0.002499999999906253]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044904931787, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1424800092876719, 0.2249999824353951, -0.22499999999860015, -1.3914817577019912e-11, 0.030484750633218455, -5.693777305049226e-12, 0.22499999999871556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0374061329101931, -0.0375936327148032, -0.0374999999999795]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985673060278, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.019214385627334598, 0.03214772656204189, -0.03562499999935418, -0.15000000000054162, 0.004003912303603865, -0.10001000000023216, 0.03562499999940766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005911945269440533, -0.005962921582434169, -0.005937499999840859]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881507441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1668077032904901, 0.3429545488051197, -0.4124999999884855, -3.3086328286054907e-13, 0.030141224192736706, -2.427690312094603e-13, 0.4124999999894401, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06834058741951482, -0.06915698887579515, -0.06874999999869214]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2025998089745868, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.027332611693070694, 0.05225635205961038, -0.06406249999670444, -0.15000000000063227, 0.00509351329647851, -0.1000100000002995, 0.06406249999708183, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010600654477185504, -0.010752838725563377, -0.010677083330842652]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487968028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.16236452131472193, 0.40217250995136977, -0.5687499999470049, -1.8132440942715141e-12, 0.021792019857492892, -1.3466319672723584e-12, 0.5687499999534835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09377418415489941, -0.09579834286258415, -0.09479166662003588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2032497612186043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.03465601580721158, 0.07338202302242261, -0.09881249999420641, -0.15000000000064317, 0.005562151157030444, -0.10001000000030755, 0.09881249999494346, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016296158549235513, -0.016639097200595834, -0.016468749995204174]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880350157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1464680822828177, 0.4225134192562447, -0.6949999999500392, -2.1797790610805456e-13, 0.009372757211038677, -1.6105727900585533e-13, 0.6949999999572325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11391008144100016, -0.11772516950064911, -0.1158333332872304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134620561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04107639227844112, 0.09452901507328197, -0.13861249997290648, -0.15000000000198216, 0.005347532109568132, -0.10001000000140058, 0.13861249995264174, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022774491634322096, -0.023423890671478025, -0.023102083324553664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869035943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.12840752942459085, 0.42293984101718723, -0.7959999995740012, -2.677979323697273e-11, -0.004292380949246234, -2.1860605853446573e-11, 0.7959999991539658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12956666170173162, -0.1356958694176438, -0.1326666665869898]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966570582583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.04666118591631699, 0.11525153479943673, -0.18245249994872562, -0.15000000000228894, 0.004470968152595306, -0.10001000000169422, 0.18245249991166518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029855627973834894, -0.030949331744835305, -0.030408749986253168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044875394872, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.11169587275751738, 0.4144503945230952, -0.8767999995163827, -6.1357932112318646e-12, -0.01753127913945652, -5.8727073376287276e-12, 0.8767999991804688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14162272679025595, -0.1505088214671456, -0.1461333332339901]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961794978372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05152178527779883, 0.1353647889149822, -0.22952449992876367, -0.15000000000234268, 0.0029953253590808606, -0.10001000000174005, 0.2295244998783314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03739517881513101, -0.03908896828573813, -0.0382540833152034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879157857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.09721198722963685, 0.402265082310909, -0.9414399996007609, -1.0748467169952566e-12, -0.029512855870288908, -9.167461066347978e-13, 0.9414399993333245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15079101682592239, -0.16279273081805654, -0.15690666657900465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966648689288, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05576265608289525, 0.15399602312200017, -0.2791820999128309, -0.1500000000017874, 0.0010285471017613223, -0.10001000000065693, 0.2791820998517253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04527752908108162, -0.047741235841549406, -0.04653034997789501]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999029257817154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08481741610192829, 0.3726246841403596, -0.9931519996813443, 1.1105360308673324e-11, -0.039335565146390764, 2.166230133870735e-11, 0.993151999467878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15764700531901213, -0.17304535111622546, -0.16552533325383217]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20389971424308817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05942678249747326, 0.17116549308609977, -0.32918212496676713, -0.15000000000206704, -0.001336658350849851, -0.10001000000106844, 0.3291820998507171, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05341021492784108, -0.05682436098581435, -0.055151363307386986]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044876094263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07328252829156022, 0.3433893992819922, -1.0000005010787243, -5.592900813623596e-12, -0.04730410905222346, -8.230135473705073e-12, 0.9999999999798355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16265371693518918, -0.1816625028852989, -0.1724202665898396]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976199901068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06254927332067894, 0.18720822280178823, -0.3791821500200128, -0.15000000000220307, -0.0040210550792610135, -0.10001000000208868, 0.3791820998487869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.061719348735855044, -0.06627236474911988, -0.06404817396991841]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488154993, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.062449816464113767, 0.32085459431376934, -1.000000501064914, -2.720657585222056e-12, -0.053687934568223246, -2.0404835988778344e-11, 0.9999999999613957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16618267616027926, -0.18896007526611042, -0.17793621325062856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980975502256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06530334246783995, 0.20274448077030074, -0.42918217507376827, -0.150000000002362, -0.006981139353238399, -0.10169702523622634, 0.42918209984579514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07014591555267684, -0.07603190914626919, -0.07316562249855446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879762176, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05508138294321995, 0.31072515937025036, -1.0000005010751092, -3.178670627095961e-12, -0.059201685479547704, -0.03374050468275326, 0.9999999999401649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16853133633643577, -0.1951908879429861, -0.18234897057272118]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985751100356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06790328523509014, 0.21824311964802745, -0.47918220012370066, -0.1500000000023791, -0.010200549301847222, -0.10666265915696402, 0.479182099845268, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07864278700313587, -0.0860597960924229, -0.0824595813214565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880380298, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05199885534500379, 0.30997277755453384, -1.0000005009986477, -3.419628306111715e-13, -0.06438819897217644, -0.09931267841475351, 0.9999999999894567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1699374290091808, -0.20055773892307413, -0.18587917645804092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2012999052667752, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0698257236356248, 0.23421513254549522, -0.525432225169826, -0.1500000000023803, -0.017429254760860668, -0.1153266305046296, 0.5257753718839405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08717232125632797, -0.09632097536722978, -0.09189474837977776]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884567195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.038448768010693184, 0.31944025794935554, -0.9250005009225063, -2.4558949901505577e-14, -0.14457410918026892, -0.17327942695331155, 0.9318654407734511, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17059068506384195, -0.20522358549613762, -0.18870334116642523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995302277, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07072955470746402, 0.2508652922059786, -0.5641822502121976, -0.1500000000023839, -0.024917259070361825, -0.12713418211536878, 0.5652119159618963, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09570443891067591, -0.10678695264977467, -0.10144288202640352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880103793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018076621436784384, 0.3330031932096672, -0.7750005008474314, -7.163789731263766e-14, -0.1497600861900231, -0.23615103221478356, 0.7887308815591166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17064235308695888, -0.20931954565089778, -0.19096267293251507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2000000007787679, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.07051671251909349, 0.268156085445879, -0.5916822752530768, -0.15000000000252947, -0.030483560079777795, -0.1410550519159715, 0.5937417320800253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10421508353998447, -0.11743451382759128, -0.11108138894132084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880041834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004256843767410735, 0.3458158647980082, -0.5500005008175851, -2.9113963874629762e-12, -0.11132602018831939, -0.2784173960120548, 0.5705963223625797, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17021289258617123, -0.21295122355633223, -0.19277013829834663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935004853499577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06914440590006907, 0.2860034411792493, -0.6041823002928683, -0.1500000000025775, -0.034551304873879134, -0.15604040622717463, 0.6076148202386424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11268499205073444, -0.12824470059199697, -0.12079219447249467]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875442563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027446132380488278, 0.3569471146674063, -0.2500005007958297, -9.603601719665634e-13, -0.08135489588202678, -0.2997070862240625, 0.2774617631723428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16939817021499945, -0.21620373528811399, -0.1942161106234766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009629126512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06662506364786523, 0.3043069196152068, -0.6033489878269833, -0.15000000000261468, -0.0377013785949796, -0.17129104770331385, 0.6079257270381646, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12109871381632487, -0.1392019864674616, -0.1305608388964588]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044874612967, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0503868450440767, 0.3660695687191493, 0.016666249317699444, -7.435904150903004e-13, -0.0630014744220093, -0.3050128295227844, 0.006218135990444407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1682744353118084, -0.21914571750929274, -0.19537288847928289]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980501440472577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.06301180850687928, 0.3229607227779738, -0.5914045607766345, -0.15000000000275565, -0.0404202259926186, -0.18633468310182805, 0.5969348160408071, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12944382915393812, -0.15029361321615042, -0.14037575443354122]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880148077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07226510281971905, 0.37307606325533976, 0.23888854100697743, -2.8192075957799583e-12, -0.05437694795278004, -0.300872707970284, -0.21981821994715087, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16690230675226528, -0.22183253497377647, -0.19629831074164802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019180376744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05835369809320081, 0.3418781576483917, -0.5702008715717964, -0.15000000000280575, -0.042984091717350646, -0.2009783937928531, 0.5765257235469713, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1377103272166334, -0.16150905591226594, -0.1502276868616847]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869805191, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0931622082735693, 0.37834869740835814, 0.42407378409676216, -1.0021247626099497e-12, -0.05127731449464091, -0.2928742138205009, -0.40818184987671735, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1653299612539053, -0.2243088539223104, -0.19703864856286932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023955960436, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.05283808113905355, 0.3608647472264093, -0.541281130567749, -0.15000000000280686, -0.049142975769148396, -0.2151847073040153, 0.5504484495566567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14589011117262793, -0.17283959141676142, -0.1601092328042018]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044883261575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11031233908294522, 0.37973179156035275, 0.5783948200809502, -2.2256829060496475e-14, -0.12317768103595497, -0.28412627022324377, -0.5215454798062913, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16359567911989042, -0.22661071008990966, -0.19763091885034242]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028731554044, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.0468828881752113, 0.37881810371212465, -0.5083953377571927, -0.15000000000280925, -0.05955011904709216, -0.22854789099420542, 0.5224529940698626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1539766048967487, -0.18427795010648435, -0.17001446955819063]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044881278357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11910385927684494, 0.3590671297143069, 0.6577158562111252, -4.777915898499416e-14, -0.20814286555887532, -0.26726367380380267, -0.559909109735883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16172987448241521, -0.2287671737944585, -0.19810473507977652]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033507151394, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.039489176492562186, 0.39434308050261524, -0.47401288993818014, -0.15000000000280894, -0.07605884905722497, -0.24014598372470913, 0.49628935708658883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1619644405443123, -0.19581803469267806, -0.17993865896138403]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880529788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1478742336529823, 0.31049953580981204, 0.6876489563802516, 6.001150630434665e-15, -0.3301746002026562, -0.23196185461007457, -0.5232727396654748, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597567129512723, -0.23080169172387394, -0.19848378806386788]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19480038282762216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.02912803671121529, 0.40700369900793454, -0.4347193541259278, -0.15000000000282587, -0.10106612406230406, -0.24950232708356584, 0.47570753856798886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16984921049433546, -0.2074546931553055, -0.1898780104834433]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487783569, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2072227956269379, 0.25321237010638586, 0.785870716245046, -3.383971651076609e-13, -0.5001455001015817, -0.1871268671771344, -0.4116363703719989, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15769539900046325, -0.23273316925254883, -0.19878703044118534]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415043058362855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, -0.015160346642552938, 0.41691035843029217, -0.39128452547647374, -0.15000000000282784, -0.13178511024205766, -0.256619368591889, 0.4624542279061011, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17762727049736116, -0.2191835353580724, -0.19982949170094993]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879871994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27935380137324706, 0.19813318844715294, 0.8686965729890815, -3.967496378540561e-14, -0.6143797235950719, -0.1423408301664627, -0.26506621323775525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555612000605141, -0.23457684405533777, -0.19902962435013272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1935004783396239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0010544919765346963, 0.4244440260482049, -0.34478616097160525, -0.15000000000306368, -0.16836029912447867, -0.2623223432269921, 0.45640264438867295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18542523778181494, -0.2303918611023138, -0.20979067667094325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880092969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.32429677238175264, 0.1506733523582546, 0.92996729009737, -4.717020045662648e-12, -0.7315037776484199, -0.11405949270206249, -0.12103167034856235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15595934568907588, -0.22416651488482797, -0.19922369939986634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052609584238, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.017990172499795433, 0.43002769747145114, -0.29745313055942657, -0.15000000000306685, -0.20962045022955575, -0.2673301636176097, 0.45645726789410673, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19338851010814545, -0.240470959076024, -0.2197596246463134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875630292, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3387136104652147, 0.11167342846492416, 0.9466606082435739, -6.305298277255488e-14, -0.8252030221015414, -0.1001564078123521, 0.0010924701086751226, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15926544652661026, -0.20158195947420426, -0.1993789595074029]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057385268532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.034633937661149736, 0.43408397522487135, -0.2509924394712505, -0.15000000000307334, -0.254628571111664, -0.2720775054129418, 0.4612372135474278, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20168110604227568, -0.2488164766271966, -0.22973478302476968]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904486314135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3328753032270861, 0.08112555506840465, 0.929213821763521, -1.2973782201901264e-13, -0.9001624176421646, -0.0949468359066419, 0.09559891306642167, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16585191868260477, -0.166910351023452, -0.19950316756912542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062160885408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05038109109233241, 0.43698377827011203, -0.2062769560467902, -0.1500000000030303, -0.3026350678164349, -0.27680439306808935, 0.46963702328319196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21048551165906207, -0.25482878655505964, -0.23971490972753168]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904487662466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.31494306862365334, 0.05799606090481324, 0.894309668489206, 8.61057110298199e-13, -0.9601299340954177, -0.09453775310295114, 0.16799619471528346, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17608811233572796, -0.12024619855726101, -0.19960253405524014]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1909006693655404, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06480739276910497, 0.4390182074893643, -0.16374552838281367, -0.15000000000310118, -0.352635067796133, -0.28165835998037597, 0.48107232232329783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21985108412303236, -0.2585072145199832, -0.2496990110867917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044866273417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28852603353545125, 0.04068858438504559, 0.8506285532795304, -1.4178771870427743e-12, -0.9999999995939625, -0.0970793382457321, 0.2287059808021172, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18731144927940593, -0.07356855929847182, -0.19968202718520056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071712154568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0778639865331052, 0.4403986943985648, -0.12341388476288026, -0.15000000000342525, -0.40263506778443214, -0.28661976031327846, 0.4947352979582852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22971747857223404, -0.2602663301864443, -0.2596862921686938]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879894287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2611318752800045, 0.027609738184010073, 0.8066328723986682, -6.481603995935989e-12, -0.9999999997659831, -0.09922800665805001, 0.2732595126997477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1973278889840334, -0.03518231332922182, -0.19974562163804244]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076487878388, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08960632613335213, 0.4412786820272664, -0.08518470788416493, -0.15000000000342903, -0.45263506778363916, -0.29165174474811223, 0.5100567329315848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24003079304811664, -0.2604512344466754, -0.26967611703273203]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044855235719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2348467920049388, 0.017599752574031128, 0.7645835375743064, -7.556952870580749e-14, -0.9999999999841401, -0.10063968869667546, 0.30642869946599255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626628951765177, -0.00369808520462251, -0.19979649728076374]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081263595057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10012538049733546, 0.4417707391744566, -0.048900642422342884, -0.15000000002090327, -0.502635058468305, -0.2967397921520137, 0.5266874660851547, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2507430585638294, -0.25934918989534483, -0.2796679768159551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044856666147, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21038108727966653, 0.009841142943803444, 0.7256813092364408, -3.494851173489374e-10, -0.9999998136933174, -0.10176094807802873, 0.33261466307139687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21424531031425448, 0.02204089102661109, -0.19983719566446229]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1883008603919477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10954847526776193, 0.4419571883966162, -0.014367997310744396, -0.1500000000211803, -0.5526350580449824, -0.301882594912368, 0.5443458263067931, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26180919034589345, -0.25720781352688615, -0.2896614646336549]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880057178, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18846189540852917, 0.0037289844431916365, 0.6906529022319696, -5.540833742186225e-12, -0.9999999915335459, -0.10285605520708724, 0.3531672044327671, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22132263564128063, 0.04282752736917327, -0.1998697563539953]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090814794783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1179706381381946, 0.4418935075813233, 0.016964069596627884, -0.15000000002149855, -0.6011411559440306, -0.3069730171706668, 0.562211777117165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2731800344558688, -0.2542627868713367, -0.29965625483496033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879997514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684432574086534, -0.0012736163058581565, 0.6266413381474456, -6.365140340883624e-12, -0.9701219579809645, -0.10180844516597544, 0.3573190162074384, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2274168821995075, 0.05890053311098942, -0.19989580402610851]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095590393237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12525915448078667, 0.441634097401911, 0.04134555911688437, -0.15000000002160307, -0.6444033522273456, -0.311744073252931, 0.5787944038885866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28481413906839403, -0.2507023858354849, -0.3096520869762748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880308914, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14577032685184171, -0.005188203588245912, 0.48762979040512955, -2.0907089903838952e-12, -0.8652439256662979, -0.09542112164528489, 0.3316525354284317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2326820922505048, 0.0712080207170367, -0.19991664282628832]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100365980284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1313513205464919, 0.44124386808255134, 0.05502647125002504, -0.1500000000215953, -0.6786716468949271, -0.3159972693498794, 0.5932267019823172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.296676588895923, -0.24667702213022927, -0.31964875268938886]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488259057, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12184332131410458, -0.007804586387193758, 0.27361824266281354, 1.551690204954065e-13, -0.6853658933516314, -0.08506392193896672, 0.28864596187461183, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2372489965505798, 0.08050727410511217, -0.19993331426228184]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18570105288280192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.136339795663082, 0.44078078485635436, 0.05678283755996691, -0.15000000002383843, -0.7001960410986275, -0.31967707647770316, 0.6054562781240743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3087380042495055, -0.24230687045644275, -0.3296460832366151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999015540018491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09976950233180201, -0.009261664523939889, 0.035127326198837294, -4.4862169923335214e-11, -0.4304878840740096, -0.073596142556476, 0.24459152283514315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24122830707164972, 0.08740303347573053, -0.1999466109445247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1850511006577185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1403739775991099, 0.4402826726247442, 0.04822745343402488, -0.1500000000248627, -0.7070023962496585, -0.3227923508163898, 0.615743208675111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32097365668102484, -0.23768794898686268, -0.3396439476590971]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044501668429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08068363872055852, -0.00996224463220329, -0.17110768251884048, -2.048503143121075e-11, -0.13612710302062075, -0.06230548677373299, 0.2057386110207331, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2447130486303871, 0.09237842939160111, -0.1999572884496409]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18440114841725014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14361877299200565, 0.43976236018285114, 0.030859130217651836, -0.15000000007348846, -0.7014558226299935, -0.325386575019998, 0.6244399697182978, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3333623537966084, -0.23289685232547214, -0.34964223930107513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044809367193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06489590785791459, -0.010406248837861082, -0.347366464327461, -9.725154651936012e-10, 0.11093147239330017, -0.05188448407216407, 0.17393522086373578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24777394231167094, 0.09582193322781084, -0.1999658328395606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1837511961730274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14627042200302473, 0.4392113408282703, 0.006404764233721889, -0.15000000007347383, -0.6860884467169129, -0.32756334470320386, 0.6319844357652927, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34588706173631506, -0.22799509062665366, -0.35964087261484745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884454658, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05303298022038146, -0.011020387091616967, -0.489087319678599, 2.9241916106869966e-13, 0.30734751826161155, -0.04353539366411645, 0.1508893209398978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25049415879413317, 0.09803523397636962, -0.19997266627544694]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1831012439345092, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14862707827098026, 0.43860818028500903, -0.02173736102535413, -0.15000000014852674, -0.6646502246800632, -0.3295430435189884, 0.6391345243792194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3585326942824072, -0.22303158384386015, -0.3696397804257587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904477036431, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04713312535911083, -0.012063210865225656, -0.5628425051815203, -1.5010581625509328e-09, 0.42876444073699455, -0.039593976315690504, 0.14300177227853184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25291265092184284, 0.09927013565586996, -0.19997815621822487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18245129169918597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15098847092079548, 0.4379392198459649, -0.04981810865727518, -0.15000000026691218, -0.640891128792935, -0.3315558760481963, 0.6466499899032134, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37128685024476943, -0.21804557905289973, -0.379638908852616]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044706464295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04722785299630441, -0.013379208780883091, -0.561614952638421, -2.3677085608208317e-09, 0.4751819177425639, -0.04025665058415828, 0.1503093104798807, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25508311924724514, 0.09972009581920824, -0.19998256853714594]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1818013394551751, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15361201681855424, 0.43720934477050205, -0.07408748067813539, -0.1500000002671049, -0.6185611590246747, -0.3337869304114391, 0.6551798549509213, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3841390359567358, -0.2130684844543532, -0.3896382065770143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880217258, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05247091795517526, -0.014597501509257033, -0.4853874404172041, -3.854006702048701e-12, 0.4465993953652055, -0.0446210872648559, 0.17059730095415865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2570437142393276, 0.09954189197093079, -0.1999859544879673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18115138721169452, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.15662255869767946, 0.4364369383321497, -0.0920694808987948, -0.15000000027445468, -0.6014103142061942, -0.3362952775264959, 0.6649603634477795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.397080345227432, -0.20812544943908332, -0.39963753810742575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044869611545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.060210837582504284, -0.015448128767046605, -0.3596400044131882, -1.469960216966954e-10, 0.34301689636960914, -0.05016694230113629, 0.19561016993716446, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2588261854139236, 0.09886070030539758, -0.19998663060822866]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1805014350126715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16008291407614098, 0.4356489459658702, -0.10314522137853752, -0.15000000032117652, -0.5931885821525483, -0.33908849694302806, 0.6760465483809904, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4101032854431277, -0.2032366709928696, -0.4096370032096144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043980460383, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0692071075692303, -0.0157598473255898, -0.22151480959485437, -9.344371551251991e-10, 0.16443464107291708, -0.05586438833064317, 0.22172369866421882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2604588043139138, 0.09777556892427441, -0.19998930204377258]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1798514827691054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16401294489847063, 0.4348714362378778, -0.10753469435180923, -0.15000000032734015, -0.5975871337098351, -0.34215296203903756, 0.6883404490796959, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42320155524855735, -0.19841840351592052, -0.41963654416424745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044871322005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0786006164465928, -0.015550194559849573, -0.08778945946543423, -1.2327224208445614e-10, -0.08797103114573582, -0.06128930192019008, 0.2458780139741103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26196539610859304, 0.09636534953898135, -0.1999908190926619]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920153096651503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16842268819552575, 0.43412433950386115, -0.1055752963965853, -0.15000000033161018, -0.6125025899562251, -0.34549028722149383, 0.7016691044491477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4363694132846129, -0.19368356624971556, -0.42963617662216164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999036051807536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08819486594110235, -0.014941934680332796, 0.03918795910447867, -8.540031090567923e-11, -0.2983091249278011, -0.06674650364912567, 0.2665731073890347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2633571607211105, 0.0946967453240995, -0.1999926491582839]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17855157872250568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17331802755472506, 0.4334179287139158, -0.0975812186810684, -0.15000000033179423, -0.6361821365552746, -0.34911534860963317, 0.7158289013827932, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4496018800625285, -0.18904253417637906, -0.43963580915140527]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880187185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09790678718398627, -0.014128215798906118, 0.15988155431033824, -3.6808962678137926e-12, -0.4735909319809897, -0.07250122776278717, 0.28319593867291154, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2646493355583121, 0.09282064146672975, -0.19999265058487298]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1779016264791473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.17869609412867896, 0.43275193474447343, -0.08392009559487104, -0.15000000034070904, -0.667125762956517, -0.3530451215191956, 0.7305939301272426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46289473446551743, -0.18450371494238038, -0.449635500706733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044867167265, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10756133147907815, -0.013319879388847785, 0.27322246172394715, -1.7829622625670783e-10, -0.6188725280248493, -0.07859545819124866, 0.2953005748889871, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2658570880597793, 0.09077638467997386, -0.19999383110655497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17725167440045553, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.18453115721617097, 0.43211523433246785, -0.06524891141117733, -0.15000000034465547, -0.7038806581320318, -0.35727900048734473, 0.7456873303840093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4762442785668876, -0.18007389979051477, -0.4596351940869579]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999041573835425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11670126174984043, -0.012734008240111524, 0.37342368367387413, -7.892855084053905e-11, -0.7350979035102958, -0.08467757936298281, 0.30186800513533224, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2669908820274035, 0.08859630303731199, -0.1999938676044979]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17660172216076417, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19079802755817085, 0.4314907022762652, -0.04215205093421874, -0.15000000034476055, -0.7452845739857905, -0.3618144847762589, 0.7608675803120775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48964721418125357, -0.17575857342243134, -0.46963488782734575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044793826978, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12533740683999753, -0.012490641124053342, 0.4619372095391718, -2.1019064209754778e-12, -0.8280783170751729, -0.09070968577828255, 0.30360499856136425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2680587122873189, 0.08630652736166854, -0.19999387480775682]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517699244491, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.19745101062421855, 0.4308566390532984, -0.015492942956834833, -0.15000000034476255, -0.7900402369587985, -0.3666237761353134, 0.77586579024628, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5031005933238065, -0.17156218657241754, -0.47963458157272865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044726300965, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13305966132095415, -0.012681264459336034, 0.5331821595476781, -4.0180088471313993e-14, -0.8951132594601598, -0.09618582718108987, 0.2999641986840513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26906758285105886, 0.08392773700027627, -0.19999387490765777]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181768817774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20429869235524203, 0.43018921136363203, 0.011561347760489393, -0.15000000034476443, -0.8343976472426254, -0.37152096901653797, 0.7900397479780699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5166017544224925, -0.16748836223703867, -0.4896342753243602]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044725427596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13695363462046975, -0.013348553793327129, 0.5410858143464845, -3.7792526309170664e-14, -0.8871482056765386, -0.09794385762449165, 0.28347915463579826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27002322197371964, 0.08147648670757757, -0.19999387503263136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1746518654441957, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21106084470780176, 0.4294803101746147, 0.0352608928338347, -0.15000000034517985, -0.8746068060921408, -0.37619829009713696, 0.8026129679991686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5301482652130773, -0.16354005805248029, -0.4996339690953167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879640693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13524304705119453, -0.014178023780347321, 0.473990901466906, -8.30845163949667e-12, -0.8041831769903062, -0.09354642161197935, 0.2514644004219742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27093021581169674, 0.07896608369116766, -0.19999387541912966]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019132011054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.21749362887568768, 0.42874615824902884, 0.05185571625630446, -0.15000000035758476, -0.9069177194520512, -0.38035397080865707, 0.8130482911599413, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5437378890087027, -0.1597197019726948, -0.5096336628697844]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044861806194, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12865568335771865, -0.014683038511717254, 0.33189646844939513, -2.4809823421677747e-10, -0.6462182671982093, -0.0831136142304018, 0.20870646321545439, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2717924759125063, 0.07640712159570982, -0.1999938754893533]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335196100720662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22347858144976765, 0.4280164038517146, 0.057595844541327545, -0.15000000035872857, -0.9275803879420003, -0.38380293119513265, 0.8212329860775145, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.55736854367625, -0.1560292951668711, -0.5196333570732884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043877975163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11969905148159951, -0.014595087946284972, 0.11480256570046177, -2.287588752736056e-11, -0.4132533697989808, -0.06897920772951133, 0.16369389835146378, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.272613093350947, 0.07380813611647408, -0.19999388407008045]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17270200876325248, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22903896123748255, 0.4273127643816033, 0.05281121453470389, -0.15000000035912384, -0.9337932462575385, -0.38651038616964434, 0.8274220686663509, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5710384625195986, -0.15247060578652985, -0.5296330516281241]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879083075, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11120759575429769, -0.014072789402225436, -0.09569260013247319, -7.90507323970248e-12, -0.12425716631076489, -0.054149099490233436, 0.12378165177672848, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2733983768669711, 0.0711737876068251, -0.19999389109671545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205657711464, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23424798762539437, 0.42664004522457366, 0.03911764779982529, -0.15000000037087663, -0.9278394097171462, -0.388504668153933, 0.8319573036278338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5847456086236841, -0.1490449097966328, -0.5396327464411657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043722756851, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10418052775823633, -0.013454383140593051, -0.273871334697572, -2.3505569851564733e-10, 0.11907673080784495, -0.03988563968577311, 0.090704699229657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2741429220817115, 0.0685139197979413, -0.19999389626082975]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.171402104293002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.23923205457061464, 0.4259849324500342, 0.018436482219367036, -0.15000000038710556, -0.9121962383179879, -0.38989717997876316, 0.8352322850001218, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5984882262442217, -0.14575337320288173, -0.5496324508246603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045682252472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09968133890440528, -0.013102255490789031, -0.413623311609165, -3.2457882062231604e-10, 0.3128634279831657, -0.027850236496603883, 0.06549962744575973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27485235241075223, 0.06583073187502111, -0.19999408766989268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1707521520575697, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24422583156991662, 0.42532246530660345, -0.00555031856739973, -0.15000000039537445, -0.8906137167302688, -0.39094491140178245, 0.8378212028767753, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6122646120201827, -0.14259697251217773, -0.5596321903973148]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044708646441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09987553998603985, -0.013249342868614945, -0.47973601573533525, -1.6537752932253542e-10, 0.43165043175438333, -0.020954628460386107, 0.0517783575330693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27552771551922034, 0.0631280138140797, -0.19999479145309051]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1701021998135605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24946920468951667, 0.42463385227151207, -0.0290929572713701, -0.1500000003954848, -0.8668418448440921, -0.391918157720855, 0.8402813655859216, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6260731200792969, -0.1395765383470203, -0.5696319299797198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880183804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10486746239200077, -0.013772260701827965, -0.4708527740794074, -2.2072549929455032e-12, 0.4754374377235345, -0.019464926381450327, 0.04920325418292578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2761701611822855, 0.06040868330314855, -0.19999479164810025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16945224757237884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.25516944595905977, 0.4239162479926318, -0.04844312282407755, -0.15000000043275608, -0.8446306110731324, -0.3930446651772077, 0.8431031605815192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6399121558868406, -0.1366927854017676, -0.5796316852796015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044823633524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11400482539086217, -0.014352085577606042, -0.387003311054149, -7.454253047135546e-10, 0.44422467541919314, -0.022530149127054505, 0.056435899911953635, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27678071615087274, 0.057675058905053825, -0.19999510599763426]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1688022953287255, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.26148853125727184, 0.4231836791111797, -0.060789854106602766, -0.15000000043759532, -0.8277300140474624, -0.3944924301177664, 0.8466983395970097, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6537801601809091, -0.13394633015859936, -0.5896314532712005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044873066662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12638170596424136, -0.01465137762904124, -0.24693462565050434, -9.678469925604596e-11, 0.3380119405133998, -0.028955298811174205, 0.07190358030980874, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2773600858813717, 0.05492910486336483, -0.19999535983197894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16815234297802745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2684807220246036, 0.4224558112324561, -0.06527087640309061, -0.15000000044036302, -0.8198900525499863, -0.39630701670632307, 0.8512295378511465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6676756117913564, -0.13133771393422394, -0.5996312235102744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999047013961484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13984381534663498, -0.01455735757447166, -0.08962044592975674, -5.5353837964381035e-11, 0.15679922994952317, -0.03629173177113289, 0.09062396508273715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2779090322089457, 0.05217232448750808, -0.19999540478147848]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16750239073409937, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.27614697321489, 0.42174948917047583, -0.06193103118282252, -0.15000000044160214, -0.8245069658850457, -0.39848145497101634, 0.8567077699898648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6815969967026524, -0.1288673997502389, -0.6096309937908481]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878561702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15332502380572785, -0.014126441239606031, 0.06679690440536179, -2.4782191290981817e-11, -0.09233826670118767, -0.043488765293864876, 0.10956464277436537, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27842769822592073, 0.049406283679700846, -0.19999540561147325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1668524384899788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2844465507766662, 0.4210712187078201, -0.051505170525520734, -0.15000000044159464, -0.8394566359819176, -0.40097652166045167, 0.8629874285847511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6955429647403144, -0.1265358978511637, -0.6196308100153683]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882411426, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16599155123552348, -0.013565409253114235, 0.20851721314603572, 1.4991957751880736e-13, -0.29899340193743756, -0.04990133378870636, 0.12559317189772634, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2789193607532412, 0.04663003798150395, -0.19999632449040627]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16620248624597564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2933122644070877, 0.420415030496474, -0.03515432002112065, -0.1500000004418532, -0.8626926246928943, -0.4037341684422625, 0.8698200492138377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7095119089558011, -0.1243434784644009, -0.6296306274970043]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880063123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17731427260842994, -0.0131237642269218, 0.32701701008800155, -5.170628356396471e-12, -0.4647197742195341, -0.05515293563621632, 0.13665241258173166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.27937888430973296, 0.04384838773525608, -0.1999963496327175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16555253391705643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3026181788739974, 0.41976420895689087, -0.014978721143549367, -0.1500000004418538, -0.891460497569343, -0.4066365402930106, 0.8768026569294196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.723502369979279, -0.12229046517566407, -0.6396304449791188]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046578384271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18611828933819452, -0.013016430791661975, 0.40351197755142554, -1.2462032528120356e-14, -0.5753574575289726, -0.05804743701496184, 0.13965215431163894, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2798092204695588, 0.04106026577473655, -0.19999634964229177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16490258171661942, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3121654776012759, 0.41910003045659716, 0.005768785606304252, -0.1500000010063125, -0.922012071867307, -0.4094790751062277, 0.8833874117322497, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7375128954617187, -0.12037714548959577, -0.6496302625646709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044008740433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19094597454556977, -0.01328357000587474, 0.41495013499707234, -1.1289173866109095e-08, -0.6110314859592819, -0.05685069626434171, 0.13169509605660054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2802105096487961, 0.03826639372136595, -0.19999635171104427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16425262949838296, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3217501446312281, 0.4184137763516962, 0.023756242031074543, -0.15000000100699085, -0.9505973482429387, -0.4120344603183687, 0.889079025091563, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7515420490451525, -0.11860378060434715, -0.6596300808050813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044364729578, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19169334059904425, -0.01372508209801955, 0.3597491284954058, -1.3566967215285644e-11, -0.5717055275126331, -0.051107704242819414, 0.11383226718626614, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2805830716686754, 0.035467297704972534, -0.19999636480820776]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16360267725436375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3312160963493463, 0.4177101509579465, 0.036441879827668465, -0.1500000010070652, -0.9734663268738926, -0.4141099510282917, 0.8935656432049074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.765588387967712, -0.1169705968368372, -0.6696298990489231]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880384279, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1893190343623644, -0.01407250787499421, 0.2537127559318784, -1.4870587345468537e-12, -0.4573795726190772, -0.0415098141984595, 0.08973236226688744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.28092677845118896, 0.032663675350198915, -0.1999963648768364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16295272503000652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34045122145829243, 0.41700320072593433, 0.04199829933138077, -0.1500000012604679, -0.98686937459093, -0.41554827645050274, 0.8966911639083539, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.779650480775944, -0.11547779865077691, -0.6796297173345924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044487144661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18470250217892253, -0.014139004640243704, 0.11112839007424605, -5.0680535637459815e-09, -0.2680609543407494, -0.028766508444221496, 0.0625104140689295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2812418561646397, 0.029855963721205997, -0.19999636571338647]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1623027728560306, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.34940779051471443, 0.4163070350890156, 0.03963894085804336, -0.15000000216132275, -0.9887506532601159, -0.4162627949531472, 0.8984580034112469, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7937269090741327, -0.11412555641960652, -0.6896295357220649]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043479518585, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17913138112844024, -0.013923312738374397, -0.04718716946674814, -1.8017097340678524e-08, -0.03762557338371636, -0.014290370052889648, 0.03533679005785974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2815285659637734, 0.027044844623407754, -0.19999636774944918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1616528206248878, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3581518793422042, 0.41562502524976, 0.03040854207971421, -0.1500000023266479, -0.9811168629168205, -0.41630805453785746, 0.8990774586984458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8078162020289991, -0.11291408594252392, -0.6996293542013194]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044622855765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17488177654979614, -0.013640196785111983, -0.18460797556658298, -3.3065028712482224e-09, 0.15267580686590637, -0.000905191694204931, 0.012389105743977936, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2817858590973277, 0.02422940954165209, -0.19999636958509107]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16100286860474192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.36683814399089076, 0.41494932978245186, 0.016791047158609428, -0.15000000233139915, -0.9672604094286987, -0.4158573868782251, 0.8988949537723698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8219169783238547, -0.11184347849608633, -0.7096291726825542]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999040402917607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1737252929737304, -0.0135139093461632, -0.27234989842209567, -9.502527628821921e-11, 0.27712906976243656, 0.009013353192647712, -0.0036500985215188533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2820155258971129, 0.021412148928751623, -0.1999963696246956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16035291636084198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.37565199692650764, 0.4142681915220035, 0.0017704865311310557, -0.15000000233297325, -0.9509312760383858, -0.4151295764964091, 0.8982852091036574, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8360278130418554, -0.11091386318945841, -0.7196290871132098]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877998677, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17627705871233754, -0.01362276520896731, -0.30041121254956743, -3.148181310187109e-11, 0.32658266780625916, 0.01455620763632064, -0.012194893374249496, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2822166943600131, 0.01859230613255855, -0.19999828861311156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597029641054135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.38477356728157597, 0.413573864833353, -0.011751701041473297, -0.15000000233447416, -0.9358684895014033, -0.414339180377886, 0.8976053179857624, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8501472410013078, -0.11012540169420493, -0.7296290015439164]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045108569954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18243140710136713, -0.013886533773010225, -0.27044375145208704, -3.001811950312277e-11, 0.3012557307396483, 0.01580792237046159, -0.013597822357900403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.282388559189048, 0.015769229905069737, -0.19999828861413183]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15905301186612078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3943368375518594, 0.4128662350367365, -0.0216176214153116, -0.15000000239470182, -0.9246739086281888, -0.41364298228573787, 0.8971290144816123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8642738498644776, -0.10947816784407297, -0.7396289159888139]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044785854006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1912654054056681, -0.014152595932330626, -0.19731840747676604, -1.2045532684839895e-09, 0.2238916174642921, 0.013923961842962605, -0.009526070083000996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2825321772633965, 0.012944677002639349, -0.1999982888979484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15862762370758512, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.40336755535140295, 0.41340607693608517, -0.0281417745480004, -0.15056065624380852, -0.9158851234555722, -0.4147688123198622, 0.8954882412787241, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8777409739113674, -0.1091985760415698, -0.749003830450675]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00850776317071313, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1806143559908712, 0.010796837986974256, -0.130483062653776, -0.011213076982133769, 0.17577570345233196, -0.022516600682486506, -0.032815464057764435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26934248093779445, 0.005591836050063553, -0.18749828923722325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15866397467095064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41120634123183086, 0.41524304262477346, -0.032422882310377946, -0.15213246733544894, -0.9090773270695434, -0.4168751986923581, 0.8933873651445428, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8896595776911644, -0.10928316141749454, -0.7571287475162742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007270192673103013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15677571760855868, 0.03673931377376621, -0.08562215524755097, -0.03143622183280849, 0.13615592772057628, -0.04212772744991837, -0.0420175226836258, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2383720755959403, -0.001691707518494845, -0.1624983413119849]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1588003517278768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41757497128040044, 0.41779023609231675, -0.035314351568069974, -0.154423409678742, -0.9039497222098302, -0.4191124837784526, 0.8914320019333295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8991418356088946, -0.10970790054089162, -0.7635050977073535]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002727541138523093, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12737260097139155, 0.05094386935086524, -0.05782938515384049, -0.04581884686586117, 0.10255209719426467, -0.04474570172189043, -0.03910726422426541, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18964515835460338, -0.008494782467941539, -0.12752700382158688]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15891866914771227, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.422458909698806, 0.42044679063717627, -0.03738836557092126, -0.15692689937591378, -0.9002174207846231, -0.4210719777976021, 0.8899399717272123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9058713832796049, -0.11001163766274924, -0.7682529106805343]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023663483967094855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0976787683681114, 0.05313109089719014, -0.041480280057025795, -0.050069793943436025, 0.07464602850414166, -0.03918988038298938, -0.029840604122345193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1345909534142064, -0.0060747424371524195, -0.09495625946361337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15901219306706263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4260259400394143, 0.42284212067648425, -0.03898148106632429, -0.15928328389903323, -0.8975956193402806, -0.4226101795595985, 0.8889916251372522, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9102745008821276, -0.11009953125758494, -0.7716770084735937]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000" - }, - "execution_count": 10, - "metadata": {}, - "output_type": "execute_result" - } - ], + "execution_count": 8, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -302,7 +247,7 @@ "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01,\n", " orientation_threshold=0.01)\n", "gs.monitors.add_end_motion(pose_monitor)\n", - "gs.execute()" + "assert gs.execute().error.code == GiskardError.SUCCESS" ], "metadata": { "collapsed": false, @@ -339,17 +284,8 @@ }, { "cell_type": "code", - "execution_count": 9, - "outputs": [ - { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.0020876631136696375, 0.0037499998672351578, 0.00019471474162977202, -0.15000000164960314, 3.7829411969664335e-05, -0.10001000398503089, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006250370152481892, -5.90706498035983e-05, 0.0006249999081531167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04175326227339274, 0.07499999734470315, 0.00389429483259544, -3.299206281492319e-08, 0.0007565882393932866, -7.970061789824146e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012500740304963783, -0.001181412996071966, 0.012499998163062333]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.005748831451660165, 0.014999911625644522, 0.0005366000919809209, -0.15000051009817622, 0.00010427796097227672, -0.1000111677480421, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0025002804358226684, -0.00017499404359716932, 0.0024987303825485373]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07322336675981056, 0.2249982351681873, 0.006837707007022976, -1.0168971461347905e-05, 0.0013289709800522478, -2.3275260224123218e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03750486841148958, -0.0023184678758714204, 0.037474609487908414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.009904069007649525, 0.03379389126350592, 0.0009249277825230434, -0.15000051010562018, 0.0001797763760935028, -0.10001116776407216, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.00589700329790533, -0.0003103470634419895, 0.004996191433763215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08310475111978717, 0.3758795927572279, 0.007766553810842451, -1.4887912588198147e-10, 0.0015099683024245216, -3.2060128409347596e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06793445724165324, -0.002707060396896403, 0.04994922102429357]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.01410062444050083, 0.0563819722997141, 0.0013173267313473843, -0.15000051020939031, 0.00025609163336437734, -0.10001116958089652, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010486404953052475, -0.0004477889050711366, 0.00766949351826411]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08393110865702608, 0.4517616207241637, 0.007847978976486817, -2.075402794784519e-09, 0.0015263051454174907, -3.6336487175869836e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0917880331029429, -0.002748836832582941, 0.05346604169001788]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.01820611048639602, 0.07949476306340346, 0.0017012579197973536, -0.15000051080969784, 0.0003307879202235581, -0.10001117114225146, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016040133286662362, -0.0005840742347895849, 0.010328598224828007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08210972091790388, 0.46225581527378706, 0.007678623768999387, -1.2006150345894164e-08, 0.0014939257371836142, -3.122709877801651e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11107456667219773, -0.002725706594368965, 0.05318209413127793]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.02222160407768684, 0.10079384271814296, 0.002076568320432928, -0.15000052789849957, 0.0004038361678194121, -0.10001120125286588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.02238328361038687, -0.0007245170569926648, 0.012935934463477185]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08030987182581635, 0.42598159309478995, 0.007506208012711485, -3.417760347815328e-07, 0.0014609649519170802, -6.022122884723246e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12686300647449014, -0.0028088564440615976, 0.05214672477298358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.026154883590617434, 0.11849253658389435, 0.002443676973187925, -0.15000052809148837, 0.0004753127237887259, -0.10001120154644538, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029355405072700992, -0.0008730655023351766, 0.015479823080700755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07866559025861192, 0.3539738773150278, 0.0073421730550999355, -3.8597758651328375e-09, 0.0014295311193862764, -5.871590070862548e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13944242924628247, -0.002970968906850236, 0.0508777723444714]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.02998010712069136, 0.13160423318446376, 0.002799938707498612, -0.15000054469388538, 0.0005446926211230858, -0.10001122598160703, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.036782145831624376, -0.0010270064993040718, 0.017920996815444352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07650447060147852, 0.2622339320113881, 0.007125234686213743, -3.320479400429139e-07, 0.0013875979466871978, -4.887032327669745e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1485348151784677, -0.0030788199393779027, 0.048823474694871916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.03366475220547315, 0.14002453785059119, 0.0031422259854090103, -0.15000054489276568, 0.0006113572399642135, -0.10001122623890712, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04449709635323544, -0.001180769148041398, 0.020216490094773523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07369290169563586, 0.1684060933225482, 0.006845745558207968, -3.977606023993649e-09, 0.0013332923768225526, -5.146001912908356e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15429901043222133, -0.0030752529747465267, 0.04590986558658338]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.03719838560104596, 0.144182211038836, 0.0034695572139267694, -0.15000056813263796, 0.0006751094581425631, -0.10001125479342804, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0523366215352019, -0.0013325337044522941, 0.02235152988491964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07067266791145604, 0.08315346376489618, 0.006546624570355178, -4.6479744543194967e-07, 0.0012750443635669915, -5.710904181857254e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15679050363932925, -0.0030352911282179205, 0.04270079580292232]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.040588438496928794, 0.1447625993206287, 0.0037826722797508093, -0.15000106004769992, 0.0007360910530891141, -0.1000118404182472, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06018406121442206, -0.001483373465027545, 0.024333735555414654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06780105791765671, 0.011607765635854542, 0.0062623013164808, -9.838301239430676e-06, 0.0012196318989310198, -1.1712496383278903e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1569487935844032, -0.0030167952115050154, 0.03964411340990028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.04385419897749301, 0.14252076718587106, 0.004083446567852978, -0.15000118825626152, 0.00079466805741713, -0.10001199941485582, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06799119209285112, -0.0016359214961377082, 0.026185602914079162]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06531520961128422, -0.044836642695152897, 0.006015485762043373, -2.564171232208125e-06, 0.0011715400865603173, -3.1799321723204208e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1561426175685811, -0.0030509606222032656, 0.037037347173290186]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.04701995958635031, 0.13819763186467912, 0.004374245874515086, -0.15000127809192243, 0.0008513043820226777, -0.10001212265813088, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07575808814734845, -0.0017933469737392211, 0.027935965289999105]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06331521217714606, -0.08646270642383899, 0.0058159861332421564, -1.7967132180976775e-06, 0.0011327264921109537, -2.4648655010492274e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15533792108994673, -0.0031485095520302556, 0.03500724751839887]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.050109996950189896, 0.13248754523197742, 0.004657459986532812, -0.15000135611398183, 0.0009064703092848628, -0.10001224400721725, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08350877893487604, -0.0019587190318480245, 0.029613731024807924]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06180074727679177, -0.1142017326540339, 0.005664282240354523, -1.560441188040712e-06, 0.0011033185452437022, -2.426981727638467e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15501381575055181, -0.003307441162176063, 0.033555314696176376]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.05314551553911133, 0.12602405055979307, 0.004935218357751498, -0.15000142748032838, 0.0009605864805969355, -0.10001236103313897, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09127281082911505, -0.00213464255214284, 0.03124410269990247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.060710371778428654, -0.12926989344368683, 0.005555167424373715, -1.4273269309871063e-06, 0.0010823234262414532, -2.3405184343630722e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15528063788478005, -0.003518470405896308, 0.03260743350189086]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.056143126500881026, 0.11936771293944992, 0.005209243336760879, -0.15000150389115868, 0.0010139946562518771, -0.10001248116316473, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09907392535431646, -0.0023230648461933083, 0.032846725949708]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05995221923539391, -0.1331267524068629, 0.00548049958018763, -1.5282166062362677e-06, 0.0010681635130988325, -2.4026005152752026e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15602229050402822, -0.003768445881009365, 0.032052464996110586]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.05911445981327309, 0.11299150178103126, 0.005480802424147435, -0.15000150479512453, 0.0010669477536916746, -0.10001248248545974, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10692487944556332, -0.002525202585451863, 0.03443523037490541]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05942666624784121, -0.12752422316837325, 0.005431181747731117, -1.8079317000552607e-08, 0.0010590619487959496, -2.6445900230735512e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1570190818249372, -0.0040427547851711, 0.031770088503948135]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.062066632597567964, 0.10726599916336475, 0.005750735431581176, -0.15000150569347462, 0.0011196145403574596, -0.10001248372639389, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11482694147280874, -0.002741591129652345, 0.03601781006983567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05904345568589747, -0.11451005235333007, 0.005398660148674814, -1.7967001999891985e-08, 0.0010533357333157025, -2.4818682921246718e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15804124054490837, -0.004327770884009645, 0.03165159389860516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.06500323823486201, 0.10244980092596892, 0.0060195294129101505, -0.15000150673397622, 0.0011720937980546813, -0.10001248512057687, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12277257000221148, -0.002972219787345933, 0.037598421608252296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05873211274588096, -0.0963239647479166, 0.005375879626579483, -2.0810032242831352e-08, 0.0010495851539444334, -2.7883659592355694e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15891257058805494, -0.0046125731538717565, 0.03161223076833247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.06792555812652318, 0.09868905584532096, 0.00628741755669849, -0.1500016123604411, 0.0012244333790247207, -0.1000126276568153, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13074950943593966, -0.003216729678259439, 0.03917825314797849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.058446397833223335, -0.07521490161295905, 0.005357762875766789, -2.1125292978066464e-06, 0.0010467916194007902, -2.850724768721872e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1595387886745637, -0.004890197818270117, 0.031596630794523864]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07083367478634559, 0.0960269305807533, 0.006554474897015343, -0.1500017139107497, 0.0012766488578148613, -0.10001276717067617, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13874485715391177, -0.003474604929647466, 0.04075706853994019]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05816233319644805, -0.0532425052913533, 0.005341146806337053, -2.031006172216235e-06, 0.0010443095758028119, -2.790277217313188e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1599069543594422, -0.005157505027760538, 0.03157630783923401]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07372732439272076, 0.09442069071698626, 0.006820696164447082, -0.15000180303355806, 0.001328738860621185, -0.10001288854141732, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1467479276633926, -0.00374533832513258, 0.04233424517253666]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.057872992127503374, -0.03212479727534079, 0.005324425348634768, -1.7824561669068486e-06, 0.0010418000561264768, -2.427414823026788e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16006141018961662, -0.005414667909702285, 0.031543532651929336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07660640217247879, 0.09376274294577842, 0.007086046776707491, -0.15000188146490448, 0.0013806952456893464, -0.10001299367879939, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15475165440623598, -0.0040285337206670425, 0.043909390920544134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05758155559516072, -0.013158955424156734, 0.00530701224520818, -1.5686269281445476e-06, 0.0010391277013632272, -2.102747641271741e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16007453485686785, -0.0056639079106892525, 0.03150291496014951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.07947115546784388, 0.09390221879460182, 0.007350488443897669, -0.15000195632460775, 0.0014325083581940427, -0.10001309321923099, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1627526712145131, -0.004323943241541222, 0.04548257866520635]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.057295065907301865, 0.0027895169764679296, 0.005288833343803562, -1.4971940654482357e-06, 0.0010362622500939259, -1.9908086322269075e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16002033616554232, -0.005908190417483597, 0.03146375489324434]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.08232215831429435, 0.09466479339877282, 0.007613986401722041, -0.1500020323830217, 0.0014841686903628753, -0.10001319422620963, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17075052372531938, -0.004631453279187666, 0.04705431070070234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05702005692900939, 0.01525149208341989, 0.005269959156487428, -1.5211682789370048e-06, 0.0010332066433766528, -2.020139572724712e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15995705021612586, -0.0061502007529288675, 0.031434640709919734]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.08516017384368171, 0.09586957923283822, 0.007876506833521207, -0.15000211314403042, 0.0015356666042063629, -0.10001330203683399, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17874651719427476, -0.004951040721145524, 0.04862534308998595]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05676031058774722, 0.024095716681308096, 0.00525040863598331, -1.6152201744217732e-06, 0.0010299582768697518, -2.1562124871216715e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15991986937910774, -0.006391748839157157, 0.031420647785672294]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.08798599248589298, 0.09734270814796529, 0.008138011731836335, -0.15000220138697695, 0.0015869915326211055, -0.10001342115158829, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.186742605188359, -0.005282720520976461, 0.050196479146461005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.056516372844225254, 0.029462578302541467, 0.005230097966302567, -1.7648589307398148e-06, 0.0010264985682948513, -2.3822950860616985e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1599217598816847, -0.006633595996618754, 0.031422721129501056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09080030259900418, 0.09892759325096909, 0.008398455808033363, -0.1500022994425874, 0.0016381315616010787, -0.10001355576572014, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1947405627691917, -0.005626500516171323, 0.051768403311781494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.056286202262224076, 0.031697702060075855, 0.005208881523940577, -1.9611122088593767e-06, 0.0010228005795994656, -2.692282636989708e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15995915161665356, -0.006875599903897247, 0.0314384833064098]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09360361876015387, 0.10049200312613894, 0.00865778731131385, -0.1500024010574014, 0.0016890737563265408, -0.10001369561928782, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20274152876472634, -0.005982352661385059, 0.05334158807929443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05606632322299371, 0.03128819750339707, 0.005186630065609744, -2.032296280306048e-06, 0.0010188438945092403, -2.797071353327598e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16001931991069326, -0.007117042904274718, 0.031463695350258634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09639626774279439, 0.1019321465187894, 0.008915952413463893, -0.15000250323279554, 0.0017398051575173107, -0.10001383568140829, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2107458898040053, -0.006350202287427256, 0.054916274542256525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.055852979652810324, 0.028802867853009177, 0.005163302043000864, -2.0435078829855017e-06, 0.0010146280238153996, -2.8012424093048454e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600872207855793, -0.0073569925208439284, 0.03149372925924195]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.09917841710293, 0.10317404932740164, 0.00917290157888373, -0.15000260565919835, 0.001790314131360599, -0.10001397561361902, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21875340354721814, -0.006729932252852412, 0.056492507702740884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05564298720271227, 0.02483805617224464, 0.0051389833083967515, -2.0485280558458973e-06, 0.0010101794768657662, -2.798644214716896e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16015027486425687, -0.007594599308503119, 0.031524663209687165]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.10195012591569663, 0.10417261483113908, 0.009428596016540806, -0.15000270811669592, 0.0018405916939532405, -0.10001411522550832, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22676343982889113, -0.007121396377360576, 0.058070200708085454]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.055434176255332625, 0.019971310074748908, 0.0051138887531415175, -2.049149951576258e-06, 0.0010055512518528317, -2.79223778608895e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602007256334595, -0.007829282490163294, 0.03155386010689139]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.10471139871800485, 0.10490885952264604, 0.00968301262266311, -0.15000281046689043, 0.0018906324956189182, -0.10001425443557388, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2347752359528914, -0.007524435922369098, 0.05964920369459655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05522545604616425, 0.014724893830139283, 0.005088332122446073, -2.0470038903068266e-06, 0.0010008160333135538, -2.7842013110638597e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16023592248000548, -0.008060790900170433, 0.03158005973022196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.10746222948891189, 0.10538587556941209, 0.009936146494038864, -0.15000291263614787, 0.0019404352867358064, -0.10001439324360752, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24278809698318404, -0.007938894113816876, 0.061229360052086235]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05501661541814079, 0.00954032093532093, 0.00506267742751509, -2.0433851488248467e-06, 0.0009960558223377654, -2.7761606727253146e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16025722060585304, -0.008289163828955571, 0.03160312714979371]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11020262952693957, 0.10562406974997551, 0.01018801082078672, -0.15000301459049678, 0.0019900028339980857, -0.1000145316937579, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2508015110008898, -0.008364625799578364, 0.06281054189029536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.054808000760553637, 0.004763883611268485, 0.0050372865349571395, -2.0390869781037383e-06, 0.0009913509452455843, -2.7690030075937545e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602682803541154, -0.008514633715229772, 0.0316236367641825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11293263910242243, 0.1056561736197166, 0.010438634545635421, -0.15000311631227786, 0.0020393413724660125, -0.10001466984176427, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2588151814761437, -0.008801501478749588, 0.06439266432815272]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.054600191509657364, 0.0006420773948217738, 0.005012474496974011, -2.034435621507249e-06, 0.0009867707693585349, -2.7629601272238864e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027340950507718, -0.0087375135834245, 0.03164244875714719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11565232661690082, 0.10552242993791294, 0.010688058511064672, -0.1500032177831877, 0.0020884597457442662, -0.10001480773142808, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.26682899863348464, -0.009249406569056356, 0.06597568335662803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05439375028956773, -0.002674873636073163, 0.00498847930858501, -2.0294181966086833e-06, 0.0009823674655650772, -2.7577932761261993e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027634314681902, -0.008958101806135335, 0.03166038056950626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.11836178052850597, 0.10526625710164986, 0.010936330908741418, -0.15000331897616992, 0.002137368404785757, -0.10001494538288014, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2748429786823032, -0.009708237652476269, 0.06755958414850484]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05418907823210299, -0.005123456725261635, 0.004965447953534923, -2.023859644087188e-06, 0.0009781731808298146, -2.753029041045394e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027960097637037, -0.009176621668398268, 0.031678015837536336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1210610989938251, 0.10493059213367162, 0.01118350275716096, -0.15000341985480473, 0.0021860784171861005, -0.10001508279085179, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28285719706915874, -0.010177897593766385, 0.06914436638199215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05398636930638248, -0.0067132993595648074, 0.004943436968390851, -2.0175726963463243e-06, 0.000974200248006867, -2.7481594331319943e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16028436773711088, -0.009393198825802328, 0.031695644669746156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.12375038079690809, 0.10455502222364167, 0.011429623942267745, -0.1500035203779346, 0.002234600599319792, -0.1000152199302356, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2908717337874219, -0.010658291066705046, 0.07073003137889249]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.053785636061659696, -0.007511398200599033, 0.0049224237021357, -2.010462597635803e-06, 0.0009704436426738275, -2.742787676064544e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602907343652638, -0.009607869458773236, 0.03171329993800688]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.12642971942227485, 0.10417373820477834, 0.011674740134079896, -0.1500036205060456, 0.0022829448377889344, -0.10001535676470304, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2988866392571594, -0.011149321410316434, 0.07231657359768932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05358677250733544, -0.00762568037726677, 0.004902323836243018, -2.0025622198112902e-06, 0.0009668847693828508, -2.736689348874819e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16029810939474964, -0.009820606872227739, 0.031730844375936706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.12909920062064456, 0.1038142813062913, 0.011918890691698896, -0.15000372020677194, 0.0023311196248879695, -0.10001549325512123, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30690192120502396, -0.01165088910690919, 0.0739039769941741]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0533896239673944, -0.0071891379697407096, 0.004883011152379989, -1.994014526775476e-06, 0.0009634957419807043, -2.7298083638265085e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16030563895729083, -0.010031353931855115, 0.03174806792969542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13175890280009678, 0.10349700692651807, 0.012162107517795916, -0.15000381945822788, 0.0023791318009343887, -0.10001562936589996, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3149175477617597, -0.012162891684923644, 0.07549221536866349]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.053194043589044365, -0.006345487595464606, 0.004864336521940398, -1.985029118847568e-06, 0.0009602435209283887, -2.722215574728978e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031253113471383, -0.01024005156028909, 0.03176476748978784]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13440889911166298, 0.10323515578609144, 0.012404414729707488, -0.15000391824982176, 0.0024269864761138665, -0.1000157650685688, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3229334598600846, -0.012685224573635566, 0.07708125516054178]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05299992623132407, -0.005237022808532758, 0.004846144238231459, -1.975831877379156e-06, 0.0009570935035895583, -2.7140533767438286e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031824196649866, -0.010446657774238456, 0.03178079583756558]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13704926009105978, 0.10303540317611057, 0.012645828971454411, -0.15000401658088752, 0.0024746870948140175, -0.10001590034270395, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33094958634329213, -0.013217782369081704, 0.07867105911465036]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05280721958793577, -0.003995052199617488, 0.004828284834938473, -1.966621315383495e-06, 0.0009540123740030161, -2.705482703031077e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032252966415117, -0.010651155908922754, 0.0317960790821716]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.13968005599678643, 0.10289875007253549, 0.012886360185752323, -0.15000411445759593, 0.0025222356036181956, -0.10001603517448816, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33896585699866766, -0.013760460057138527, 0.08026158960804541]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05261591811453283, -0.0027330620715015548, 0.004810624285958224, -1.957534168241165e-06, 0.0009509701760835617, -2.6966356842751498e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032541310751044, -0.010853553761136453, 0.031810609867901005]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.14230135837292215, 0.10282162387553041, 0.013126012682208414, -0.15000421188955856, 0.0025696326871641126, -0.10001616955450232, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3469822110270512, -0.014313153906979549, 0.08185281095266303]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.052426047522714375, -0.0015425239401015232, 0.0047930499291218434, -1.948639252903821e-06, 0.0009479416709183389, -2.6876002832324993e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032708056767095, -0.01105387699682044, 0.031824426892352264]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.14491324072588432, 0.1027970690815313, 0.013364786364548426, -0.15000430888651767, 0.00261687804133027, -0.1000163034751356, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3549986005094158, -0.01487576192769053, 0.08344469048998202]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05223764705924334, -0.0004910958799823689, 0.004775473646800229, -1.939939182292898e-06, 0.0009449070833231465, -2.6784126655474985e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603277896472922, -0.011252160414219602, 0.031837590746379596]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.147515778459514, 0.10281592665069528, 0.013602678007255217, -0.15000440545603017, 0.0026639706589021745, -0.10001643692874143, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.36301498982583513, -0.015448183924631567, 0.08503719865508186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05205075467259349, 0.00037715138327953717, 0.0047578328541358185, -1.93139024968456e-06, 0.0009418523514380869, -2.6690721166780173e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032778632838668, -0.011448439938820741, 0.03185016330199672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.15010904833780306, 0.10286792259337411, 0.013839682496059753, -0.15000450149935324, 0.0027109091080382633, -0.10001656977631, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3710313526255033, -0.01603032127127016, 0.08663030836443807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05186539756578117, 0.001039918853576738, 0.00474008977609071, -1.9208664614119633e-06, 0.0009387689827217774, -2.6569513714093516e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160327255993363, -0.011642746932771885, 0.03186219418712418]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.15269312776344712, 0.10294260908181223, 0.014075793966906997, -0.15000459698000315, 0.002757691788370953, -0.10001670196043576, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37904766795765293, -0.016622076559047433, 0.08822399413825294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05168158851288156, 0.0014937297687621703, 0.004722229416944879, -1.9096129980630864e-06, 0.0009356536066537995, -2.6436825151918284e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032630664299236, -0.01183510575554544, 0.03187371547629732]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.15526809409616898, 0.10303012336622061, 0.014311006794281923, -0.15000469189564844, 0.002804317153345284, -0.10001683347076099, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.387063916788, -0.01722335324650534, 0.08981823126051386]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05149932665443709, 0.0017502856881675601, 0.004704256547498512, -1.8983129059466525e-06, 0.0009325072994866163, -2.630206504537499e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032497660694164, -0.012025533749158183, 0.031884742445218356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1578340241447835, 0.10312174956733564, 0.014545316394676069, -0.1500047862394967, 0.0028507838909023523, -0.10001696429444111, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.39508007958383323, -0.017834055389177036, 0.09141299516122561]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05131860097229048, 0.0018325240223005684, 0.004686192007882923, -1.8868769651933487e-06, 0.0009293347511413645, -2.6164736025186358e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603232559166643, -0.012214042853433896, 0.03189527801423514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.16039099387875008, 0.10321028513847601, 0.014778719825304428, -0.15000488000098455, 0.0028970910579823993, -0.10001709441650874, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.40309613514194387, -0.0184540874873721, 0.09300826108719261]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05113939467933149, 0.0017707114228074554, 0.004668068612567201, -1.8752297572542138e-06, 0.0009261433416009425, -2.6024413527010967e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16032111116221281, -0.012400641963901258, 0.031905318519339816]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.16293907833816565, 0.10329022693559496, 0.01501121617225754, -0.15000497316615874, 0.0029432381675868896, -0.10001722382012562, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4111120604695264, -0.019083354447213808, 0.0946040040322801]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05096168918831153, 0.0015988359423789796, 0.004649926939062258, -1.8633034837966203e-06, 0.0009229421920898092, -2.5880723375732797e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031850655165075, -0.01258533919683416, 0.03191485890174994]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1654783516844296, 0.10335780123988149, 0.01524280673576578, -0.15000506572064762, 0.002989225230216298, -0.10001735248807969, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.41912783134119036, -0.019721761624768727, 0.09620019884546158]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05078546692527899, 0.0013514860857304829, 0.004631811270164776, -1.8510897776065506e-06, 0.0009197412525881734, -2.573359081392818e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031541743327934, -0.012768143551098406, 0.03192389626362951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.16800888732471583, 0.10341086786448839, 0.015473495032315489, -0.1500051576494521, 0.0030350527542101075, -0.10001748040284295, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42714342313855763, -0.020369214913387158, 0.09779682042235331]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05061071280572483, 0.0010613324921380433, 0.004613765930994204, -1.8385760897522917e-06, 0.0009165504798761872, -2.5582952651828924e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16031183594734527, -0.012949065772368635, 0.03193243153783478]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1705307580532344, 0.10344873098540215, 0.015703286642976298, -0.15000524893733921, 0.0030807217116472054, -0.10001760754655847, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.43515881165343523, -0.02102562083799346, 0.0993938439001995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05043741457037101, 0.0007572624182753398, 0.004595832213216189, -1.8257577420423889e-06, 0.0009133791487419609, -2.5428743106810666e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603077702975522, -0.013128118492126098, 0.031940469556923756]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.17304403617171873, 0.10347188906398222, 0.015932188943755282, -0.1500053395695857, 0.0031262334778758864, -0.1000177339015863, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.44317397366458217, -0.02169088663127147, 0.10099124480537151]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.050265562369686774, 0.0004631615716014219, 0.0045780460155797, -1.8126449295723366e-06, 0.0009102353245736233, -2.5271005565511222e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1603032402229392, -0.01330531586556015, 0.0319480181034405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.17554879357212447, 0.10348175376545704, 0.016160210756716153, -0.15000542953208593, 0.0031715897533633416, -0.10001785945037384, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4511888872247797, -0.022364920279907247, 0.10258899913299559]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05009514800811438, 0.00019729402949635635, 0.00456043625921739, -1.7992500044204525e-06, 0.0009071255097491021, -2.5109757506601937e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16029827120395065, -0.013480672972715567, 0.03195508655248156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.17804510178080624, 0.10348036374685363, 0.01638736196009529, -0.15000551881174337, 0.0032167924764168266, -0.10001798417576871, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45920353168969674, -0.023047630540533506, 0.10418708336258187]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.049926164173635455, -2.7800372068357215e-05, 0.004543024067582732, -1.7855931486566788e-06, 0.0009040544610697035, -2.4945078973837476e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16029288929834185, -0.013654205212525184, 0.031961684591725735]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.18053303197316722, 0.10347011419438958, 0.01661365309220967, -0.15000560739647148, 0.0032618437345468742, -0.10001810806096284, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46721788757183114, -0.023738926932461792, 0.10578547442777889]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04975860384721978, -0.00020499104928089752, 0.004525822642287584, -1.7716945620114073e-06, 0.0009010251626009576, -2.47770388269714e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160287117642688, -0.013825927838565726, 0.03196782130394042]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.183012654971167, 0.10345351758118154, 0.016839094978340474, -0.15000569527543056, 0.003306745680984454, -0.10001823108980991, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4752319363150039, -0.02443871971741958, 0.10738414966299131]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0495924599599955, -0.00033193226416061684, 0.004508837722616096, -1.7575791813816841e-06, 0.000898038928751594, -2.4605769412409795e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16028097486345472, -0.013995855699155773, 0.031973504704248666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.18548404123481146, 0.10343300575341878, 0.017063698402856802, -0.15000578243924914, 0.0033515004613197713, -0.10001835324725894, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48324566006924347, -0.02514691987599346, 0.10898308674691021]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04942772527288892, -0.00041023655525519585, 0.004492068490326587, -1.7432763717618052e-06, 0.0008950956067063493, -2.443148980529404e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16027447508479176, -0.01416400317147756, 0.03197874167837799]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1879472608550279, 0.10341077849955624, 0.01728747384145766, -0.1500058688798323, 0.003396110153584233, -0.10001847451921646, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49125904151653366, -0.02586343908780115, 0.11058226365644613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.049264392404328394, -0.0004445450772507193, 0.004475508772017207, -1.7288116631258034e-06, 0.0008921938452892325, -2.4254391504056314e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16026762894580424, -0.014330384236153841, 0.031983538190718606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.1904023835510969, 0.1033886994713745, 0.017510431261273066, -0.15000595458983532, 0.0034405767235067986, -0.10001859489177588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49927206376709743, -0.02658818971898559, 0.1121816586371489]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.049102453921380504, -0.0004415805636348532, 0.004459148396308083, -1.7142000602500772e-06, 0.0008893313984513139, -2.407451188525968e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16026044501127573, -0.014495012623688824, 0.03198789961405549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.19284947867213184, 0.10336823686666416, 0.017732579990172585, -0.15000603960783235, 0.003484901995256173, -0.10001871435921601, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5072847103179591, -0.027321084823910848, 0.11378125019612272]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04894190242069861, -0.00040925209420674807, 0.004442974577990359, -1.700359940612609e-06, 0.0008865054349874861, -2.3893488027200186e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160252931017232, -0.014657902098505156, 0.03199183117947626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.19528861520026722, 0.10335044372075877, 0.017953928651477456, -0.15000612401254956, 0.003529087636818467, -0.10001883292458877, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5152969650615643, -0.028062038153902853, 0.11538101710832856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04878273056270739, -0.00035586291810782336, 0.004426973226097425, -1.6880943444734038e-06, 0.0008837128312458869, -2.371307455198067e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1602450948721056, -0.014819066599840128, 0.03199533824411692]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.19771986175401954, 0.10333597097699894, 0.018174485156528267, -0.150006207798246, 0.0035731351583073124, -0.10001895057872319, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5233088123281033, -0.028810964150623924, 0.11698093841183672]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04862493107504653, -0.00028945487519659095, 0.004411130101016184, -1.6757139286449603e-06, 0.0008809504297769052, -2.353082688446571e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16023694533078126, -0.014978519934421407, 0.03199842607016335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20014328658872746, 0.10332510564698862, 0.01839425674461783, -0.15000629095935178, 0.003617045920889742, -0.10001906731283572, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5313202369234871, -0.02956777794732276, 0.11858099341127382]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.048468496694158286, -0.00021730660020653463, 0.0043954317617912785, -1.663222115502699e-06, 0.0008782152516485842, -2.3346822505692515e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.160228491907675, -0.015136275933976664, 0.032001099988741906]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20255895759272344, 0.10331782622989841, 0.018613250058649052, -0.15000637349057583, 0.003660821153721014, -0.10001918311851406, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5393312241563296, -0.030332395372301445, 0.12018116168277192]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04831342007991974, -0.0001455883418041401, 0.004379866280624439, -1.6506244807590696e-06, 0.0008755046566254421, -2.3161135668965226e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16021974465684996, -0.015292348499573696, 0.03200336542996195]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2049669422773501, 0.1033138679862704, 0.018831471244400506, -0.15000645554894895, 0.0037044619761907537, -0.10001929820039597, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5473417598495662, -0.031104732964475353, 0.12178142308918284]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.048159693692533166, -7.916487256010157e-05, 0.004364423715029095, -1.6411674626802083e-06, 0.0008728164493947907, -2.301637638216595e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16021071386473268, -0.015446751843478167, 0.03200522812821858]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20736730776636728, 0.1033127915178504, 0.01904892606269705, -0.15000653717341306, 0.0037479694230460056, -0.100019412609588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5553518303348315, -0.031884707967505664, 0.12338175777267554]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.048007309780343656, -2.1529368399892335e-05, 0.004349096365930887, -1.6324892818649363e-06, 0.0008701489371050387, -2.288183840417323e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16020140970530578, -0.01559950006060615, 0.032006693669854175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.20976012078340545, 0.10331404922073026, 0.019265620004060888, -0.15000661835563406, 0.0037913444700729175, -0.10001952633492237, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5633614224375337, -0.03267223832205153, 0.12498214614486355]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047856260340763464, 2.5154057597067764e-05, 0.0043338788272767916, -1.623644420283036e-06, 0.0008675009405382368, -2.2745066875558122e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601918420540452, -0.01575060709091739, 0.03200776744376017]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.21214544763836848, 0.10331704545761965, 0.019481558397456054, -0.1500066990872712, 0.0038345880584625277, -0.1000196393652088, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5713705234565156, -0.033467242661410164, 0.12658256887981856]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047706537099260676, 5.992473778770339e-05, 0.004318767867903331, -1.6146327431952826e-06, 0.0008648717677921988, -2.2606057285836942e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601820203796373, -0.01590008678717264, 0.03200845469910025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.214523354214581, 0.10332118759211503, 0.019696746506841594, -0.15000677936017673, 0.00387770111644924, -0.10001975168958674, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5793791211419874, -0.03426964030839385, 0.1281830069082024]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04755813152424989, 8.28426899076737e-05, 0.004303762187710815, -1.605458110199994e-06, 0.0008622611597342448, -2.246487558695672e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601719537094368, -0.016047952939673663, 0.0320087605676766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.21689390595778058, 0.10332592625129348, 0.019911189611223668, -0.15000685916625156, 0.003920684577254598, -0.10001986329730693, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5873872036752521, -0.03507935127277763, 0.1297834414122128]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0474110348639917, 9.477318356901133e-05, 0.004288862087641491, -1.5961214965137194e-06, 0.000859669216107161, -2.232154403898749e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1601616506652927, -0.016194219287675567, 0.03200869008020809]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2192571678675089, 0.10333078426620629, 0.02012489306581871, -0.1500069384975424, 0.003963539392800279, -0.10001997417781891, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.595394759652164, -0.03589629624917731, 0.13138385382139514]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047265238194566676, 9.716029825608835e-05, 0.004274069091900832, -1.5866258167803704e-06, 0.0008570963109136047, -2.2176102395773785e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16015111953823954, -0.016338899527993667, 0.03200824818364714]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22161320449103558, 0.10333537463672725, 0.02033786234367572, -0.15000701734626684, 0.004006266543043353, -0.10002008432080574, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6034017780706572, -0.03672039661528834, 0.13298422580927458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04712073247053373, 9.180741041927896e-05, 0.004259385557140274, -1.5769744889082373e-06, 0.0008545430048614926, -2.2028597365723687e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16014036836986395, -0.016482007322220493, 0.03200743975758855]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22396207991964015, 0.10333940855415552, 0.02055010305856593, -0.15000709570486315, 0.0040488670411144055, -0.10002019371621192, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6114082483215768, -0.03755157443037732, 0.1345845392906191]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04697750857209155, 8.067834856550048e-05, 0.004244814297804152, -1.5671719259900302e-06, 0.0008520099614210539, -2.1879081234785065e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16012940501839243, -0.016623556301779634, 0.032006269626890335]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22630385778689716, 0.10334269498793672, 0.02076162097108167, -0.15000717356601803, 0.004091341934693161, -0.10002030235426686, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6194141601815647, -0.03838975243387168, 0.1361847764190553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04683555734514031, 6.572867562404062e-05, 0.004230358250314796, -1.5572230978801982e-06, 0.0008494978715751032, -2.172761098905231e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16011823719975704, -0.016763560069887256, 0.032004742568724154]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.22863860126852809, 0.10334513361349326, 0.020972421980677322, -0.15000725092269504, 0.004133692304233598, -0.10002041022551572, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6274195038067542, -0.03923485404388815, 0.1377849195847638]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04669486963261854, 4.87725111308398e-05, 0.004216020191912997, -1.5471335402288695e-06, 0.0008470073908087491, -2.157424977295874e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16010687250378855, -0.0169020322003294, 0.03200286331417026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.23096637308338197, 0.10334670294970959, 0.021182512106838868, -0.1500073277681514, 0.004175919258752189, -0.10002051732082845, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.635424269726342, -0.04008680335557255, 0.13938495141204849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.046555436297077916, 3.1386724326404114e-05, 0.004201802523230933, -1.5369091271096457e-06, 0.0008445390903718153, -2.1419062545396127e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16009531839175742, -0.01703898623368797, 0.03200063654569387]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2332872354951531, 0.10334744551794267, 0.021391897462718353, -0.1500074040959531, 0.004218023929926689, -0.1000206236314152, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6434284488355283, -0.04094552513917494, 0.14098485475666991]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04641724823542268, 1.4851364661654091e-05, 0.004187707117589671, -1.5265560337321164e-06, 0.0008420934234900004, -2.1262117349273296e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600835821837258, -0.0171744356720478, 0.03199806689242857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.23560125031450982, 0.10334745166423494, 0.021600584224459176, -0.15000747989998708, 0.004260007465228015, -0.10002072914885637, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6514320323877014, -0.04181094483783783, 0.14258461270292636]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04628029638713441, 1.2292584547088654e-07, 0.004173735234816468, -1.5160806800711904e-06, 0.0008396707060265139, -2.1103488235878295e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600716710434631, -0.017308393973257882, 0.031995158925128726]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.23790847890137787, 0.10334684343805581, 0.02180857859912628, -0.1500075551744723, 0.004301871020738212, -0.1000208338650932, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6594350119860194, -0.04268298856511886, 0.14418420856053016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.046144571737360925, -1.2164523582535762e-05, 0.004159887493342035, -1.5054897046058864e-06, 0.0008372711102039476, -2.0943247363514818e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600595919663592, -0.01744087454562057, 0.03199191715207618]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24020898216718775, 0.10334575962781317, 0.022015886793699892, -0.15000762991395247, 0.004343615754205344, -0.10002093777245358, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.66743737957467, -0.043561583102290906, 0.14578362586136095]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04601006531619754, -2.167620485271188e-05, 0.0041461638914723, -1.4947896030987316e-06, 0.0008348946693426383, -2.0781472075761348e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16004735177301213, -0.017571890743440868, 0.031988346016616064]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24250282057694758, 0.10334434274513316, 0.022222514987051262, -0.15000770411331082, 0.004385242818765281, -0.10002104086364545, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6754391274301076, -0.04444665589547332, 0.14738284835618237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.045876768195196586, -2.833765360031708e-05, 0.004132563867027421, -1.4839871668655537e-06, 0.000832541291198747, -2.061823837582297e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600349571087517, -0.01770145586364828, 0.031984449896428395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24479005415104668, 0.10334272845097672, 0.02242846930624998, -0.15000777776775132, 0.004426753357632958, -0.10002114313176848, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6834402481524985, -0.045338135052637646, 0.1489818600113899]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04574467148198211, -3.2285883128606505e-05, 0.00411908638397435, -1.4730888100131256e-06, 0.000830210777353534, -2.0453624605102816e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1600224144478189, -0.01782958314328649, 0.03198023310415052]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24707074246673555, 0.10334103764578095, 0.022633755807996526, -0.15000785087280727, 0.004468148499941095, -0.1000212445703161, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6914407346575107, -0.0462359493405216, 0.1505806450058359]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04561376631377729, -3.381610391538624e-05, 0.00410573003493091, -1.4621011192002264e-06, 0.0008279028461627341, -2.0287709524375374e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16000973010024377, -0.01795628575767917, 0.03197569988891966]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.24934494465932536, 0.10333937121588066, 0.022838380465478522, -0.1500079234220059, 0.004509429357793151, -0.10002134516998495, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.699440580168477, -0.047140028181256774, 0.15217918772758207]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.045484043851796226, -3.3328598005766444e-05, 0.004092493149639925, -1.4509839722865077e-06, 0.0008256171570411013, -2.011993377127638e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1599969102193264, -0.018081576814703418, 0.03197085443492361]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.25161271942632224, 0.10333780724678863, 0.023042349160843065, -0.15000799529489925, 0.004550597024556257, -0.10002144476505512, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7074397782084517, -0.04805030163861886, 0.15377747276273857]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04535549533993808, -3.127938184055098e-05, 0.0040793739072908265, -1.4374578672876962e-06, 0.0008233533352621341, -1.991901403365508e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15998396079949395, -0.018205469147241714, 0.03196570070312983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2538741250250015, 0.10333640037958398, 0.023245667681798775, -0.15000806649093595, 0.004591652574109741, -0.1000215433532149, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7154383225950193, -0.04896670042382532, 0.15537548489993488]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04522811197358551, -2.8137344093005064e-05, 0.004066370419114236, -1.4239207338742502e-06, 0.0008211109910696841, -1.9717631957763895e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15997088773135104, -0.018327975704129137, 0.031960242743926476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.25612921927169197, 0.10333518291572864, 0.023448341722547655, -0.15000813701028293, 0.004632597061055798, -0.10002164093350979, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7234362074326022, -0.049889155895411895, 0.15697320912989823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04510188493380949, -2.4349277106919086e-05, 0.004053480814977581, -1.4103869392300339e-06, 0.0008188897389211255, -1.9516058977264347e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15995769675165808, -0.018449109431731614, 0.0319544845992672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.25837805954158516, 0.10333416722997266, 0.023650376888045523, -0.15000820685342905, 0.004673431521673097, -0.10002173750536082, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7314334271048738, -0.050817600056630746, 0.15857063064318155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044976805397864146, -2.031371511964554e-05, 0.004040703309957356, -1.3968629223907938e-06, 0.0008166892123459742, -1.9314370205954102e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15994439344543218, -0.018568883224377032, 0.03194843026566624]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.26062070276972954, 0.10333334905306475, 0.02385177870073128, -0.15000827598790845, 0.004714156975416838, -0.10002183302315162, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7394299762674554, -0.05175196554883487, 0.16016773482497235]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04485286456288734, -1.6363538158197644e-05, 0.004028036253715111, -1.382689587868713e-06, 0.0008145090748748352, -1.9103558159788117e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15993098325163188, -0.018687309844082418, 0.03194208363581572]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2628572054505867, 0.10333271121640945, 0.02405255260853905, -0.15000834440005673, 0.004754774426712563, -0.10002192746663706, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7474258498417211, -0.052692185648650185, 0.16176450725297814]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04473005361714357, -1.2756733106001308e-05, 0.004015478156155436, -1.3682429654596555e-06, 0.0008123490259144914, -1.8888697087540805e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15991747148531305, -0.018804401996306248, 0.031935448560115626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.26508762363726895, 0.10333222750617385, 0.024252703993492972, -0.1500084120939234, 0.0047952848668825765, -0.10002202083984314, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7554210430084136, -0.0536381942661282, 0.16336093369605836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04460836373364514, -9.674204712095643e-06, 0.004003027699078406, -1.353877333509523e-06, 0.0008102088034002794, -1.8674641215638693e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15990386333384968, -0.018920172349560307, 0.031928528861604494]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2673120129414288, 0.10333186633945665, 0.024452238180277724, -0.1500084790738226, 0.004835689276064566, -0.10002211314722456, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.76341555120095, -0.054589925941318555, 0.16495700011168518]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04448778608319669, -7.223334344032695e-06, 0.0039906837356950475, -1.3395979834725042e-06, 0.000808088183639793, -1.8461476282723448e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15989016385072644, -0.019034633503807106, 0.031921328312536405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.26953042853347003, 0.10333159404634065, 0.02465116044417969, -0.15000854534428604, 0.004875988624988173, -0.10002220439355264, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7714093700989456, -0.055547315840243486, 0.1665526926430417]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044368311840824744, -5.445862320050276e-06, 0.003978445278039363, -1.3254092689671988e-06, 0.0008059869784721276, -1.824926561473613e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15987637795991314, -0.019147797978498554, 0.031913850627130376]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2717429251429817, 0.10333137761394057, 0.024849476017975516, -0.15000861091005177, 0.004916183876515213, -0.10002229458393049, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7794024956219943, -0.056510299750678276, 0.16814799761606405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044249932190233085, -4.32864800172508e-06, 0.003966311475916454, -1.311315314905916e-06, 0.0008039050305408062, -1.8038075569355152e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15986251046097405, -0.0192596782086958, 0.03190609946044691]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2739495570593706, 0.10333118681560001, 0.025047190097506257, -0.15000867577605453, 0.004956275986885084, -0.10002238372376349, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7873949239236486, -0.05747881407789648, 0.1697429015365352]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.044132638327777016, -3.815966811214887e-06, 0.003954281590614795, -1.2973200551719209e-06, 0.0008018422073974141, -1.7827966601206466e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15984856603308634, -0.019370286544363978, 0.0318980784094228]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.27615037813268956, 0.10333099570671443, 0.025244307845820144, -0.15000873994741984, 0.004996265906639071, -0.10002247181875316, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.795386651385558, -0.05845279584043266, 0.17133739108726143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04401642146637921, -3.822177711434511e-06, 0.003942354966277703, -1.2834273063283703e-06, 0.0007997983950797364, -1.7618997935989611e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15983454923818607, -0.01947963525072365, 0.03188979101452433]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2783454417746549, 0.10333078351608817, 0.025440834395887547, -0.15000880342944778, 0.005036154581224447, -0.10002255887489248, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.803377674611739, -0.059432182665875015, 0.1729314531253334]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04390127283930712, -4.243812525363838e-06, 0.003930531001348092, -1.2696405585411844e-06, 0.0007977734917075222, -1.7411227861338585e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15982046452362142, -0.01958773650884707, 0.031881240761439625]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.280534800959843, 0.1033305349972854, 0.025636774851990726, -0.15000886622760784, 0.0050759429513011975, -0.10002264489845251, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8113679904229674, -0.06041691278668432, 0.17452507467946504]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043787183703761466, -4.9703760554135155e-06, 0.003918809122063529, -1.2559632014907505e-06, 0.0007957674015350019, -1.7204712008525275e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15980631622456604, -0.019694602416186122, 0.031872431082632845]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.28271850822704814, 0.10333024032814164, 0.025832134289960413, -0.1500089283475258, 0.00511563195279003, -0.10002272989596761, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8193575958512821, -0.06140692503603015, 0.17611824294739997]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04367414534410213, -5.893382875004663e-06, 0.003907188759393764, -1.2423983592222752e-06, 0.0007937800297766446, -1.6999503019726594e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15979210856629433, -0.019800244986916744, 0.03186336535869875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2848966156807819, 0.10332989465929975, 0.02602691775647827, -0.1500089897949776, 0.0051552225167106926, -0.10002281387423123, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.827346488134601, -0.0624021588436359, 0.17771094529337791]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04356214907467464, -6.9133768380495665e-06, 0.0038956693303571015, -1.2289490358422545e-06, 0.0007918112784132601, -1.6795652724324474e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1597778456663768, -0.01990467615211503, 0.03185404691955871]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.28706917499289303, 0.10332949741574912, 0.026221130267684387, -0.1500090505758676, 0.005194715568864285, -0.10002289684027461, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8353346647114424, -0.06340255423162452, 0.17930316924565265]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0434511862422227, -7.944871012459946e-06, 0.0038842502241223965, -1.2156178000953194e-06, 0.0007898610430718366, -1.6593208675950465e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15976353153682643, -0.020007907759772434, 0.0318444790454949]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.28923623740428234, 0.10332905145066051, 0.02641477680733089, -0.15000911069623774, 0.005234112029413506, -0.10002297880136972, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8433221232157535, -0.0644080518103614, 0.18089490249405826]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043341248227785976, -8.919301772053437e-06, 0.003872930792930072, -1.2024074025364023e-06, 0.0007879292109844364, -1.6392219020593067e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15974917008622308, -0.020109951574737304, 0.031834664968112485]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.29139785372669147, 0.10332856214027344, 0.02660786232470734, -0.15000917016223753, 0.0052734128124114115, -0.10002305976500296, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8513088614718439, -0.06541859277428819, 0.1824861328876172]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04323232644818272, -9.786207741316617e-06, 0.00386171034752901, -1.1893199955852009e-06, 0.000786015659958096, -1.6192726648206346e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15973476512180762, -0.02021081927853593, 0.03182460787117888]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.293554074344547, 0.10332803649415295, 0.026800391732533846, -0.15000922898012845, 0.0053126188253227345, -0.10002313973887929, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8592948774894236, -0.06643411889774825, 0.18407684843218974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04312441235711089, -1.0512922409870303e-05, 0.0038505881565301173, -1.1763578184363522e-06, 0.0007841202582264676, -1.599477526548888e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15972032035159217, -0.020310522469201408, 0.03181431089145096]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.2957049492168433, 0.10332748233859759, 0.026992369904983667, -0.15000928715626657, 0.00535173096857404, -0.10002321873090829, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.867280169458746, -0.06745457253080042, 0.18566703728816195]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043017497445926825, -1.1083111107229559e-05, 0.0038395634489964, -1.1635227624855766e-06, 0.0007822428650261137, -1.5798405801472918e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15970583938644847, -0.02040907266104334, 0.0318037771194439]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.297850527879053, 0.10332690761392402, 0.027183801675955917, -0.1500093446970918, 0.005390750135159585, -0.10002329674918031, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8752647357458557, -0.06847989659502164, 0.18725668776817084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04291157324419298, -1.1494493471360395e-05, 0.0038286354194450307, -1.1508165042166715e-06, 0.0007803833317108914, -1.560365440380827e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1596913257421954, -0.02050648128442441, 0.03179300960017787]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.299990859445052, 0.10332631981005735, 0.02737469183767937, -0.1500094016091248, 0.005429677210321284, -0.10002337380196107, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8832485748879394, -0.06951003457929926, 0.18884578833486626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.042806631319979874, -1.1756077333398683e-05, 0.003817803234469083, -1.1382406602047044e-06, 0.0007785415032339804, -1.541055614946231e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1596767828416742, -0.020602759685552495, 0.03178201133390833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3021259926090574, 0.1033257255502829, 0.027565045139689, -0.1500094578989542, 0.005468513071312054, -0.10002344989769207, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8912316855887791, -0.07054493053561418, 0.19043432759870804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04270266328010881, -1.1885195489109694e-05, 0.0038070660401925915, -1.125796588031035e-06, 0.0007767172198153971, -1.5219146202139667e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15966221401679462, -0.02069791912629838, 0.031770785276835516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.30425597564757445, 0.10332513032080516, 0.02775486628818479, -0.15000951357322692, 0.0055072585872446645, -0.10002352504496832, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8992140667143067, -0.07158452907481427, 0.19202229431579765]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.042599660770340914, -1.1904589554583705e-05, 0.003796422969915852, -1.113485454153704e-06, 0.0007749103186522053, -1.502945524915729e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1596476225105518, -0.02079197078400172, 0.031759334341792095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3063808564213513, 0.10332453833425918, 0.027944159945754, -0.15000956863863843, 0.005545914619021985, -0.10002359925253017, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9071957172882569, -0.07262877536238123, 0.1936096773857436]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.042497615475537376, -1.1839730919630454e-05, 0.003785873151384124, -1.1013082301515212e-06, 0.0007731206355464007, -1.4841512369652657e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15963301147900363, -0.02088492575133897, 0.03174766139891916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3085006823773436, 0.10332395250861434, 0.028132930731417975, -0.1500096231019266, 0.005584482019339736, -0.10002367252924202, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9151766364879175, -0.07367761511419113, 0.19519646584956013]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04239651911984614, -1.1716512896918848e-05, 0.0037754157132795143, -1.0892657633621812e-06, 0.0007713480063550346, -1.4655342371064153e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15961838399321296, -0.020976795036197902, 0.03173576927633021]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3106073020659039, 0.10332337854148974, 0.028320482265820502, -0.15000966870639382, 0.0056228111617659575, -0.10002373461224327, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9231094530516137, -0.07472145554500015, 0.19677115644984025]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04213239377120598, -1.1479342492114194e-05, 0.003751030688050521, -9.120893446924336e-07, 0.000766582848524428, -1.2416600250398667e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15865633127392514, -0.020876808616180447, 0.031493812005602514]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3126098952457772, 0.10332284641696683, 0.028498839598930518, -0.1500100817900876, 0.0056592446112130245, -0.10002456041684918, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9305957187118021, -0.07569602507676208, 0.19824826232288928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.040051863597465216, -1.0642490458097362e-05, 0.003567146662200323, -8.261673875510393e-06, 0.0007286689889413484, -1.6516092118097312e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1497253132037683, -0.019491390635238734, 0.029542117460980476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31443926874850425, 0.10332237757976635, 0.028661836022275976, -0.15001099483960964, 0.005692523725398532, -0.10002625734702274, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9373928210073526, -0.07656971098201253, 0.1995806815535737]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03658747005454047, -9.376744009706101e-06, 0.003259928466909189, -1.8260990441132797e-05, 0.0006655822837101507, -3.393860347107556e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13594204591100795, -0.01747371810500881, 0.02664838461368838]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31606662275376346, 0.10332198661734378, 0.028806880545416913, -0.15001257687774291, 0.005722125750397684, -0.10002894925667692, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9434149581715543, -0.07733494011630161, 0.20075404313385897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03254708010518427, -7.819248451635785e-06, 0.0029008904628187553, -3.164076266573587e-05, 0.0005920404999830507, -5.3838193083670426e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12044274328403481, -0.015304582685781595, 0.02346723160570544]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3174911365978103, 0.10332168483362031, 0.028933877029759927, -0.15001470981484208, 0.005748036844570836, -0.10003245257333418, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9486738710338738, -0.07799701600317752, 0.20177314556168108]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.028490276880937, -6.03567446938783e-06, 0.002539929686860283, -4.2658741983145474e-05, 0.0005182218834630396, -7.006633314509806e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1051782572463891, -0.013241517737518204, 0.020382048556442097]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31872650927865204, 0.10332148004915269, 0.02904402967296915, -0.15001696685470292, 0.005770507000930261, -0.10003629158150958, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9532290314546588, -0.07856656533767781, 0.20265165905603091]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02470745361683458, -4.095689352428911e-06, 0.0022030528641844957, -4.514079721687587e-05, 0.00044940312718850964, -7.678016350787341e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0911032084157001, -0.0113909866900057, 0.017570269886996635]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.31979223350183095, 0.10332137362159707, 0.02913906505109426, -0.1500172425565492, 0.005789891310918553, -0.10003703400972054, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9571572315169582, -0.0790554597448708, 0.2034061068439106]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021314484463578184, -2.128551112394285e-06, 0.001900707562502168, -5.514036925250084e-06, 0.00038768619976583066, -1.4848564219303214e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07856400124598857, -0.009777888143859867, 0.015088955757593765]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32070891599535056, 0.10332134744762694, 0.02922081330264332, -0.1500174527708254, 0.005806564858331019, -0.10003757044046865, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9605370255841236, -0.07947497749144482, 0.20405289807664298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01833364987039281, -5.234794025623375e-07, 0.001634965030981182, -4.204285523890006e-06, 0.00033347094824932866, -1.0728614962244765e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06759588134330642, -0.008390354931480395, 0.012935824654647422]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3214961207886183, 0.10332137910660898, 0.029291014768987076, -0.1500177379551962, 0.005820883597945364, -0.10003820291117005, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.963441666044053, -0.0798351264558084, 0.20460704949494996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015744095865354316, 6.331796406987266e-07, 0.0014040293268751777, -5.703687416282992e-06, 0.00028637479228689575, -1.2649414027945605e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05809280919858905, -0.007202979287271632, 0.011083028366139438]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32217152815939015, 0.10332144881363478, 0.029351244011058337, -0.1500180868576028, 0.005833169130580514, -0.10003888891608088, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9659365901093725, -0.08014452429683226, 0.20508178811557237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013508147415436971, 1.394140515977055e-06, 0.0012045848414252306, -6.978048131656092e-06, 0.00024571065270300254, -1.3720098216709745e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.049898481306390526, -0.006187956820477323, 0.009494772412448255]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.322750727622933, 0.10332154125683989, 0.02940289054596245, -0.1500184384201689, 0.005843704981633201, -0.10003956220902593, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9680790465613092, -0.0804105032920081, 0.20548855407438218]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011583989270857404, 1.848864102105997e-06, 0.0010329306980822808, -7.031251322381427e-06, 0.00021071702105373175, -1.3465858900937968e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04284912903873378, -0.0053195799035167905, 0.00813531917619604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32324728989494617, 0.1033216452919178, 0.02944716466561267, -0.1500188299406522, 0.005852737936282021, -0.10004034714895085, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9699186205235781, -0.0806392833780997, 0.20583716093998775]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009931245440262929, 2.0807015581975825e-06, 0.0008854823930044233, -7.830409665420957e-06, 0.0001806590929764091, -1.5698798498486524e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03679147924537868, -0.004575601721831806, 0.006972137312110954]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3236729481301363, 0.10332175335745515, 0.0294851132091579, -0.1500192406217717, 0.005860481351922626, -0.10004117837040108, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9714980488411608, -0.08083614579002193, 0.20613599757900758]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008513164703802359, 2.1613107470021494e-06, 0.0007589708709046055, -8.213622390221093e-06, 0.00015486831281211555, -1.6624429004414887e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03158856635165154, -0.003937248238444746, 0.00597673278039645]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3240378081386516, 0.10332186056774079, 0.029517638054237686, -0.15001967678864575, 0.005867118989848188, -0.10004196194888963, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9728540853626501, -0.08100558657493173, 0.20639222786283906]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0072972001703054444, 2.1442057127400096e-06, 0.0006504969015957227, -8.723337481520962e-06, 0.00013275275851123815, -1.5671569771085008e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027120730429785765, -0.0033888156981960547, 0.005124605676629434]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32435055461301737, 0.10332196390654821, 0.029545514354327704, -0.15002014436279623, 0.005872808769887851, -0.1000426880018997, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9740183104427782, -0.08115144492470755, 0.20661197046205118]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006254929487316511, 2.0667761485109546e-06, 0.000557526001800362, -9.351483009625949e-06, 0.00011379560079326082, -1.4521060201099538e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02328450160256351, -0.0029171669955164606, 0.004394851984242261]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32461864112407124, 0.1033220616391923, 0.02956940740601082, -0.15002055313455698, 0.005877686227451204, -0.10004334078103809, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9750178466632097, -0.08127700778558342, 0.20680045364637603]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005361730221077603, 1.9546528818555513e-06, 0.000477861033662324, -8.175435215123442e-06, 9.754915126705303e-05, -1.305558276794181e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.019990724408628962, -0.002511257217517263, 0.003769663686497212]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32484845861298506, 0.10332215278860385, 0.029589887631756163, -0.15002095710621496, 0.005881867578496745, -0.10004401668926688, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9758759891374625, -0.08138509608602612, 0.20696214859478393]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004596349778275921, 1.822988230838852e-06, 0.00040960451490685374, -8.079433159526202e-06, 8.362702091082998e-05, -1.3518164575795766e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017162849485057044, -0.002161766008854222, 0.0032338989681580093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.3250454837649755, 0.10332223693673287, 0.029607443805142464, -0.15002147062836285, 0.005885452417907611, -0.10004483722416617, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9766127451390855, -0.08147813501145389, 0.2071008815247186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003940503039808336, 1.6829625803326659e-06, 0.0003511234677260382, -1.0270442957594471e-05, 7.169678821730668e-05, -1.6410697985898636e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014735120032458051, -0.0018607785085553367, 0.002774658598693349]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32521440922120926, 0.10332231416827514, 0.029622494684762593, -0.15002211021273992, 0.005888526086572418, -0.10004575402998754, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9772452898530821, -0.08155821117836452, 0.20721992697227853]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0033785091246751847, 1.5446308455821939e-06, 0.00030101759240258103, -1.2791687541520382e-05, 6.147337329615691e-05, -1.83361164273692e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012650894279933177, -0.0016015233382128628, 0.0023809089511987037]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32535925476056105, 0.10332238490610468, 0.029635398937231664, -0.15002286362761322, 0.0058911616924520556, -0.10004675938412434, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9777883692474848, -0.08162712168540125, 0.20732208910195418]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002896910787036039, 1.4147565907436082e-06, 0.00025808504938143483, -1.5068297465661992e-05, 5.271211759275058e-05, -2.0107082735898254e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010861587888052712, -0.0013782101407345034, 0.0020432425935131226]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, -0.32548346282801216, 0.10332244974404842, 0.029646463663863906, -0.1500237412231271, 0.005893421847063744, -0.10004797785332699, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9782546479731619, -0.0816864156426958, 0.20740977113148507]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0" - }, - "execution_count": 9, - "metadata": {}, - "output_type": "execute_result" - } - ], + "execution_count": 11, + "outputs": [], "source": [ "reset_giskard()\n", "# Define a world feature as a point at the origin of map\n", @@ -361,16 +297,15 @@ "robot_feature.header.frame_id = 'r_gripper_tool_frame'\n", "\n", "# use the distance feature function to constrain the distance between the features to be between 2m and 2.5m\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction',\n", - " root_link='map',\n", - " tip_link='r_gripper_tool_frame',\n", - " world_feature=world_feature,\n", - " robot_feature=robot_feature,\n", - " lower_limit=2,\n", - " upper_limit=2.5)\n", + "gs.motion_goals.add_distance(root_link='map',\n", + " tip_link='r_gripper_tool_frame',\n", + " reference_point=world_feature,\n", + " tip_point=robot_feature,\n", + " lower_limit=2,\n", + " upper_limit=2.5)\n", "\n", "gs.add_default_end_motion_conditions()\n", - "gs.execute()" + "assert gs.execute().error.code == GiskardError.SUCCESS" ], "metadata": { "collapsed": false, @@ -397,17 +332,8 @@ }, { "cell_type": "code", - "execution_count": 25, - "outputs": [ - { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995221653958, 0.0, 0.0, 0.0, -0.0015703775115318255, 0.003282713647665629, 0.003026158987476063, -0.15000000006019606, 0.0015374000077203185, -0.10001000003167682, 6.429855888227713e-20, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006247115511932974, 0.0004616962537508633, 0.000624999852377246]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044330791465, 0.0, 0.0, 0.0, -0.03140755023063651, 0.06565427295331257, 0.060523179749521254, -1.2039214455783773e-09, 0.030748000154406364, -6.335363548201422e-10, 1.2859711776455427e-18, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012494231023865947, 0.009233925075017265, 0.012499997047544918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990445676024, 0.0, 0.0, 0.0, -0.006755901413791964, 0.008753017198904492, 0.0053284771598860105, -0.15000000006915654, 0.0008622001356011302, -0.10001000003714006, -0.0037499999010584422, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0024958366420357193, 0.002013990282373121, 0.0024999995417754797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044804412895, 0.0, 0.0, 0.0, -0.10371047804520278, 0.10940607102477724, 0.046046363448198964, -1.792091831848076e-10, -0.013503997442383762, -1.0926480652581477e-10, -0.07499999802116884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03742250181684844, 0.031045880572445155, 0.037499993787964675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985669148155, 0.0, 0.0, 0.0, -0.014744384398796447, 0.015279346312955468, 0.003156957255756268, -0.15000000009040484, -0.005775599367293093, -0.10001000004944276, -0.014999999238081001, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0059176141607758855, 0.004697522503904497, 0.005880900225464659]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044694426184, 0.0, 0.0, 0.0, -0.1597696597000896, 0.13052658228101952, -0.04343039808259485, -4.249661995310357e-10, -0.13275599005788444, -2.4605399786351803e-10, -0.22499998674045113, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06843555037480333, 0.05367064443062752, 0.06761801367378358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980893382729, 0.0, 0.0, 0.0, -0.021787446482147494, 0.0222326984114459, 0.0002615992679069145, -0.15000000009451547, -0.014625998505889616, -0.10001000005168982, -0.02999999801357465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010597863524518143, 0.007900249813603396, 0.010350386544235202]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044846914836, 0.0, 0.0, 0.0, -0.14086124166702096, 0.13906704196980868, -0.05790715975698706, -8.221259503883282e-11, -0.17700798277193047, -4.4941409038965875e-11, -0.2999999755098729, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09360498727484513, 0.06405454619397798, 0.08938972637541083]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976117780566, 0.0, 0.0, 0.0, -0.026653873851331944, 0.028696017227165915, 0.0003924031961315786, -0.15000000009462847, -0.02193899728036525, -0.10001000005175661, -0.04499999622762701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016222696771134453, 0.011007162548498569, 0.015410517283923585]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879567476, 0.0, 0.0, 0.0, -0.09732854738368898, 0.12926637631440027, 0.0026160785644932863, -2.2599334557434373e-12, -0.1462599754895127, -1.3358845254008728e-12, -0.2999999642810472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11249666493232618, 0.06213825469790344, 0.10120261479376766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134210975, 0.0, 0.0, 0.0, -0.029264665764574014, 0.03347298766345755, 0.0072993688221773285, -0.1500000000964399, -0.023964595754733677, -0.10001000005277047, -0.056249993903809026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022548176101336193, 0.013398881926501795, 0.020646939792804873]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044865836936, 0.0, 0.0, 0.0, -0.052215838264841385, 0.09553940872583261, 0.13813931252091496, -3.622864186616696e-11, -0.04051196948736856, -2.0277166286824266e-11, -0.22499995352364038, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12650958660403477, 0.047834387560064515, 0.1047284501776258]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966565872612, 0.0, 0.0, 0.0, -0.030698916801691834, 0.036781136745916945, 0.0191412684915748, -0.15000000011194803, -0.01738277245628061, -0.10001000006168011, -0.0599999928637143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.02940939096061492, 0.01445075572565422, 0.02553196890319519]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044752572424, 0.0, 0.0, 0.0, -0.028685020742356383, 0.0661629816491879, 0.23683799338794945, -3.101625735212342e-10, 0.1316364659690613, -1.7819285107010279e-10, -0.07499997919810561, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1372242971855746, 0.021037475983048483, 0.09770058220780634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961790214503, 0.0, 0.0, 0.0, -0.03094022359446766, 0.039194295230485565, 0.03590932499636888, -0.1500000001134369, -0.004486299228333535, -0.10001000006254271, -0.05407310148517385, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.036653412085490035, 0.013984549081381468, 0.029893874579441853]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904486837801, 0.0, 0.0, 0.0, -0.0048261358555164655, 0.04826316969137234, 0.33536113009588164, -2.977719576380854e-11, 0.2579294645589415, -1.725194792822288e-11, 0.1185378275708091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1448804224975023, -0.009324132885455031, 0.08723811352493321]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2058495701460289, 0.0, 0.0, 0.0, -0.028541966195731946, 0.04158424263777133, 0.06113270540868164, -0.15000000011375714, 0.017510761783818562, -0.10001000006274377, -0.037884025366766536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.04406346987877525, 0.011792833881908733, 0.033882894093707844]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044877677186, 0.0, 0.0, 0.0, 0.04796514797471423, 0.0477989481457153, 0.5044676082462551, -6.4047724819789275e-12, 0.43994122024304194, -4.0213470212477625e-12, 0.3237815223681462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1482011558657042, -0.04383430398945469, 0.07978039028531984]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952236442112, 0.0, 0.0, 0.0, -0.024683106303693775, 0.04769021367659524, 0.09106140973439328, -0.15000000017227058, 0.044858410586010464, -0.10001000009829364, -0.015182764502755287, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05137298421918549, 0.008487441509706446, 0.037407950184213605]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044367844746, 0.0, 0.0, 0.0, 0.07717719784076345, 0.1221194207764782, 0.5985740865142327, -1.1702688663704997e-09, 0.5469529760438381, -7.109972417165659e-10, 0.45402521728022494, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14619028680820487, -0.06610784744404573, 0.07050112181011528]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20714947460838093, 0.0, 0.0, 0.0, -0.020858999806023345, 0.058046323998970736, 0.12194543797350729, -0.15000000017241016, 0.0738066471782457, -0.10001000009837022, 0.010280681106863438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05860462720353032, 0.004690215098383745, 0.040429687397281956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879196259, 0.0, 0.0, 0.0, 0.07648212995340858, 0.20712220644750995, 0.6176805647822803, -2.7919081062526814e-12, 0.5789647318447045, -1.5315994487427349e-12, 0.5092689121923745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14463285968689646, -0.075944528226454, 0.06043474426136707]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2077994268501965, 0.0, 0.0, 0.0, -0.018134570423865817, 0.06890263434192896, 0.15003479012617332, -0.1500000001771229, 0.10060547156067459, -0.10001000010102225, 0.034756311462241465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06602790501256466, 0.0010348003189873606, 0.04303379603046195]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836311804, 0.0, 0.0, 0.0, 0.05448858764315058, 0.21712620685916442, 0.5617870430533203, -9.425452062625182e-11, 0.5359764876485777, -5.3040759378980744e-11, 0.48951260710756056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14846555618068683, -0.07310829558792768, 0.05208217266359997]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2084493790941273, 0.0, 0.0, 0.0, -0.01708525644819017, 0.07650914482900094, 0.17157946619240233, -0.15000000017736673, 0.12150488373330834, -0.10001000010116455, 0.05449412656339041, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07379363222107337, -0.0018474606745197764, 0.045349749037888284]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044878616297, 0.0, 0.0, 0.0, 0.020986279513512916, 0.15213020974143948, 0.43089352132458014, -4.876468442942762e-12, 0.41798824345267493, -2.846019531188478e-12, 0.39475630202297884, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1553145441701743, -0.05764521987014274, 0.04631906014852671]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20909933133720682, 0.0, 0.0, 0.0, -0.017613126548445397, 0.07711585595114098, 0.18282946622975466, -0.15000000017936918, 0.1327548837193033, -0.10001000010244541, 0.06574412642482488, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08182018860532334, -0.0036750923213572824, 0.04748974351651834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861590418, 0.0, 0.0, 0.0, -0.010557402005104521, 0.012134222442800796, 0.22500000074704662, -4.004909909979424e-11, 0.22499999971989926, -2.5617215822644437e-11, 0.22499999722868932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16053112768499928, -0.03655263293675012, 0.04279988957260117]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2097492835792608, 0.0, 0.0, 0.0, -0.017961433437616258, 0.07212268498125661, 0.18753479016897634, -0.1500000001836914, 0.13453306909224536, -0.1000100001049987, 0.06475631116544972, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08998196153562694, -0.005079155093326413, 0.0495838125379807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044841079355, 0.0, 0.0, 0.0, -0.006966137783417199, -0.09986341939768756, 0.09410647878443348, -8.64440654052035e-11, 0.035563707458841326, -5.106580412440603e-11, -0.01975630518750332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1632354586060722, -0.028081255439382613, 0.04188138042924712]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.210399235696626, 0.0, 0.0, 0.0, -0.017336349354425813, 0.06441202604501901, 0.18944541359829328, -0.15000000049395185, 0.13058937748796107, -0.10001000029062612, 0.05268368273895247, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09821210177343816, -0.006688109789839386, 0.051699948567954804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042347304122, 0.0, 0.0, 0.0, 0.012501681663808877, -0.1542131787247519, 0.038212468586338824, -6.205209233944879e-09, -0.07887383208568581, -3.712548254105807e-09, -0.24145256852994498, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16460280475622413, -0.032179093930259466, 0.04232272059948208]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2110491878167223, 0.0, 0.0, 0.0, -0.01566087886119214, 0.056227627250662125, 0.1923113049568272, -0.15000000080487622, 0.1246728158709866, -0.10001000047442696, 0.03137363071510729, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10650401637349055, -0.009077139244646036, 0.05383154925667112]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042401925898, 0.0, 0.0, 0.0, 0.033509409864673434, -0.16368797588713774, 0.05731782717067806, -6.2184874587217276e-09, -0.11833123233948932, -3.6760167492971274e-09, -0.42620104047690344, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16583829200104783, -0.047780589096132996, 0.042632013774326384]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21169914003756007, 0.0, 0.0, 0.0, -0.013136203519607408, 0.04883700270829323, 0.19988246226128245, -0.1500000008623399, 0.11863606571430928, -0.10001000050854808, 0.0023652701545303356, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11483161231922363, -0.01199410907733664, 0.05595489857210957]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044416755284, 0.0, 0.0, 0.0, 0.050493506831694665, -0.14781249084737794, 0.15142314608910537, -1.1492734315868921e-09, -0.12073500313354632, -6.824224889017973e-10, -0.5801672112115391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16655191891466153, -0.058339396653812096, 0.04246698630876896]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21234909228126364, 0.0, 0.0, 0.0, -0.009996518414377473, 0.04273535156098593, 0.215908885222191, -0.15000000086310458, 0.1116744585608232, -0.10001000050901339, -0.03284141825077267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12316562136608956, -0.015097741704376453, 0.05805133257902995]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874071369, 0.0, 0.0, 0.0, 0.0627937021045987, -0.12203302294614593, 0.3205284592181714, -1.5294059539376564e-11, -0.13923214306972154, -9.30620393572005e-12, -0.70413376810606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16668018093731854, -0.06207265254079625, 0.04192868013840767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21299904452415347, 0.0, 0.0, 0.0, -0.006331705371242254, 0.03790943535812955, 0.24037723313094952, -0.15000000086586115, 0.10284123930706682, -0.1000100005108645, -0.07300676894792131, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1314859257035349, -0.018250096413792175, 0.06011837155963506]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044857796615, 0.0, 0.0, 0.0, 0.0732962608627044, -0.09651832405712751, 0.4893669581751701, -5.513133716006377e-11, -0.17666438507512774, -3.7022213019124806e-11, -0.8033070139429728, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1664060867489066, -0.06304709418831446, 0.041340779612102134]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21364899674866902, 0.0, 0.0, 0.0, -0.0021310152188000727, 0.03408183068271783, 0.27183783923295674, -0.15000000091315058, 0.09170729336620415, -0.10001000054063608, -0.11713904823135295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13978718735426665, -0.02148522962944596, 0.062165479515142216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904449031127, 0.0, 0.0, 0.0, 0.08401380304884362, -0.07655209350823454, 0.629212122040144, -9.457883126845746e-10, -0.22267891881725335, -5.954313511165483e-10, -0.8826455856686328, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.166025233014635, -0.06470266431307567, 0.04094215911014314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21429894897224797, 0.0, 0.0, 0.0, 0.002618918882544759, 0.03089030739639266, 0.3090062986159122, -0.1500000009636665, 0.07829625545545993, -0.10001000057189699, -0.16444487045810013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14807644600964662, -0.024890531278901576, 0.06420539799268152]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044471579091, 0.0, 0.0, 0.0, 0.09499868202689664, -0.06383046572650333, 0.7433691876591096, -1.0103186766167955e-09, -0.26822075821488434, -6.252182749891895e-10, -0.9461164445349441, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16578517310759916, -0.06810603298911234, 0.040798369550785904]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2149489011877622, 0.0, 0.0, 0.0, 0.007887573970318732, 0.027992024360826553, 0.35074106070063243, -0.15000000103470368, 0.06286146034625155, -0.10001000061682119, -0.21428952700062373, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15636696266222688, -0.028532363098245243, 0.06624871376591593]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044310284567, 0.0, 0.0, 0.0, 0.10537310175547943, -0.05796566071132215, 0.8346952416944045, -1.4207435090862836e-09, -0.3086959021841675, -8.984841375973418e-10, -0.9968931308504718, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16581033305160503, -0.07283663638687331, 0.04086631546468815]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2155988533756801, 0.0, 0.0, 0.0, 0.013574763609478475, 0.02512004480954612, 0.39612886856468366, -0.1500000011856277, 0.04510614524715473, -0.10001000071089143, -0.26428952665842814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16467173590768128, -0.03240879334063301, 0.06830022544105084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904375835823, 0.0, 0.0, 0.0, 0.11374379278319485, -0.05743959102560865, 0.9077561572810242, -3.018480627462082e-09, -0.3551063019819364, -1.8814046766948426e-09, -0.9999999931560881, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16609546490908805, -0.07752860484775541, 0.0410302335026982]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624880558416132, 0.0, 0.0, 0.0, 0.0195701845637466, 0.022079443557865976, 0.4444391109026193, -0.15000000128027646, 0.024805426753651952, -0.10001000077052048, -0.3142895262251288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17300153362301599, -0.036489077275742986, 0.07036182699592802]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044169624125, 0.0, 0.0, 0.0, 0.11990841908536248, -0.06081202503360286, 0.9662048467587127, -1.8929750031210578e-09, -0.4060143698700555, -1.1925809209356786e-09, -0.9999999913340133, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16659595430669427, -0.08160567870219951, 0.041232031097543524]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21689875782517948, 0.0, 0.0, 0.0, 0.02507571543406815, 0.019019541055688288, 0.4919217887903812, -0.15000000129044885, 0.005709302944708245, -0.10001000077629935, -0.3642895262142361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18134667132315893, -0.0404091552544216, 0.0723994163209617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044820363286, 0.0, 0.0, 0.0, 0.11011061740643106, -0.06119805004355374, 0.9496535362364198, -2.034479045125849e-10, -0.38192247617887404, -1.155772169569584e-10, -0.999999999782146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16690275400285903, -0.07840155957357217, 0.040751786500673494]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2175487100676129, 0.0, 0.0, 0.0, 0.029566738237343133, 0.016123477460733445, 0.534826901663469, -0.15000000129650115, -0.008432226622555414, -0.10001000077904601, -0.41428952619337234, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18969425976746682, -0.04392129938137812, 0.07438936426831737]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044848668269, 0.0, 0.0, 0.0, 0.08982045606549964, -0.05792127189909688, 0.8581022257141909, -1.2104577163512962e-10, -0.28283059134527316, -5.493327682588649e-11, -0.9999999995827247, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16695176888615754, -0.07024288253913048, 0.03979895894711345]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2181986623086019, 0.0, 0.0, 0.0, 0.03289131700704225, 0.013537664629740438, 0.5694044494975414, -0.15000000130619115, -0.014308749232157287, -0.10001000078430726, -0.46428952615945046, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19803467517427262, -0.04696313308851339, 0.0763249347470274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044819780552, 0.0, 0.0, 0.0, 0.06649157539398237, -0.05171625661986015, 0.6915509151922709, -1.9380019955859497e-10, -0.11753045219203742, -1.0522491493786935e-10, -0.9999999993215625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.166808308136116, -0.06083667414270541, 0.038711409574200446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21884861451131554, 0.0, 0.0, 0.0, 0.035478194901017494, 0.011172048597397682, 0.5994044263852495, -0.15000000141970898, -0.015670159632519286, -0.10001000085700867, -0.5142895256940225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20637256451024763, -0.04973497725553512, 0.07822704641516812]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904405427277, 0.0, 0.0, 0.0, 0.0517375578795048, -0.04731232064685512, 0.5999995377541619, -2.2703566182933645e-09, -0.027228208007239976, -1.4540282671025796e-09, -0.9999999906914403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16675778671950026, -0.055436883340434694, 0.038042233362814364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21949856673946982, 0.0, 0.0, 0.0, 0.037339534981802334, 0.009169766677100004, 0.6219044056770292, -0.1500000014719545, -0.014911802957116527, -0.10001000088843456, -0.5642895255994165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21469855237726354, -0.052246544048200644, 0.08009496639630348]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904456308541, 0.0, 0.0, 0.0, 0.03722680161569686, -0.04004563840595356, 0.4499995858355947, -1.0449104583004981e-09, 0.01516713350805518, -6.285177338949042e-10, -0.9999999981078781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1665197573403182, -0.05023133585331048, 0.03735839962270717]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22014851897708723, 0.0, 0.0, 0.0, 0.03825262879767167, 0.007883870238442581, 0.6331543954465214, -0.15000000149538356, -0.01578357000991264, -0.10001000090277094, -0.6142895255626146, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22297815887216155, -0.05429578125684771, 0.08190853328103219]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044752348156, 0.0, 0.0, 0.0, 0.018261876317386665, -0.02571792877314846, 0.2249997953898433, -4.685810088265969e-10, -0.017435341055922274, -2.867274976067409e-10, -0.9999999992639639, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16559212989796004, -0.040984744172941276, 0.03627133769457415]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22079847107427297, 0.0, 0.0, 0.0, 0.038514727136303564, 0.008636080503649817, 0.6369043948152749, -0.15000000196821664, -0.015892091832484988, -0.10001000117965608, -0.6642895246405037, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2311068407568905, -0.055996229889218416, 0.08365449570296689]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999041943715052, 0.0, 0.0, 0.0, 0.0052419667726378814, 0.015044205304144718, 0.07499998737507146, -9.456661534829018e-09, -0.0021704364514469766, -5.537702924611543e-09, -0.999999981557782, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16257363769457933, -0.03400897264741405, 0.03491924843869405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22144842330513115, 0.0, 0.0, 0.0, 0.03881945612304942, 0.011154258949750803, 0.6369044035262277, -0.15000000200899574, -0.011487368435089115, -0.10001000120312044, -0.7105395228438393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23911980973135064, -0.05777904746653064, 0.08537276922461005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044617163476, 0.0, 0.0, 0.0, 0.0060945797349171065, 0.05036356892201971, 1.7421905419701122e-07, -8.155819163594632e-10, 0.08809446794791743, -4.692872212561633e-10, -0.9249999640667111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16025937948920266, -0.035656351546244504, 0.03436547043286329]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2220983755470146, 0.0, 0.0, 0.0, 0.03927622762773583, 0.013444607113997054, 0.636904421572609, -0.1500000020153329, 0.0011806001796475871, -0.10001000120694956, -0.749289520174343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24716759046477715, -0.059679297099055464, 0.0871037268156016]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044837668753, 0.0, 0.0, 0.0, 0.009135430093728254, 0.04580696328492501, 3.609276266573101e-07, -1.2674293177348148e-10, 0.25335937229473404, -7.658237105106777e-11, -0.7749999466100752, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16095561466853023, -0.03800499265049654, 0.034619151819831114]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22274832779102635, 0.0, 0.0, 0.0, 0.039943362177928536, 0.013315473606233964, 0.6387794305957436, -0.15000000201536612, 0.022987240691859832, -0.10001000120696761, -0.7767895166320455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25540526939811004, -0.06172598241231353, 0.08889130565217934]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880235554, 0.0, 0.0, 0.0, 0.013342691003854046, -0.0025826701552618056, 0.03750018046269218, -6.644023407942464e-13, 0.43613281024424483, -3.6104243104993683e-13, -0.5499999291540503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1647535786666575, -0.040933706265161275, 0.03575157673155471]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22339828003476725, 0.0, 0.0, 0.0, 0.04087015133636385, 0.010472197724812064, 0.6415919351014415, -0.15000000201621036, 0.052409441112288915, -0.10001000120744294, -0.7911568227119044, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2638417197223965, -0.06396724208081127, 0.09074714996818538]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487481819, 0.0, 0.0, 0.0, 0.01853578316870622, -0.05686551762843799, 0.056250090113957416, -1.6884572166468812e-11, 0.5884440084085816, -9.506442957743974e-12, -0.28734612159717715, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16872900648572914, -0.04482519336995479, 0.037116886320120765]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22404823227875492, 0.0, 0.0, 0.0, 0.04205826869255579, 0.006020210347790354, 0.6448731873534732, -0.15000000201631575, 0.08794720144778911, -0.1000100012075052, -0.7961414341315546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.27239516640312517, -0.06641290087758284, 0.09264804995694033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879753268, 0.0, 0.0, 0.0, 0.023762347123838862, -0.0890397475404342, 0.06562504504063298, -2.1077957750996635e-12, 0.7107552067100041, -1.245049128519923e-12, -0.09969222839300354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17106893361457268, -0.0489131759354315, 0.038017999775098996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22469818452259974, 0.0, 0.0, 0.0, 0.0434746343659293, 0.0012324043969994094, 0.648388813471059, -0.15000000201684774, 0.12837740970963563, -0.10001000120783675, -0.7890452771596788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2809794167415028, -0.06904429736985032, 0.09456877758265564]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876896243, 0.0, 0.0, 0.0, 0.028327313467470038, -0.09575611901581889, 0.07031252235171694, -1.0639689063175307e-11, 0.80860416523693, -6.6311075060323085e-12, 0.14192313943751741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17168500676755247, -0.052627929845349655, 0.03841455251430608]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22534813676605597, 0.0, 0.0, 0.0, 0.04498124675421104, -0.00041792293400597785, 0.6483888134603685, -0.1500000020184312, 0.1727215762752165, -0.10001000120892964, -0.7736183517948714, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28932179414282655, -0.07174845631609757, 0.09643376354809557]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869124687, 0.0, 0.0, 0.0, 0.030132247765634834, -0.03300654662010774, -2.1381185710822592e-10, -3.1669148272001986e-11, 0.8868833313116176, -2.1857827975124064e-11, 0.30853850729614873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16684754802647528, -0.05408317892494488, 0.03729971930879857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22599808900899307, 0.0, 0.0, 0.0, 0.044593826822085146, 0.0031113004633590412, 0.6411231873242181, -0.15000000202146163, 0.21722970114480858, -0.10001000121088953, -0.7536106580368721, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.29729848163442857, -0.07391233964049636, 0.09806146422326331]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044858741749, 0.0, 0.0, 0.0, -0.007748398642517973, 0.07058446794730037, -0.14531252272300743, -6.060857174788242e-11, 0.8901624973918414, -3.919794325536845e-11, 0.40015387515998607, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15953374983204063, -0.04327766648797571, 0.03255401350335468]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22664804125208457, 0.0, 0.0, 0.0, 0.04202925890032289, 0.00887338975426367, 0.6238184988797113, -0.15000000202359706, 0.2581517843186256, -0.10001000121225458, -0.7327721958854393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30511671545928915, -0.07488957768074739, 0.0995012534949413]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861830109, 0.0, 0.0, 0.0, -0.05129135843524501, 0.11524178581809255, -0.34609376889013654, -4.270844153977504e-11, 0.8184416634763412, -2.7301075902664952e-11, 0.4167692430286563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15636467649721122, -0.019544760805020545, 0.028795785433559606]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22729799349528942, 0.0, 0.0, 0.0, 0.03752910857169133, 0.01311835411024076, 0.5981479251822706, -0.15000000202597547, 0.2917378257975597, -0.10001000121392567, -0.7148529653400153, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31306297671824385, -0.07436448495134006, 0.1008882119442385]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044864096827, 0.0, 0.0, 0.0, -0.09000300657263124, 0.08489928711954182, -0.5134114739488153, -4.756792315581655e-11, 0.6717208295786815, -3.342196495794877e-11, 0.3583846109084795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15892522517909446, 0.01050185458814649, 0.027739168985944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22794794572785398, 0.0, 0.0, 0.0, 0.032348798228694756, 0.013972630551596706, 0.5678614662230811, -0.1500000020603941, 0.31427355695916304, -0.10001000124147666, -0.703602966353249, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3211571134798725, -0.0729619388440577, 0.10234616764534651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044651291458, 0.0, 0.0, 0.0, -0.1036062068599315, 0.017085528827118904, -0.605729179183789, -6.883727208212485e-10, 0.4507146232320669, -5.51019783099607e-10, 0.22499997973532485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16188273523257396, 0.028050922145647188, 0.02915911402216031]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22859789797052799, 0.0, 0.0, 0.0, 0.027451337165357068, 0.012241376045067167, 0.5367091219999504, -0.15000000206465502, 0.32950897699869386, -0.10001000124484566, -0.7027721989211999, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32936687935545905, -0.07131210264042123, 0.10390949527706811]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044853480014, 0.0, 0.0, 0.0, -0.09794922126675373, -0.03462509013059077, -0.6230468844626139, -8.521864154374937e-11, 0.30470840079061595, -6.737991098427487e-11, 0.016615348640981714, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1641953175117311, 0.032996724072729494, 0.031266552634431934]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22924785021435948, 0.0, 0.0, 0.0, 0.023231430406221817, 0.009398248238906667, 0.5084408925120971, -0.1500000020651964, 0.3411940858667552, -0.10001000124524606, -0.7133298927244414, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3376500754414695, -0.07004128093487509, 0.10554273387207767]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876629973, 0.0, 0.0, 0.0, -0.08439813518270502, -0.05686255612321001, -0.5653645897570648, -1.0827413395217968e-11, 0.2337021773612273, -8.008150535592996e-12, -0.21115387606482938, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1656639217202099, 0.025416434110922745, 0.032664771900191215]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22989780245658992, 0.0, 0.0, 0.0, 0.019752184419195993, 0.00663962338252357, 0.4868067777097906, -0.15000000206972072, 0.3521153006632454, -0.10001000124853848, -0.7333779708001987, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34592728419467145, -0.0691470221300892, 0.10720611157622553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044844608842, 0.0, 0.0, 0.0, -0.06958491974051646, -0.05517249712766193, -0.4326822960461304, -9.048658930382412e-11, 0.21842429592980428, -6.584833837623878e-11, -0.40096156151514706, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.165544175064038, 0.017885176095717666, 0.03326755408295708]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23054775467701452, 0.0, 0.0, 0.0, 0.01695923501367084, 0.0046139850739449085, 0.47555677701410276, -0.15000000213234777, 0.36160889461267165, -0.10001000129405818, -0.761334701318051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3541447263520311, -0.06850157836240235, 0.10887327525738888]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044408492038, 0.0, 0.0, 0.0, -0.05585898811050306, -0.04051276617157322, -0.22500001391375637, -1.252541023608236e-09, 0.1898718789885241, -9.103939178537349e-10, -0.5591346103570455, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16434884314719328, 0.012908875353737045, 0.03334327362326693]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23119770691872243, 0.0, 0.0, 0.0, 0.015108443679219588, 0.003358437716285252, 0.47618177540676676, -0.15000000213859438, 0.3659248681517152, -0.10001000129879484, -0.7957000856811232, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.36230178362013554, -0.06818991729018775, 0.11055061584137026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044834158466, 0.0, 0.0, 0.0, -0.037015826689025005, -0.02511094715319313, 0.012499967853280197, -1.2493217186473585e-10, 0.08631947078087118, -9.473301808023121e-11, -0.6873076872614428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16314114536208946, 0.006233221444291878, 0.03354681167962762]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23184765916274108, 0.0, 0.0, 0.0, 0.014074408407971983, 0.0028643257159356762, 0.48643177215476957, -0.15000000213860648, 0.361326735786973, -0.10001000129880386, -0.8351923931714781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37040268321628145, -0.06817406860428807, 0.11223464015375724]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880372793, 0.0, 0.0, 0.0, -0.0206807054249521, -0.00988224000699152, 0.20499993496005656, -2.4223308007021127e-13, -0.09196264729484463, -1.804787208165055e-13, -0.7898461498070983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16201799192291827, 0.0003169737179937772, 0.03368048624773972]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23249761140674877, 0.0, 0.0, 0.0, 0.013189411911339247, 0.0037822440556639523, 0.5025567672655873, -0.15000000213864853, 0.3477006290567524, -0.10001000129883539, -0.8787862391634265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3783910977643558, -0.06814521553805562, 0.11388663608743756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880153547, 0.0, 0.0, 0.0, -0.017699929932654714, 0.01835836679456552, 0.322499902205311, -8.411210218482996e-13, -0.2725221346044111, -6.306257763603e-13, -0.8718769198389668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15976829096148737, 0.0005770613246488775, 0.033039918673606394]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2331475636497501, 0.0, 0.0, 0.0, 0.01274010671888727, 0.006653638423222915, 0.5230880116977709, -0.15000000214221043, 0.3287965479603944, -0.10001000130158842, -0.9227316236581125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3862352959921521, -0.0683864075684979, 0.11551394489501998]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044860026319, 0.0, 0.0, 0.0, -0.008986103849039537, 0.05742788735117925, 0.41062488864367086, -7.123784629835075e-11, -0.37808162192715994, -5.506070179638836e-11, -0.8789076898937189, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15688396455592588, -0.004823840608845435, 0.032546176151648495]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2337975158914001, 0.0, 0.0, 0.0, 0.013038307217587454, 0.010194599707327286, 0.5469239431234003, -0.15000000214892542, 0.3083644924970208, -0.10001000130674031, -0.963278546656329, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3940636233018449, -0.06919891335438824, 0.11716344641027228]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044833000307, 0.0, 0.0, 0.0, 0.00596400997400366, 0.07081922568208743, 0.47671862851258795, -1.3430000596931742e-10, -0.4086411092674719, -1.0303789776927164e-10, -0.8109384599643291, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1565665461938554, -0.01625011571780697, 0.03299003030504582]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23444746813074982, 0.0, 0.0, 0.0, 0.013740858263575562, 0.012638223719674792, 0.5703145615424868, -0.15000000216037793, 0.2901544626656275, -0.10001000131645839, -0.9966770081597888, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.40202050257218275, -0.07048310333424881, 0.1188598460112494]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044786994532, 0.0, 0.0, 0.0, 0.014051020919762174, 0.04887248024695014, 0.46781236838172946, -2.290498776721859e-10, -0.36420059662786586, -1.943614459247949e-10, -0.6679692300691954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1591375854067563, -0.025683799597211315, 0.03392799201954224]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2350974203737984, 0.0, 0.0, 0.0, 0.014955331032671172, 0.011604165875700762, 0.5934083046299652, -0.15000000216312895, 0.27791645846592034, -0.10001000131853546, -1.0191770081691829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.41027790878090725, -0.07233822458521512, 0.12065641631914688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044860972038, 0.0, 0.0, 0.0, 0.0242894553819122, -0.02068115687948062, 0.4618748617495662, -5.502034853981952e-11, -0.24476008399414345, -4.154146746129631e-11, -0.4500000001878811, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1651481241744898, -0.03710242501932607, 0.035931406157949784]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23574737261760623, 0.0, 0.0, 0.0, 0.016394512955013554, 0.006899708590855895, 0.6124551724419617, -0.15000000216374784, 0.27540047989643035, -0.10001000131898254, -1.0272226139092842, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4188085067868335, -0.07461658135674354, 0.12255618315726981]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487615656, 0.0, 0.0, 0.0, 0.028783638446847625, -0.09408914569689733, 0.3809373551174139, -1.2377700941062604e-11, -0.05031957138979978, -8.941487090719246e-12, -0.16091211480202472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17061196011852514, -0.045567135430568284, 0.037995336762458636]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23639732486108012, 0.0, 0.0, 0.0, 0.017954208660827902, 0.00038769515953522224, 0.6294786013540644, -0.15000000216533654, 0.28272716086029154, -0.10001000132012605, -1.0245638253795792, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4274878491607696, -0.07716158849176591, 0.12450891902828394]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869477736, 0.0, 0.0, 0.0, 0.03119391411628697, -0.13024026862641344, 0.3404685782420551, -3.177427891735283e-11, 0.1465336192772237, -2.287045036912248e-11, 0.05317577059409745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17358684747872202, -0.05090014270044731, 0.03905471742028254]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23704727708853102, 0.0, 0.0, 0.0, 0.019595238382647505, -0.006186210501127249, 0.6407285915987881, -0.15000000221364113, 0.2998098416587551, -0.10001000135554115, -1.014950642557207, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.43620007477791106, -0.0799273250719775, 0.12647558585051877]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044549018042, 0.0, 0.0, 0.0, 0.03282059443639208, -0.13147811321324943, 0.22499980489447402, -9.660918503018834e-10, 0.3416536159692719, -7.083020244247227e-10, 0.19226365644744525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17424451234282906, -0.055314731604231726, 0.03933333644469656]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23769722933147222, 0.0, 0.0, 0.0, 0.021193709516988846, -0.01156823698700874, 0.644478586661093, -0.15000000221683743, 0.32529540897289355, -0.10001000135799502, -0.9990899469592981, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.44484646364072694, -0.0827820205050434, 0.12842213723748394]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044858823874, 0.0, 0.0, 0.0, 0.03196942268682679, -0.10764052971762979, 0.07499990124609829, -6.392588302726097e-11, 0.5097113462827683, -4.907738875094875e-11, 0.3172139119581795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17292777725631758, -0.05709390866131789, 0.038931027739303486]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23834718157299928, 0.0, 0.0, 0.0, 0.02259356687578448, -0.013689920189146793, 0.644478586445503, -0.1500000022243237, 0.35768386278143266, -0.10001000136406646, -0.9746227007117132, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45322340294592484, -0.08551520448957664, 0.13028843390253014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044830541071, 0.0, 0.0, 0.0, 0.027997147175912673, -0.04243366404276108, -4.311800125278431e-09, -1.49725125214992e-10, 0.6477690761707817, -1.214286615507006e-10, 0.4893449249516969, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1675387861039576, -0.05466367969066488, 0.037325933300923965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23899713381693238, 0.0, 0.0, 0.0, 0.02198794827128701, -0.009807933133245215, 0.6369785909522214, -0.15000000222460222, 0.393225203084402, -0.10001000136429544, -0.9452989038144342, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46112708197048996, -0.0875263341987617, 0.1319055943129928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044878662325, 0.0, 0.0, 0.0, -0.012112372089949378, 0.07763974111803158, -0.1499999098656319, -5.570463667068821e-12, 0.7108268060593866, -4.579807417806986e-12, 0.5864759379455804, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15807358049130285, -0.04022259418370118, 0.03234320820925342]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23964708605875154, 0.0, 0.0, 0.0, 0.01924953489751336, -0.0024064016981249605, 0.6194785947113135, -0.1500000022301561, 0.42816942988203055, -0.10001000136860272, -0.914868556267287, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4687257816014547, -0.08816489259751556, 0.13332803047291533]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836383247, 0.0, 0.0, 0.0, -0.05476826747547296, 0.14803062870240508, -0.3499999248181588, -1.1107781478374616e-10, 0.6988845359525706, -8.614543769825366e-11, 0.6086069509429433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15197399261929523, -0.012771167975077217, 0.028448723198450175]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24029703830272695, 0.0, 0.0, 0.0, 0.01472591483244424, 0.004764674176395066, 0.5936452645106434, -0.15000000223029936, 0.45876654317432763, -0.1000100013687244, -0.8870816580702633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4764017455822124, -0.08745197305992548, 0.13469279569661563]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879508329, 0.0, 0.0, 0.0, -0.0904724013013824, 0.14342151749040052, -0.5166666040134021, -2.864659719662059e-12, 0.6119422658459418, -2.4336255491093905e-12, 0.5557379639404746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15351927961515244, 0.014258390751801565, 0.02729530447400588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24094699054657165, 0.0, 0.0, 0.0, 0.009260006483324704, 0.007955294791641102, 0.5632286003095943, -0.15000000223079013, 0.481266542961808, -0.10001000136918381, -0.8656882092231303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4843298768656265, -0.08599248541580573, 0.13615884028728406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876894301, 0.0, 0.0, 0.0, -0.10931816698239069, 0.06381241230492074, -0.608333284020982, -9.815610189438853e-12, 0.4499999957496069, -9.188178349786448e-12, 0.42786897694266046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1585626256682823, 0.02918975288239512, 0.029320891813368756]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2415969427825432, 0.0, 0.0, 0.0, 0.004012219833836244, 0.006942920278873571, 0.531978602079852, -0.1500000022533208, 0.49425984585428906, -0.1000100013904639, -0.8544382096806061, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.492474849984536, -0.0844200048346356, 0.1377734722815161]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044719430934, 0.0, 0.0, 0.0, -0.10495573298976921, -0.02024749025535061, -0.6249999645948462, -4.506131597121238e-10, 0.25986605784962186, -4.2560178950768006e-10, 0.22499999085048222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1628994623781901, 0.03144961162340244, 0.03229263988464072]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24224689502591307, 0.0, 0.0, 0.0, -0.00048814112458583133, 0.003543864738374717, 0.5036452698164533, -0.15000000225511312, 0.5014964503560285, -0.10001000139214415, -0.8563132100543398, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.500787819043769, -0.08321130916375588, 0.1394876043478745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044867397367, 0.0, 0.0, 0.0, -0.0900072191684415, -0.06798111080997707, -0.5666666452679747, -3.5846525830872954e-11, 0.14473209003478998, -3.36050351925568e-11, -0.0375000074746743, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16625938118465913, 0.024173913417594457, 0.03428264132716804]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24289684726806, 0.0, 0.0, 0.0, -0.004168229766679911, -0.0003219529251795852, 0.48197860348883503, -0.1500000022600385, 0.5067262747293185, -0.10001000139657612, -0.8691257103293859, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5091421999015469, -0.0823590808814413, 0.1412363811028138]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904484293847, 0.0, 0.0, 0.0, -0.0736017728418816, -0.07731635327108605, -0.43333332655236567, -9.850760092762137e-11, 0.1045964874658, -8.863933029665228e-11, -0.2562500055009216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16708761715555687, 0.017044565646291587, 0.0349755350987865]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24354679950988234, 0.0, 0.0, 0.0, -0.006888250947228752, -0.00352720357974074, 0.4707286030617599, -0.15000000226590895, 0.5096201197264563, -0.10001000140183516, -0.8910527938526906, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.517447724564752, -0.08184447874476872, 0.14298860405420677]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904483644681, 0.0, 0.0, 0.0, -0.05440042361097681, -0.06410501309122309, -0.22500000854150223, -1.1740913168691173e-10, 0.057876899942755286, -1.0518076615243323e-10, -0.43854167046609543, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16611049326410152, 0.010292042733451518, 0.03504445902785944]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24419675175192818, 0.0, 0.0, 0.0, -0.008672049648762434, -0.005648944735906632, 0.4713033959179685, -0.15000000227110377, 0.5090408388385431, -0.10001000140646096, -0.9205753634145297, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5256659908531884, -0.08163061162027141, 0.1447306024122858]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044840916844, 0.0, 0.0, 0.0, -0.03567597403067362, -0.042434823123317846, 0.011495857124171532, -1.0389633925641154e-10, -0.011585617758261946, -9.251611829696118e-11, -0.5904513912367821, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16436532576872934, 0.004277342489946094, 0.03483996716158089]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24484670375961787, 0.0, 0.0, 0.0, -0.009649236282535143, -0.00671961444572953, 0.48150646876707304, -0.15000000285772597, 0.5028295100813256, -0.10001000193299572, -0.9561934121253606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.533800844549945, -0.08168334751616103, 0.1464601401128604]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904015379394, 0.0, 0.0, 0.0, -0.019543732675454197, -0.021413394196457967, 0.20406145698209088, -1.173244403942478e-08, -0.12422657514435131, -1.0530695122209537e-08, -0.7123609742166166, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16269707393513103, -0.0010547179177925158, 0.03459075401149231]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24549665572200083, 0.0, 0.0, 0.0, -0.010107392188387245, -0.006714201994857078, 0.49941867762422726, -0.15000000356932516, 0.48723627053088364, -0.100010002574971, -0.9966878427374076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5418515809451242, -0.08187682679111444, 0.14816955892984807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999039247659284, 0.0, 0.0, 0.0, -0.009163118117042018, 0.00010824901744903304, 0.3582441771430843, -1.4231983810202587e-08, -0.3118647910088392, -1.283950568919665e-08, -0.8098886122409407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16101472790358415, -0.0038695854990680872, 0.03418837633975339]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24614660796571572, 0.0, 0.0, 0.0, -0.010377610247803867, -0.004767636493328833, 0.5212903254323229, -0.150000003570115, 0.4660111201864633, -0.10001000257567925, -1.0410833872156853, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5497403003809942, -0.08216035164431038, 0.1498322788152291]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874297847, 0.0, 0.0, 0.0, -0.005404361188332428, 0.03893131003056491, 0.43742689730423295, -1.5797053598165124e-11, -0.4245030068884067, -1.4165099103277334e-11, -0.8879108895655533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15777438871739963, -0.005670497063918804, 0.03325439770762069]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24679656020925456, 0.0, 0.0, 0.0, -0.010195590803734318, -0.0011561047988294243, 0.5461313321878922, -0.15000000357149273, 0.44290405904791824, -0.10001000257696065, -1.0856300455603276, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.557508535978402, -0.08279373788033606, 0.15147089576791598]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044870776738, 0.0, 0.0, 0.0, 0.003640388881390984, 0.07223063388998818, 0.4968201351113864, -2.7554565827704738e-11, -0.4621412227709009, -2.562788036423942e-11, -0.8909331668928461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15536471194815493, -0.0126677247205138, 0.03277233905373779]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24744651244974744, 0.0, 0.0, 0.0, -0.00980040929878985, 0.0026811407611621314, 0.5701920008369606, -0.150000003579875, 0.42166508711470707, -0.10001000258577943, -1.1265778177718353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5652999796635733, -0.08374799523424048, 0.15311495318724236]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044809857632, 0.0, 0.0, 0.0, 0.00790363009888935, 0.07674491119983112, 0.4812133729186726, -1.6764552904344134e-10, -0.42477943866422324, -1.7637547870830137e-10, -0.8189554442301539, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15582887370342552, -0.01908514707808846, 0.03288114838652776]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24809646469084198, 0.0, 0.0, 0.0, -0.008983763684291723, 0.0037639190099873696, 0.5937324440748326, -0.15000000358810514, 0.4060442043864778, -0.10001000259424908, -1.1601767038505864, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5733606946047325, -0.08519883147721558, 0.15483561533202042]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044821890822, 0.0, 0.0, 0.0, 0.01633291228996256, 0.021655564976504754, 0.4708088647574393, -1.646026384417975e-10, -0.31241765456458537, -1.6939307751881575e-10, -0.6719777215750204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16121429882318572, -0.02901672485950179, 0.03441324289556128]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2487464169304844, 0.0, 0.0, 0.0, -0.007944313047067492, 0.0007044563268547351, 0.6130026619101681, -0.15000000359857432, 0.3997914108624564, -0.10001000260569375, -1.182676703797343, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5817682839615067, -0.08708266944779683, 0.15667030524756712]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044792848635, 0.0, 0.0, 0.0, 0.02078901274448461, -0.06118925366265268, 0.3854043565962808, -2.0938386449979712e-10, -0.12505587048042807, -2.2889328417987563e-10, -0.4499999989351295, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16815178713548443, -0.037676759411625016, 0.03669379831093371]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24939636866964474, 0.0, 0.0, 0.0, -0.006902114365735982, -0.00570625026803921, 0.6242526543376133, -0.15000000445483958, 0.40566466350172675, -0.10001000328112325, -1.1914295802025956, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5904387120262181, -0.08924411062668099, 0.15860229137978665]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999034783206334, 0.0, 0.0, 0.0, 0.020843973626630194, -0.1282141318978789, 0.22499984854890487, -1.7125304837134286e-08, 0.11746505278540734, -1.350859021019295e-08, -0.17505752810505587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17340856129422802, -0.043228823577683186, 0.03863972264439093]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2500463209133398, 0.0, 0.0, 0.0, -0.0060506561184218, -0.01289713247522516, 0.6306063122218272, -0.15000000445554768, 0.4199139623046952, -0.1000100032817105, -1.1901853330661696, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5991910197889214, -0.09142313248726645, 0.16055388198092427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044873900675, 0.0, 0.0, 0.0, 0.017029164946283655, -0.143817644143719, 0.127073157684277, -1.4161816640906512e-11, 0.28498597605936826, -1.1745030547207762e-11, 0.02488494272852204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17504615525406536, -0.043580437211709296, 0.03903181202275252]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2506962731178172, 0.0, 0.0, 0.0, -0.005397563568633427, -0.01902707483766551, 0.6358134010941479, -0.15000000456046234, 0.43998241016291806, -0.10001000337675249, -1.1826939623471984, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6078722636958098, -0.09349907653627267, 0.16247600787861916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904408954848, 0.0, 0.0, 0.0, 0.013061850995767451, -0.12259884724880701, 0.10414177744641392, -2.0982932927398097e-09, 0.4013689571644573, -1.9008398997767702e-09, 0.14982741437942454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17362487813776764, -0.0415188809801242, 0.03844251795389762]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2513462253513273, 0.0, 0.0, 0.0, -0.004823088089091537, -0.02349975414795299, 0.6390381938185379, -0.1500000045882679, 0.4672753028764694, -0.10001000340262074, -1.172705468033193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6164230543834146, -0.09551754006144239, 0.16435404335766032]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044670201071, 0.0, 0.0, 0.0, 0.011489509590837802, -0.08945358620574961, 0.06449585448779967, -5.561114383596229e-10, 0.5458578542710268, -5.17364935186227e-10, 0.1997698862801058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17101581375209543, -0.040369270503394436, 0.037560709580823304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25199617753195014, 0.0, 0.0, 0.0, -0.004268154303310389, -0.02638712934007061, 0.6425096591430016, -0.15000000475591305, 0.5011096062155245, -0.1000100035806168, -1.1583913599522733, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6248365040523479, -0.09749544120402881, 0.16618701485665827]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043612456993, 0.0, 0.0, 0.0, 0.01109867571562296, -0.05774750384235234, 0.06942930648927527, -3.352903141673128e-09, 0.6766860667811023, -3.5599212131519184e-09, 0.28628216161839204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16826899337866677, -0.03955802285172845, 0.03665942997995904]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2526461297737612, 0.0, 0.0, 0.0, -0.003795661432659677, -0.025840059903537965, 0.6461203892176793, -0.15000000476435538, 0.5394751103095166, -0.10001000358976507, -1.143501638099991, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6329072411536976, -0.09936363026747207, 0.16792217823073058]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836221465, 0.0, 0.0, 0.0, 0.009449857413014236, 0.010941388730652903, 0.07221460149355459, -1.688464524953272e-10, 0.767310081879841, -1.8296518606956624e-10, 0.2977944370456482, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16141474202699277, -0.037363781268865234, 0.03470326748144654]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2532960820177071, 0.0, 0.0, 0.0, -0.004646401928232452, -0.021765843092444774, 0.6461203840426114, -0.15000000476455602, 0.5786218151584571, -0.10001000358995357, -1.131786302476316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6406485298400609, -0.10048794275929654, 0.1695155899713417]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044878917638, 0.0, 0.0, 0.0, -0.017014809911455507, 0.08148433622186385, -1.0350135815073713e-07, -4.012635972534725e-12, 0.7829340969788106, -3.770040695945876e-12, 0.23430671247349766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15482577372726838, -0.02248624983648953, 0.03186823481222253]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25394603423143336, 0.0, 0.0, 0.0, -0.006895452834509845, -0.017740698972948988, 0.638759643640322, -0.15000000484768655, 0.614799720767078, -0.10001000368132468, -1.1269953530423473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6484267484068842, -0.10079636349627738, 0.17106063989428508]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044274525421, 0.0, 0.0, 0.0, -0.044981018125547854, 0.08050288238991571, -0.14721480804578715, -1.662610588068856e-09, 0.7235581121724168, -1.8274220637202932e-09, 0.09581898867937447, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15556437133646414, -0.006168414739616806, 0.030900998458867582]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2545959864744359, 0.0, 0.0, 0.0, -0.009950760847136978, -0.016745304251679603, 0.6234004948394937, -0.15000000484979625, 0.6442588271370862, -0.10001000368423207, -1.1328787897953214, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6564849805353146, -0.10069775247460928, 0.17269152124734863]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044860050126, 0.0, 0.0, 0.0, -0.06110616025254266, 0.019907894425387734, -0.3071829760165674, -4.2193815529858164e-11, 0.5891821274001621, -5.814790798825068e-11, -0.11766873505948228, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16116464256860855, 0.00197222043336193, 0.03261762706127116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2552459377246717, 0.0, 0.0, 0.0, -0.013195267963204664, -0.018431299649025883, 0.6037929376068366, -0.15000000487543433, 0.6644226156439798, -0.1000100037140889, -1.1468941459961746, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6647703730797146, -0.10054961585287966, 0.17441604925946227]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999025004716764, 0.0, 0.0, 0.0, -0.0648901423213537, -0.03371990794692561, -0.3921511446531417, -5.127616579030929e-10, 0.4032757701378722, -5.971364028593951e-10, -0.2803071240170649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16570785088800064, 0.0029627324345924168, 0.03449056024227303]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25589588996622215, 0.0, 0.0, 0.0, -0.016228992035135757, -0.021303872614366243, 0.5836869719376038, -0.1500000048784462, 0.6777772714893643, -0.10001000371775856, -1.166796538421553, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6731755898880346, -0.10050510625320491, 0.17618232050667443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044831009133, 0.0, 0.0, 0.0, -0.06067448143862185, -0.05745145930680718, -0.40211931338465773, -6.023722949324673e-11, 0.26709311690769166, -7.339329352619006e-11, -0.39804784850757163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16810433616639833, 0.0008901919934949723, 0.035325424944242886]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25654584199944663, 0.0, 0.0, 0.0, -0.018821682248450718, -0.02406620989989246, 0.5668325972003992, -0.15000000514882206, 0.6874138472151763, -0.10001000401790613, -1.1932351417780716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6815721534222468, -0.10060781885612195, 0.17795060461117523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999040664489621, 0.0, 0.0, 0.0, -0.051853804266299215, -0.055246745710524355, -0.33708749474409005, -5.407517433817161e-09, 0.19273151451624104, -6.002951402909067e-09, -0.5287720671303698, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16793127068424282, -0.0020542520583409253, 0.0353656820900163]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2571957942368065, 0.0, 0.0, 0.0, -0.021030526070991526, -0.02583122405480676, 0.5569797803526632, -0.15000000516158715, 0.6935965170272611, -0.10001000403853104, -1.2260927865425424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6898628081806145, -0.10075490095039759, 0.1796898247121083]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044747197394, 0.0, 0.0, 0.0, -0.04417687645081614, -0.03530028309828599, -0.19705633695472205, -2.5530202171910014e-10, 0.12365339624169644, -4.1249800761350907e-10, -0.657152895289418, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16581309516735432, -0.002941641885512644, 0.03478440201866129]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25784574642766844, 0.0, 0.0, 0.0, -0.023193199089211716, -0.02584941673978691, 0.552586631753888, -0.15000000528853683, 0.6925752814900638, -0.1000100042521587, -1.2643789002499701, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6979752964488379, -0.10071916093802642, 0.18137068635731157]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904381723864, 0.0, 0.0, 0.0, -0.043253460364403785, -0.0003638536996029701, -0.08786297197550341, -2.5389933942581746e-09, -0.020424710743946306, -4.27255323824e-09, -0.7657222741485548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1622497653644684, 0.0007148002474231877, 0.033617232904065465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2584956986515413, 0.0, 0.0, 0.0, -0.02479396679382947, -0.023526917884262886, 0.5558542686467571, -0.15000000535675037, 0.68810014052081, -0.10001000434367516, -1.307007788960623, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7058356430445942, -0.10085989692740603, 0.18299244497127226]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044477457056, 0.0, 0.0, 0.0, -0.032015354092355106, 0.04644997711048044, 0.06535273785738177, -1.364270949504064e-09, -0.08950281938507451, -1.8303290893366554e-09, -0.8525777742130605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15720693191512572, -0.0028147197875922764, 0.03243517227921405]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25914565088290237, 0.0, 0.0, 0.0, -0.02566693450687854, -0.019936623504859793, 0.5648674950700266, -0.1500000053931401, 0.6839210941172903, -0.10001000441741272, -1.3502294526759393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7135752476167202, -0.10137984999814018, 0.184593289681007]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044627221394, 0.0, 0.0, 0.0, -0.0174593542609814, 0.07180588758806183, 0.18026452846539098, -7.277945399223232e-10, -0.08358092807039383, -1.4747512226103276e-09, -0.8644332743063232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1547920914425192, -0.010399061414682758, 0.032016894194694445]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2597956031263604, 0.0, 0.0, 0.0, -0.025774748556258654, -0.01780445682302976, 0.5781899136583082, -0.15000000539493336, 0.6837881422794766, -0.10001000483271755, -1.3902938913959322, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7214844368774657, -0.10240231562622805, 0.18624795103452463]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869160528, 0.0, 0.0, 0.0, -0.0021562809876022396, 0.04264333363660069, 0.26644837176563047, -3.586512766477454e-11, -0.0026590367562732004, -8.306096680008556e-09, -0.8012887743998566, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1581837852149095, -0.020449312561757374, 0.0330932270703528]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2598658852087168, 0.0, 0.0, 0.0, -0.02417105347374379, -0.018942077460056456, 0.5920715244118882, -0.1500000058581311, 0.6914512850049533, -0.10169252931425445, -1.4234511051218284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.729803611555447, -0.10451569445043497, 0.18813570409939795]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056416471276301, 0.0, 0.0, 0.0, 0.032073901650297325, -0.02275241274053396, 0.27763221506596825, -9.263955299595153e-09, 0.15326285450953497, -0.03365048963073792, -0.6631442745179232, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1663834935596275, -0.042267576484138536, 0.0377550612974664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2598603358381357, 0.0, 0.0, 0.0, -0.02202400190327803, -0.025848615029055704, 0.6063259299086122, -0.15000001787717726, 0.7090872372511039, -0.10370817414853585, -1.4459510938623377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7386427048135271, -0.10735032155569993, 0.1902912404780716]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098741162081198, 0.0, 0.0, 0.0, 0.042941031409315204, -0.13813075137998493, 0.28508810993448075, -2.4038092315470945e-07, 0.35271904492301215, -0.0403128966856282, -0.4499997748101875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1767818651616023, -0.05669254210529909, 0.0431107275734735]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25985801560027416, 0.0, 0.0, 0.0, -0.020214435002908024, -0.03559371235320291, 0.6181760778774441, -0.15027348704013516, 0.7333912749795579, -0.1048132576179428, -1.4548134931372068, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7477504944094632, -0.11031579167708203, 0.19256178158061815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.640475723094991e-05, 0.0, 0.0, 0.0, 0.03619133800740016, -0.19490194648294412, 0.23700295937663768, -0.005469383259157716, 0.48608075456907973, -0.022101669388138966, -0.1772479854973803, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1821557919187207, -0.05930940242764186, 0.04541082205093094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25985783795362477, 0.0, 0.0, 0.0, -0.01914926631370249, -0.04442736973464008, 0.6257676971349708, -0.15034678696107948, 0.7614978488738366, -0.10530275890264636, -1.45305751232337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7567200478965508, -0.11285491159674448, 0.1947570197550181]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.552932987545649e-06, 0.0, 0.0, 0.0, 0.02130337378411068, -0.1766731476287434, 0.15183238515053366, -0.0014659984188861268, 0.5621314778855735, -0.009790025694071206, 0.03511961627673374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1793910697417529, -0.05078239839324906, 0.04390476348799888]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25985786735649136, 0.0, 0.0, 0.0, -0.01874579893060344, -0.049482077596133725, 0.6307538165912997, -0.1503467885954998, 0.7944038074411464, -0.10537629818489141, -1.4413325447469143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7652820814043271, -0.114858609128315, 0.19678904466533048]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.880573317755398e-07, 0.0, 0.0, 0.0, 0.008069347661981002, -0.10109415722987282, 0.0997223891265775, -3.268840632550396e-08, 0.6581191713461934, -0.001470785644901081, 0.23449935152911297, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.171240670155526, -0.04007395063141043, 0.0406404982062476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26050781952266383, 0.0, 0.0, 0.0, -0.019583930036423027, -0.048049099453531, 0.6302141944918352, -0.15034678880078067, 0.8283591508099767, -0.10353806952890039, -1.4233885903872465, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7731326366810041, -0.11594590930939756, 0.19856856776498627]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043323449155, 0.0, 0.0, 0.0, -0.01676262211639175, 0.028659562852054468, -0.010792441989288179, -4.105617712921411e-09, 0.6791068673766075, 0.0367645731198204, 0.35887908719335504, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15701110553353909, -0.021746003621651324, 0.035590461993115614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26115777176225796, 0.0, 0.0, 0.0, -0.02236125756937396, -0.04170637512103204, 0.6203988308394888, -0.15034678881359276, 0.8596138789811012, -0.10353806953984153, -1.4029756492438499, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7804519018834217, -0.11574963602150377, 0.20011582256470034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044791882287, 0.0, 0.0, 0.0, -0.05554655065901866, 0.12685448664997923, -0.19630727304692952, -2.5624163825232143e-10, 0.6250945634224909, -2.188227307686752e-10, 0.4082588228679334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14638530404835404, 0.003925465757875682, 0.030945095994281354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.261807724004747, 0.0, 0.0, 0.0, -0.026688774749956515, -0.034203904573014914, 0.6009693611293708, -0.1503467888159505, 0.8844179919545457, -0.10353806954128617, -1.383843721316707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7878314094938836, -0.11459351614808005, 0.20159368555766696]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044849781061, 0.0, 0.0, 0.0, -0.08655034361165108, 0.15004941096034263, -0.3885893942023597, -4.7155321064671516e-11, 0.49608225946889145, -2.8892788967273624e-11, 0.38263855854285644, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14759015220923732, 0.023122397468474356, 0.029557259859332212]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26187800634666525, 0.0, 0.0, 0.0, -0.031533727911692164, -0.029291682645900794, 0.5737364213625592, -0.15174754438186744, 0.8990214940137036, -0.10353808182325872, -1.3697428036929775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7956308157976005, -0.11303804465602316, 0.20341647774533198]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056468383654118, 0.0, 0.0, 0.0, -0.09689906323471295, 0.09824443854228238, -0.5446587953362328, -0.028015111318338573, 0.2920700411831571, -2.456394510039133e-07, 0.2820183524745896, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15598812607433857, 0.03110942984113791, 0.036455843753300174]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26187245699306955, 0.0, 0.0, 0.0, -0.03646935087116352, -0.029144166586206322, 0.541526632055496, -0.15468248121517883, 0.9018810938245759, -0.10353808527542419, -1.3644191712358333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8038544899256512, -0.11164247993154357, 0.20566070640730655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0001109870719135308, 0.0, 0.0, 0.0, -0.09871245918942712, 0.002950321193889438, -0.6441957861412642, -0.0586987366662277, 0.057191996217446694, -6.904330948531505e-08, 0.10647264914288174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1644734825610141, 0.027911294489591773, 0.044884573239491694]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26187013675092996, 0.0, 0.0, 0.0, -0.0413971383518849, -0.031251057577658704, 0.5074028613863277, -0.1584889736330377, 0.8957183844188342, -0.10365788700857188, -1.3669620504449431, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8123486975096323, -0.11036797471090136, 0.2080869596978349]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6404842792183927e-05, 0.0, 0.0, 0.0, -0.09855574961442765, -0.042137819829047685, -0.6824754133833661, -0.07612984835717752, -0.12325418811483488, -0.002396034662953854, -0.05085758418219716, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16988415167962173, 0.02549010441284403, 0.048525065810566634]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2618699591089978, 0.0, 0.0, 0.0, -0.0465196218576904, -0.03193175666002731, 0.4718185293511527, -0.16129434808582155, 0.8814450821156392, -0.10477586922521916, -1.3776460979375869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8207303711550354, -0.10914159028211846, 0.21041284500792268]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.5528386437629986e-06, 0.0, 0.0, 0.0, -0.10244967011610996, -0.013613981647372052, -0.7116866407035009, -0.0561074890556765, -0.28546604606390097, -0.022359644332945353, -0.2136809498528738, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16763347290806171, 0.02452768857565786, 0.04651770620175569]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2625199112062968, 0.0, 0.0, 0.0, -0.05232190415753779, -0.02813769586557966, 0.4385236357297044, -0.16082203578437945, 0.8628111867706117, -0.10345986616196146, -1.397765922976405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8284889534752338, -0.10743731253478052, 0.21242640529267992]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999041945980335, 0.0, 0.0, 0.0, -0.1160456459969478, 0.07588121588895298, -0.6658978724289663, 0.009446246028841684, -0.37267790690054853, 0.026320061265153957, -0.402396500776364, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15517164640396613, 0.03408555494675899, 0.04027120569514496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26316986344983917, 0.0, 0.0, 0.0, -0.05799782284951898, -0.020411801299310438, 0.41126818052191066, -0.15871087963536779, 0.8435666983837111, -0.10345986919047581, -1.4235715255614179, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8356711644763805, -0.10527193116889255, 0.21417101264257513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044870847146, 0.0, 0.0, 0.0, -0.11351837383962377, 0.15451789132538443, -0.5451091041558741, 0.042223122980233375, -0.38488976773801237, -6.057028700823253e-08, -0.5161120517002588, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14364422002293442, 0.04330762731775935, 0.0348921469979039]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638198130355039, 0.0, 0.0, 0.0, -0.060630343238567336, -0.012504038986998043, 0.3938021636994627, -0.15578030511294264, 0.8274616169396686, -0.1085139049548833, -1.4513129056978176, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8428783647974224, -0.10315233270220363, 0.2162715984536831]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998991713294576, 0.0, 0.0, 0.0, -0.05265040778096719, 0.15815524624624785, -0.34932033644895893, 0.058611490448503105, -0.32210162888085025, -0.10108071528814994, -0.5548276027279956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14414400642083908, 0.04239196933377841, 0.0420117162221593]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26389009461883645, 0.0, 0.0, 0.0, -0.060874581884900324, -0.008164408321550364, 0.3898755852540028, -0.15371341282255718, 0.8182459424374798, -0.11783109106975892, -1.477240063386274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8506935690837899, -0.1015836444951585, 0.21906237470241008]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056316666514815, 0.0, 0.0, 0.0, -0.004884772926659696, 0.08679261330895359, -0.07853156890919855, 0.04133784580770933, -0.1843134900437745, -0.1863437222975124, -0.5185431537691267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15630408572735097, 0.03137376414090247, 0.05581552497453941]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638845444118319, 0.0, 0.0, 0.0, -0.06060900216223089, -0.011140369943549373, 0.3968326881756824, -0.15615056188602797, 0.8196695839111771, -0.12811763682751465, -1.4976030098797966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8590870106409448, -0.10072675303650415, 0.22265959708652802]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011100414009110977, 0.0, 0.0, 0.0, 0.005311594453388689, -0.059519232439980155, 0.13914205843359176, -0.048742981269415675, 0.028472829473944722, -0.20573091515511469, -0.40725892987045376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16786883114309784, 0.017137829173087076, 0.0719444476823588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638822240713975, 0.0, 0.0, 0.0, -0.0602908624161976, -0.019011111589700445, 0.410923472649284, -0.1618319591349285, 0.8279825434747106, -0.13909637762643665, -1.5097609410947894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8679083050354681, -0.10031456351001095, 0.22679450655272088]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6406808688028735e-05, 0.0, 0.0, 0.0, 0.006362794920665866, -0.15741483292302144, 0.281815689472032, -0.11362794497801082, 0.16625919127066946, -0.21957481597844009, -0.24315862429985838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17642588789046668, 0.008243790529864094, 0.082698189323857]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2638820443668369, 0.0, 0.0, 0.0, -0.0600928702661735, -0.029333819326772002, 0.42839832560302366, -0.16928367193362603, 0.8394382481721426, -0.14993450783639845, -1.5147867538156334, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8770423860537591, -0.10016880859322587, 0.2312417295544335]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.594091212859036e-06, 0.0, 0.0, 0.0, 0.0039598430004819125, -0.2064541547414311, 0.34949705907479234, -0.1490342559739504, 0.2291140939486419, -0.21676260419923601, -0.1005162544168812, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1826816203658195, 0.0029150983357014368, 0.08894446003425287]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26388207350419796, 0.0, 0.0, 0.0, -0.06048852596243575, -0.038358506980624714, 0.4455073442495497, -0.17475573389070498, 0.8505494695373617, -0.15996639808309465, -1.5164299314005458, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8858606361297205, -0.09996212855682184, 0.23537627724381205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.827472219597269e-07, 0.0, 0.0, 0.0, -0.007913113925244953, -0.18049375307705426, 0.3421803729305211, -0.10944123914157863, 0.22222442730438127, -0.20063780493392397, -0.032863551698246216, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17636500151923085, 0.004133600728080694, 0.08269095378757108]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26453202574415674, 0.0, 0.0, 0.0, -0.06218876097346721, -0.042335174594095075, 0.4650592911190223, -0.1746537752672726, 0.8602758863621954, -0.16706127047515104, -1.518440473841656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8937319772768367, -0.0992131604801968, 0.2388443292927066]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044799175827, 0.0, 0.0, 0.0, -0.03400470022062929, -0.07953335226940725, 0.39103893738945145, 0.0020391724686476126, 0.19452833649667473, -0.14189744784112776, -0.04021084882220008, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15742682294232296, 0.014979361532500773, 0.06936104097789092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26518197796972154, 0.0, 0.0, 0.0, -0.06496345243509287, -0.041251551693083435, 0.4872751096904221, -0.17095028688431974, 0.8696531306438285, -0.17055343931423667, -1.524568381092403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9008290490391627, -0.09780314328002, 0.24169116947103791]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044511295639, 0.0, 0.0, 0.0, -0.05549382923251316, 0.02167245802023285, 0.4443163714279966, 0.07406976765905722, 0.18754488563266206, -0.06984337678171222, -0.1225581450149387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14194143524651964, 0.028200344003535938, 0.05693680356662625]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26525225987689816, 0.0, 0.0, 0.0, -0.06806769367441134, -0.038857638188476824, 0.5084048002181187, -0.1673952687119612, 0.8811873794433983, -0.17268779149945374, -1.531063653239537, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9079062007523014, -0.09619297742890337, 0.24433949316415937]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056381435322528, 0.0, 0.0, 0.0, -0.062084824786369584, 0.04787827009213223, 0.4225938105539329, 0.07110036344717073, 0.23068497599139504, -0.042687043704341524, -0.12990544294267975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1415430342627738, 0.032203317022332784, 0.05296647386242886]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26524671043880416, 0.0, 0.0, 0.0, -0.07019944023877892, -0.03890343366381969, 0.532198362212003, -0.16773871975256613, 0.8986286325403343, -0.17247913831122683, -1.534176290454848, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9156193748733226, -0.09485824573969176, 0.2474143003441742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098876188029173, 0.0, 0.0, 0.0, -0.04263493128735132, -0.0009159095068573403, 0.475871239877686, -0.006869020812098836, 0.34882506193872054, 0.0041730637645380556, -0.06225274430621755, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15426348242042162, 0.026694633784232175, 0.06149614360029639]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2651975921686999, 0.0, 0.0, 0.0, -0.07109478100927807, -0.04513893810818936, 0.5584810318145585, -0.17173305028236951, 0.9244130101201922, -0.17367747969598454, -1.530156292738684, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9240184961820027, -0.09441927214489078, 0.2514943958698442]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0009823654020849597, 0.0, 0.0, 0.0, -0.01790681540998332, -0.12471008888739334, 0.525653392051111, -0.07988661059606798, 0.5156875515971563, -0.02396682769515432, 0.08039995432328009, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16798242617360298, 0.008779471896019582, 0.08160191051340011]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26519129247975004, 0.0, 0.0, 0.0, -0.07197911675947918, -0.053814198661728214, 0.5835028090258175, -0.17640304133191498, 0.9569227453576975, -0.17775559266502539, -1.515556300474317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9325170004238078, -0.09437642662496643, 0.2559547805121902]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00012599377899816851, 0.0, 0.0, 0.0, -0.01768671500402228, -0.17350521107077718, 0.5004355442251787, -0.09339982099090921, 0.6501947047501063, -0.08156225938081704, 0.2919998452873375, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1699700848361029, 0.0008569103984870027, 0.08920769284692064]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26584124449638147, 0.0, 0.0, 0.0, -0.07537228283076634, -0.06117921539490391, 0.6035136938472028, -0.17980620529944938, 0.9924078382530588, -0.18188640980758997, -1.49412631366159, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9403537553274794, -0.09428772209539708, 0.26017045429408636]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999040332628532, 0.0, 0.0, 0.0, -0.06786332142574326, -0.14730033466351397, 0.40021769639929705, -0.06806327935068802, 0.7097018579072248, -0.08261634285129146, 0.42859973625454206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15673509807343217, 0.001774090591386765, 0.08431347563792303]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26649119673984883, 0.0, 0.0, 0.0, -0.08177957152137558, -0.0634839883275595, 0.614763686275912, -0.17832498128030075, 1.0271182888062864, -0.18231993112543302, -1.4696163323004952, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9467624232572783, -0.09372435066745514, 0.26351641721810887]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044869346797, 0.0, 0.0, 0.0, -0.12814577381218473, -0.046095458653111765, 0.22499984857418442, 0.02962448038297258, 0.6942090110645525, -0.008670426356861022, 0.49019962722189975, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1281733585959774, 0.011267428558838666, 0.06691925848044972]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665614786537338, 0.0, 0.0, 0.0, -0.08988927783543438, -0.0615368626488967, 0.6135027863135067, -0.17383437177118555, 1.057304097017421, -0.17608257334507726, -1.4457763563909898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9517302909428004, -0.09205520635639447, 0.2660082773610143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056382776999818, 0.0, 0.0, 0.0, -0.1621941262811761, 0.03894251357325604, -0.02521799924810597, 0.08981219018230388, 0.6037161642226917, 0.124747155607115, 0.476799518190109, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09935735371044103, 0.03338288622121361, 0.04983720285810804]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.266555929069743, 0.0, 0.0, 0.0, -0.09915680370832562, -0.05908783668809774, 0.6012020366787221, -0.17008418746832787, 1.0792152629412575, -0.16484205819247677, -1.4263563858695638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9558622083017572, -0.08914639033983639, 0.2679884640765657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011099167981606884, 0.0, 0.0, 0.0, -0.18535051745782485, 0.0489805192159791, -0.2460149926956934, 0.07500368605715341, 0.43822331847673, 0.22481030305200994, 0.3883994104285193, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08263834717913654, 0.05817632033116164, 0.03960373431102801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665536087825353, 0.0, 0.0, 0.0, -0.10774453341693181, -0.059886665718031716, 0.5809664995749114, -0.16996885486529575, 1.089103149661125, -0.1523483818109655, -1.4151063393598062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9598377539983957, -0.08546174143336822, 0.26967838213753276]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6405744154573886e-05, 0.0, 0.0, 0.0, -0.17175459417212388, -0.015976580598679437, -0.40471074207621344, 0.0023066520606424834, 0.19775773439734975, 0.24987345049698906, 0.22500093019514994, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07951091393277092, 0.07369297812936326, 0.03379836121934129]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665534310747967, 0.0, 0.0, 0.0, -0.11454376389138017, -0.06252842583117403, 0.5565461679442517, -0.17436363948811437, 1.0903293015534228, -0.14235151692298587, -1.4107570453238016, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9638158706779687, -0.08160648281824404, 0.2711614474476636]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.554154773011451e-06, 0.0, 0.0, 0.0, -0.13598460948896723, -0.0528352022628463, -0.4884066326131947, -0.0878956924563721, 0.024523037845955747, 0.1999372977595924, 0.08698588072009233, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07956233359146148, 0.07710517230248372, 0.029661306202616672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26655346032464927, 0.0, 0.0, 0.0, -0.11916571382133744, -0.0654611244902389, 0.5316876742052631, -0.18231851160384674, 1.0858004153289267, -0.1386008057418884, -1.411588975359321, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9677911439095875, -0.07787674227900773, 0.2724878500600121]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.84997052241308e-07, 0.0, 0.0, 0.0, -0.09243899859914517, -0.058653973181297274, -0.49716987477977276, -0.15909744231464762, -0.09057772448992046, 0.07501422362194912, -0.016638600710384296, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07950546463237747, 0.07459481078472607, 0.026528052246969656]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26720341234500505, 0.0, 0.0, 0.0, -0.1216541030911338, -0.0649347653236069, 0.5101410180480295, -0.19008347142539134, 1.079266490696631, -0.1445497233219581, -1.4143819404669564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9711528124479258, -0.07440282626085515, 0.27322782229325715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999040407115959, 0.0, 0.0, 0.0, -0.049767785395927244, 0.010527183332640223, -0.43093312314467225, -0.15529919643089174, -0.13067849264591677, -0.11897835160139353, -0.05585930215271177, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06723337076676547, 0.06947832036305181, 0.014799444664901483]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26785336458623626, 0.0, 0.0, 0.0, -0.12241441719596326, -0.05784494184522036, 0.49565619946225337, -0.19390851895850758, 1.0744775276487368, -0.15725695085755323, -1.4222674816128857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9733691848422911, -0.07159882519199075, 0.2734999822674431]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044824624656, 0.0, 0.0, 0.0, -0.015206282096589384, 0.1417964695677307, -0.28969637171552265, -0.07650095066232472, -0.09577926095788361, -0.2541445507119029, -0.15771082291858596, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04432744788730506, 0.05608002137728803, 0.0054431994837189305]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26850331682321105, 0.0, 0.0, 0.0, -0.12216537933370626, -0.04789507485126157, 0.49152912033274715, -0.1914585523481791, 1.0751835258728315, -0.17374085283197277, -1.435813328014667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9745840056109065, -0.06941402047173197, 0.273523106393477]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044739496202, 0.0, 0.0, 0.0, 0.0049807572451400425, 0.1989973398791759, -0.08254158259012484, 0.048999332206569726, 0.014119964481894967, -0.3296780394883906, -0.27091692803562556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024296415372308804, 0.04369609440517576, 0.00046248252067780746]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685735988237808, 0.0, 0.0, 0.0, -0.12305063330397298, -0.03883516434149662, 0.49400978066073464, -0.18648357159412424, 1.0776344853741517, -0.19025145223005255, -1.4583515327851377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9752293446802045, -0.06707761161028665, 0.273922194320465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056400113951484, 0.0, 0.0, 0.0, -0.017705079405334258, 0.18119821019529897, 0.04961320655974957, 0.09949961508109746, 0.04901919002640491, -0.33021198796159545, -0.4507640954094163, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012906781385959694, 0.046728177228906376, 0.007981758539760332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685680494466895, 0.0, 0.0, 0.0, -0.12406059669747342, -0.03441521031222953, 0.499348180447187, -0.18273357669315082, 1.078080406153933, -0.20307125960738243, -1.4880359556275422, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9760750139773863, -0.06502196047461477, 0.2748110184615617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098754182647767, 0.0, 0.0, 0.0, -0.02019926787000873, 0.08839908058534185, 0.10676799572904727, 0.07499989801946852, 0.008918415595627581, -0.2563961475465978, -0.5936884568480915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016913385943636308, 0.04111302271343776, 0.01777648282193446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685657289038691, 0.0, 0.0, 0.0, -0.12494473365539253, -0.036237859622744034, 0.5037943309699531, -0.1836983816275627, 1.0727713073061589, -0.21194787703928036, -1.5221509477682693, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9776776455752492, -0.06322579579794672, 0.2759020735274177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.641085640818318e-05, 0.0, 0.0, 0.0, -0.01768273915838234, -0.03645298621029003, 0.08892301045532225, -0.01929609868823716, -0.10618197695548287, -0.17753234863795891, -0.6822998428145429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03205263195725846, 0.035923293533360955, 0.021821101317119743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26856555112545394, 0.0, 0.0, 0.0, -0.12575973814404873, -0.04089553545256851, 0.5035983502414102, -0.18756019300334953, 1.058836867231935, -0.2187958994631828, -1.5593437168705004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9797032302196752, -0.0616578376223033, 0.27698101240682466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.555568303593545e-06, 0.0, 0.0, 0.0, -0.016300089773123652, -0.09315351659648952, -0.003919614570857613, -0.07723622751573661, -0.2786888014844763, -0.13696044847804895, -0.743855382044623, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04051169288852141, 0.03135916351286843, 0.021578777588139763]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268565580564015, 0.0, 0.0, 0.0, -0.12752924371210825, -0.04463829182513776, 0.495010238430804, -0.1928873919582791, 1.035974834358312, -0.22509163070746274, -1.6010979315166292, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9815795037391268, -0.05983121762938938, 0.2778456857734703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.887712221352959e-07, 0.0, 0.0, 0.0, -0.0353901113611904, -0.074855127451385, -0.1717622362121244, -0.10654397909859109, -0.4572406574724601, -0.1259146248855985, -0.8350842929225722, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.037525470389033484, 0.03653239985827841, 0.017293467332912444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26856558887551185, 0.0, 0.0, 0.0, -0.12812395147845995, -0.04371613292703018, 0.4817799955253769, -0.19592998377804816, 1.007935208681356, -0.23457100954992574, -1.643663591713776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.982877415718752, -0.058519343748966134, 0.2784616496713446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.662299361517475e-07, 0.0, 0.0, 0.0, -0.01189415532703425, 0.01844317796215167, -0.2646048581085416, -0.0608518363953813, -0.5607925135391192, -0.1895875768492601, -0.8513132039429374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02595823959250348, 0.02623747760846499, 0.012319277957486389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685655917460417, 0.0, 0.0, 0.0, -0.12526970460294906, -0.03828103130359932, 0.46765762152434637, -0.192958380246224, 0.9784679902006503, -0.25098400224482226, -1.68329069746257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9834914509686726, -0.05840325652943024, 0.2794538869832973]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.741059789166804e-08, 0.0, 0.0, 0.0, 0.057084937510217704, 0.10870203246861718, -0.2824474800206116, 0.05943207063648296, -0.5893443696141121, -0.3282598538979301, -0.7925421149758815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012280704998412264, 0.002321744390717787, 0.019844746239054308]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268565591942793, 0.0, 0.0, 0.0, -0.119363559815941, -0.032082986431909294, 0.4563931164255143, -0.18597731322860184, 0.9513231789147965, -0.2759114959845611, -1.716229248765284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9841988133606524, -0.05991131422319352, 0.2812794110553384]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.935026102377918e-09, 0.0, 0.0, 0.0, 0.11812289574016112, 0.1239608974338005, -0.22529010197664168, 0.13962134035244325, -0.5428962257170787, -0.49854987479477636, -0.6587710260542775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01414724783959576, -0.03016115387526554, 0.03651048144082083]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26856559185623186, 0.0, 0.0, 0.0, -0.11156631226867404, -0.02887199821873325, 0.45173648022280527, -0.178736782725157, 0.9302507748210604, -0.30560349142562565, -1.7387292456282257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9856118928191073, -0.06288027029446329, 0.28397439603832764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.7312234661301311e-09, 0.0, 0.0, 0.0, 0.15594495094533928, 0.06421976426352086, -0.0931327240541801, 0.14481061006889664, -0.42144808187472105, -0.5938399088212908, -0.4499999372588349, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02826158916909812, -0.05937912142539535, 0.05389969965978522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268428283599272, 0.0, 0.0, 0.0, -0.10353744778848128, -0.032398066022733166, 0.4546470167482712, -0.17498678800223172, 0.9190007772097162, -0.33630998863773404, -1.7470406884585261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9881622254363183, -0.06652947922735258, 0.28691385081540427]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002746165139196418, 0.0, 0.0, 0.0, 0.16057728960385526, -0.07052135607999827, 0.05821073050931841, 0.07499989445850562, -0.22499995222688607, -0.6141299442421679, -0.16622885660600883, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.051006652344217876, -0.0729841786577858, 0.05878909554153232]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2684103158440533, 0.0, 0.0, 0.0, -0.09590789773193015, -0.04212871852634535, 0.4613747779499957, -0.1766098341858334, 0.9154029479647217, -0.364280990813621, -1.7449135770556008, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9917335998398077, -0.07023629018782934, 0.28970425195067584]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.000359355104374385, 0.0, 0.0, 0.0, 0.1525910011310227, -0.19461305007224378, 0.13455522403449008, -0.0324609236720335, -0.07195658489988935, -0.5594200435177387, 0.04254222805850438, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0714274880697878, -0.0741362192095352, 0.05580802270543109]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2683580871799354, 0.0, 0.0, 0.0, -0.08869054127649784, -0.05437845602447167, 0.46889222968356015, -0.1830022774896997, 0.9162239085623636, -0.3887675432718657, -1.735993711007398, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9959487245622577, -0.07345693995832629, 0.29221293353553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0010445732823567092, 0.0, 0.0, 0.0, 0.14434712910864622, -0.24499474996252646, 0.15034903467128855, -0.12784886607732565, 0.016419211952837354, -0.48973104916489396, 0.17839732096405803, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08430249444900087, -0.06441299540993903, 0.05017363169708376]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.268351662308612, 0.0, 0.0, 0.0, -0.08296452140775495, -0.06539727851844616, 0.48094937192273435, -0.1904141179172502, 0.9177136609658914, -0.4097275847284972, -1.724031090312019, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0000234805164536, -0.07577541457725127, 0.29381489636310953]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00012849742646767973, 0.0, 0.0, 0.0, 0.11452039737485759, -0.2203764498794899, 0.24114284478348358, -0.14823680855100996, 0.029795048070555552, -0.41920082913263, 0.23925241390757893, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08149511908391918, -0.046369492378499556, 0.03203925655159049]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26835200658202424, 0.0, 0.0, 0.0, -0.07798318720745022, -0.07143518604873789, 0.49833416540057324, -0.195095355560346, 0.9161230671800843, -0.42902749408480056, -1.7127757149177076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0031740991404532, -0.07677936209308113, 0.2944169474636089]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.885468244651263e-06, 0.0, 0.0, 0.0, 0.09962668400609478, -0.12075815060583436, 0.347695869556778, -0.09362475286191596, -0.031811875716140796, -0.38599818712606765, 0.22510750788622713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06301237247999109, -0.020078950316597163, 0.012041022009987336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26835219762418383, 0.0, 0.0, 0.0, -0.07342244958175721, -0.06874220468909563, 0.5172966108047267, -0.19620215976923075, 0.9130861700234868, -0.44784677079635893, -1.7059775751908284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.004920035211489, -0.07704500971892342, 0.2943742837478135]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.8208431916129355e-06, 0.0, 0.0, 0.0, 0.09121475251386016, 0.05385962719284523, 0.37924890808306944, -0.022136084177695317, -0.06073794313194882, -0.3763855342311671, 0.13596279453758597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03491872142071854, -0.005312952516845786, -0.0008532743159080022]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2683522149761813, 0.0, 0.0, 0.0, -0.06927504739117361, -0.059644229920488394, 0.5340867314829538, -0.19560505869825534, 0.9104742692394945, -0.46680203836995143, -1.7038372534545905, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0054870179969935, -0.07695692859782101, 0.29403911059192184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4703994927180757e-07, 0.0, 0.0, 0.0, 0.08294804381167192, 0.18195949537214473, 0.3358024135645431, 0.01194202141950823, -0.05223801567984529, -0.37910535147185037, 0.042806434724757175, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011339655710088499, 0.0017616224220480588, -0.006703463117832598]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2684049174206975, 0.0, 0.0, 0.0, -0.06549434127835235, -0.04789122970945867, 0.5476124662114051, -0.19449860872557168, 0.9102145370237033, -0.48700635667175723, -1.7040447848416123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0055584098581891, -0.07661408474259626, 0.2936752605694536]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010540488903241644, 0.0, 0.0, 0.0, 0.07561412225642525, 0.23506000422059445, 0.2705146945690257, 0.022128999453673026, -0.005194644315824205, -0.4040863660361163, -0.004150627740436008, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014278372239113011, 0.00685687710449496, -0.007277000449365399]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2684118114524429, 0.0, 0.0, 0.0, -0.06021009578935407, -0.03723320405531662, 0.5541238160646349, -0.19663280984971285, 0.9160569733612092, -0.507696068120875, -1.7028501693540123, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0059132983951695, -0.07643351082617751, 0.2939077336052483]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013788063490849638, 0.0, 0.0, 0.0, 0.10568490977996552, 0.213160513082841, 0.13022699706459526, -0.04268402248282359, 0.11684872675011776, -0.4137942289823539, 0.023892309751998898, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007097770739605909, 0.0036114783283749665, 0.004649460715893895]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26776185952469633, 0.0, 0.0, 0.0, -0.053759912902062466, -0.03142015284891521, 0.5544512006750153, -0.20575766188808028, 0.9317515750642483, -0.5251284006131761, -1.696503407190766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0073315201413389, -0.07683058615066723, 0.29516078900401815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999038554932046, 0.0, 0.0, 0.0, 0.12900365774583214, 0.11626102412802829, 0.0065476922076079525, -0.18249704076734896, 0.3138920340607835, -0.34864664984602195, 0.12693524326492484, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.028364434923387746, -0.007941506489794383, 0.02506110797539717]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267111907310854, 0.0, 0.0, 0.0, -0.046000620850737486, -0.03374415142750001, 0.5519833367973961, -0.22461170517793413, 0.9557766953575156, -0.5383878186564345, -1.6812544983796953, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0104334309774916, -0.07768573461232883, 0.29703319022393915]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044276846597, 0.0, 0.0, 0.0, 0.15518584102649952, -0.04647997157169599, -0.04935727755238529, -0.3770808657970768, 0.4805024058653454, -0.2651883608651676, 0.30497817622141576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.062038216723052944, -0.017102969233232006, 0.03744802439842002]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2664619551355365, 0.0, 0.0, 0.0, -0.0352536462415785, -0.040476657760763216, 0.5504702244252089, -0.2515734075001164, 0.9869967915660244, -0.5512243211770045, -1.657297074392315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0151809472494062, -0.07956984160817317, 0.29932554190243454]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043506350238, 0.0, 0.0, 0.0, 0.2149394921831797, -0.1346501266652641, -0.030262247443743454, -0.5392340464436455, 0.6244019241701746, -0.2567300504114007, 0.479148479747608, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0949503254382905, -0.037682139916886556, 0.04584703356990742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26639167295800076, 0.0, 0.0, 0.0, -0.021291603050552332, -0.04786767185088748, 0.5536618635312297, -0.28289276885583514, 1.0239728684676541, -0.5673878919426599, -1.628381135225704, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0209294667219884, -0.08249524913830973, 0.30141285302927623]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001405643550714309, 0.0, 0.0, 0.0, 0.2792408638205234, -0.14782028180248521, 0.0638327821204166, -0.626387227114375, 0.7395215380325935, -0.3232714153131089, 0.5783187833322203, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11497038945164323, -0.05850815060273121, 0.04174622253683391]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26639722231388907, 0.0, 0.0, 0.0, -0.005686839251930935, -0.05216719369794628, 0.5626180916248719, -0.3148197892451369, 1.0629549260628668, -0.5873914787585406, -1.5982566808798093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0269509282722395, -0.08622522233789769, 0.3026701239037015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011098711776618363, 0.0, 0.0, 0.0, 0.312095275972428, -0.085990436941176, 0.17912456187284254, -0.6385404077860357, 0.7796411519042554, -0.40007173631761317, 0.6024890869178955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12042923100502412, -0.07459946399175912, 0.025145417488505833]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26639954255246895, 0.0, 0.0, 0.0, 0.008691861514725818, -0.04962522330201289, 0.5735889087062288, -0.3436044686680505, 1.10019296435171, -0.6074850840838151, -1.570673711354606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0324579574727435, -0.09035778390808502, 0.30247235684232177]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6404771597524926e-05, 0.0, 0.0, 0.0, 0.28757401533313504, 0.05083940791866773, 0.21941634162713863, -0.5756935884582719, 0.7447607657768647, -0.40187210650548905, 0.5516593905040659, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11014058401007938, -0.08265123140374656, -0.003955341227595201]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26704949479163353, 0.0, 0.0, 0.0, 0.020153094822954867, -0.03728323840558011, 0.5828243147755015, -0.36549680712985905, 1.1319369833343633, -0.6250353292203136, -1.549382226649861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0366611298820434, -0.09448879355597326, 0.3006891840361485]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044783292144, 0.0, 0.0, 0.0, 0.229224666164581, 0.24683969792865565, 0.18470812138545187, -0.4378467692361704, 0.6348803796530667, -0.3510049027299706, 0.42582969409490184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08406344818599779, -0.08262019295776457, -0.03566345612346435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26769944318618416, 0.0, 0.0, 0.0, 0.030072038233296187, -0.018891239001709373, 0.5867423440762979, -0.37974517005966635, 1.154436990334572, -0.6385649961519703, -1.5381322266121062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0388175281868934, -0.09833895826264186, 0.2979456054791525]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998967891012932, 0.0, 0.0, 0.0, 0.19837886820682638, 0.3678399880774147, 0.07836058601592845, -0.284967258596146, 0.45000014000417354, -0.2705933386331343, 0.2250000007550928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.043127966096999884, -0.07700329413337216, -0.05487157113992009]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26787923669365915, 0.0, 0.0, 0.0, 0.03793755401175139, 0.001800774976912032, 0.5856782034604381, -0.38868142179888104, 1.169281136514286, -0.6443240854017388, -1.5360035883738143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0391839341756397, -0.10198292311618605, 0.2948666211139144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003595870149499929, 0.0, 0.0, 0.0, 0.15731031556910402, 0.4138402795724281, -0.021282812317196823, -0.17872503478429363, 0.29688292359427926, -0.11518178499537035, 0.04257276476583702, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007328119774925068, -0.07287929707088382, -0.06157968730476235]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678880134088109, 0.0, 0.0, 0.0, 0.04299643078460586, 0.02104281882378083, 0.5758862511295437, -0.3960098281066915, 1.174845654100042, -0.6427651217073023, -1.5392463139535622, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.038392590253071, -0.10533462658552947, 0.29207722732095587]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001755343030350738, 0.0, 0.0, 0.0, 0.10117753545708943, 0.3848408769373759, -0.1958390466178866, -0.14656812615620957, 0.11129035171512094, 0.03117927388873165, -0.06485451159495724, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015826878451372095, -0.06703406938686848, -0.05578787585917042]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678850831196126, 0.0, 0.0, 0.0, 0.04570931829439437, 0.035181482034803625, 0.5608912017976336, -0.40175774145510923, 1.1738780172908025, -0.6375952698356051, -1.544110405950442, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.037055429385431, -0.10824005166407545, 0.2901345658864022]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.860578396576032e-05, 0.0, 0.0, 0.0, 0.05425775019577019, 0.2827732642204559, -0.29990098663820175, -0.11495826696835415, -0.01935273618479222, 0.1033970374339426, -0.09728183993759557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.026743217352798238, -0.05810850157091953, -0.03885322869107408]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26788450069637937, 0.0, 0.0, 0.0, 0.04670005651865394, 0.04484961842443636, 0.5440532303978588, -0.40596495287544265, 1.1690546868216118, -0.6306852242622094, -1.54854038059483, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0357986861224984, -0.11060017126285825, 0.28887555431455264]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1648464664827375e-05, 0.0, 0.0, 0.0, 0.019814764485191434, 0.19336272779265473, -0.3367594279954977, -0.08414422840666817, -0.09646660938381495, 0.13820091146791458, -0.08859949288775873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02513486525865578, -0.04720239197565592, -0.02518023143699065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678844910361218, 0.0, 0.0, 0.0, 0.04641403581955245, 0.051428580935713133, 0.5270505996193192, -0.40881045543496985, 1.1619168143388638, -0.6227716632188728, -1.5530169047520128, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0349511387552124, -0.11242576465375408, 0.28805851074598804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.9320515213740755e-07, 0.0, 0.0, 0.0, -0.005720413982029732, 0.13157925022553546, -0.34005261557079125, -0.056910051190543876, -0.14275744965495887, 0.15827122086673276, -0.08953048314366016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.016950947345717934, -0.036511867817916537, -0.01634087137129247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678845060355355, 0.0, 0.0, 0.0, 0.04517143946783047, 0.05607798243563867, 0.5104009230801457, -0.41056984719639483, 1.1531611660316217, -0.6142268712778277, -1.558247211099493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0343993821364026, -0.11384519660416094, 0.28750236510643806]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.999882742460349e-07, 0.0, 0.0, 0.0, -0.024851927034439704, 0.09298802999851072, -0.3329935307834691, -0.03518783522850004, -0.17511296614484168, 0.17089583882090162, -0.10460612694960053, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011035132376195491, -0.028388639008137363, -0.011122912790999025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678845108780542, 0.0, 0.0, 0.0, 0.04319054871543771, 0.05964536404842619, 0.4940361167643921, -0.41148572129540184, 1.1430046555639763, -0.6053279248701041, -1.5647344691777052, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0340001747938279, -0.11497488275021778, 0.2870938422084732]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.68503747436812e-08, 0.0, 0.0, 0.0, -0.03961781504785512, 0.07134763225575042, -0.32729612631507354, -0.018317481980140285, -0.20313020935290543, 0.1779789281544714, -0.12974516156424612, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007984146851495436, -0.022593722921136893, -0.008170457959297137]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2678845147273684, 0.0, 0.0, 0.0, 0.040600084947939416, 0.06278918089149538, 0.4776283739215182, -0.41169738473102385, 1.131385177479085, -0.5963297966566199, -1.572866366229264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0336534616533604, -0.11589925152952285, 0.28676533441927865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.698628396713673e-08, 0.0, 0.0, 0.0, -0.05180927534996594, 0.06287633686138369, -0.32815485685747753, -0.0042332687124397965, -0.23238956169782563, 0.17996256426968338, -0.16263794103117557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006934262809352433, -0.018487375586101355, -0.006570155783891655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26788452305016486, 0.0, 0.0, 0.0, 0.03744618275052417, 0.06613763662244682, 0.460701888045675, -0.41120685781121247, 1.1179987400446374, -0.58752101519294, -1.5831227610302945, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.033288796062019, -0.11667604404837935, 0.2864739415319033]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6645592946057356e-07, 0.0, 0.0, 0.0, -0.06307804394830493, 0.06696911461902871, -0.33852971751686384, 0.009810538396227537, -0.26772874868895274, 0.1761756292735985, -0.20512789602061043, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007293311826829159, -0.015535850377129875, -0.0058278577475065]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267884524469445, 0.0, 0.0, 0.0, 0.03368209092220058, 0.07051016465781684, 0.44256981452210153, -0.4098180720856493, 1.1021585341139906, -0.5793462282347126, -1.5963977152001754, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.032834756174601, -0.11734251396874035, 0.28618572021553523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8385602844268588e-08, 0.0, 0.0, 0.0, -0.07528183656647193, 0.08745056070740048, -0.36264147047147033, 0.02777571451126344, -0.3168041186129354, 0.16349573916454793, -0.26549908339761963, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00908079774836176, -0.013329398407219997, -0.005764426327361348]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267884528763144, 0.0, 0.0, 0.0, 0.029089508348207435, 0.07746905618259536, 0.42195962221292016, -0.4068942244603292, 1.0822252235217915, -0.572732094839798, -1.614832722324306, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.03216291535436, -0.11791734450607745, 0.2858575963365481]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.58739804694152e-08, 0.0, 0.0, 0.0, -0.09185165147986288, 0.13917783049557028, -0.41220384618362804, 0.05847695250640192, -0.39866621184398304, 0.13228266789829207, -0.36870014248261385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013436816404819045, -0.011496610746742002, -0.006562477579742597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685344810027367, 0.0, 0.0, 0.0, 0.021613017257404197, 0.08557957641797231, 0.39685434161545646, -0.39868531493843834, 1.05444880903488, -0.5703744190640847, -1.6414452282529808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0305896432412824, -0.1179493312582453, 0.2852848435263928]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044791853955, 0.0, 0.0, 0.0, -0.14952982181606475, 0.1622104047075391, -0.5021056119492735, 0.16417819043781728, -0.5555282897382301, 0.04715351551426765, -0.5322501185734968, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03146544226155234, -0.0006397350433571154, -0.011455056203106589]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2691844332414858, 0.0, 0.0, 0.0, 0.014253633762876729, 0.09109444448719291, 0.37100397272884394, -0.38144134352582393, 1.0225792906528823, -0.572632846295547, -1.6724852329912394, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0282179602939003, -0.11805848446789798, 0.2846265749896631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044774981313, 0.0, 0.0, 0.0, -0.14718766989054935, 0.1102973613844119, -0.5170073777322504, 0.3448794282522883, -0.6373903676399553, -0.0451685446292462, -0.6208000947651722, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04743365894764118, -0.0021830641930532992, -0.013165370734593037]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26925471516477245, 0.0, 0.0, 0.0, 0.009796314764779525, 0.09026366062663242, 0.348158515552932, -0.35582136899596556, 0.9903666683757127, -0.5816881497325312, -1.7042027365391854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0258231665439757, -0.11866991046736258, 0.2845077905791742]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056384657339886, 0.0, 0.0, 0.0, -0.08914637996194409, -0.016615677211209795, -0.45690914351823875, 0.5123994905971669, -0.6442524455433916, -0.18110606873968543, -0.6343500709589192, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.047895874998495146, -0.01222851998929224, -0.0023756882097782112]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.269249165728663, 0.0, 0.0, 0.0, 0.008994361191690167, 0.07933722484350195, 0.33206797008665095, -0.3255753907754556, 0.961560942202706, -0.5957034741126928, -1.732847738897428, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.024182186373852, -0.12021005495711566, 0.2855534893339755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098872218996063, 0.0, 0.0, 0.0, -0.016039071461787194, -0.21852871566260962, -0.32181090932562095, 0.6049195529421507, -0.5761145234601329, -0.2803064876032311, -0.5729000471648507, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.032819603402473085, -0.030802889795061465, 0.020913975096025855]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2686299453068434, 0.0, 0.0, 0.0, 0.010890949495971206, 0.05898186169259201, 0.3264823321310573, -0.29445341001096725, 0.9399121121317414, -0.6120152339715125, -1.7546702400663932, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.02407110123095, -0.12308100569532991, 0.2878680046096351]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012384408436390723, 0.0, 0.0, 0.0, 0.03793176608562079, -0.4071072630181988, -0.1117127591118732, 0.6224396152897669, -0.4329766014192924, -0.32623519717639443, -0.43645002337930267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002221702858041113, -0.05741901476428488, 0.04629030551319131]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2679799930667457, 0.0, 0.0, 0.0, 0.014245418054936551, 0.03263922777013159, 0.32765160168911084, -0.26620542612788334, 0.9291701780203717, -0.6319272895635404, -1.7659202400495617, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0260141530386926, -0.1268164225265875, 0.2908703247604604]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044801954596, 0.0, 0.0, 0.0, 0.0670893711793069, -0.5268526784492082, 0.023385391161070135, 0.5649596776616778, -0.21483868222739355, -0.3982411118405581, -0.22499999966337098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03886103615485048, -0.07470833662515211, 0.060046403016505615]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2673300408246939, 0.0, 0.0, 0.0, 0.018578757198493927, 0.004059323075045029, 0.331825778769018, -0.24458143912549185, 0.9255851419565458, -0.6548273871054273, -1.7640452400387698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0297704764135536, -0.13082496670453278, 0.2940646759983455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044841035097, 0.0, 0.0, 0.0, 0.08666678287114753, -0.5715980939017313, 0.08348354159814267, 0.43247974004782974, -0.07170072127651819, -0.4580019508377384, 0.037500000215839435, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07512646749721894, -0.08017088355890531, 0.06388702475770235]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26725975890762743, 0.0, 0.0, 0.0, 0.02300589291177914, -0.023007852392911827, 0.34251490480253177, -0.22583144900523122, 0.9254070039417829, -0.6780046584625603, -1.75279524003389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.034559495763242, -0.1346826364423622, 0.2968260583281673]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056383413293266, 0.0, 0.0, 0.0, 0.08854271426570424, -0.5413435093591371, 0.213782520670276, 0.37499980240521236, -0.0035627602952602727, -0.4635454271426597, 0.22500000009759907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09578038699376834, -0.07715339475658853, 0.055227646596435545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672653082964447, 0.0, 0.0, 0.0, 0.02748395397159615, -0.044812298633939485, 0.35939869842199257, -0.2062054557682501, 0.924885763977933, -0.6999418721802724, -1.7359202400348155, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0395953016012618, -0.1379763819420428, 0.2985294717530343]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011098777634474164, 0.0, 0.0, 0.0, 0.08956122119634018, -0.43608892482055317, 0.3376758723892157, 0.3925198647396224, -0.010424799276997791, -0.43874427435424057, 0.3374999999814902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10071611676039582, -0.06587490999361185, 0.03406826849733996]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672676285340556, 0.0, 0.0, 0.0, 0.03219238678344218, -0.05760401565276381, 0.38102691995733606, -0.18889246297898166, 0.9202714221158639, -0.7209210492562389, -1.7171702400399795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0440906988811793, -0.14029977334240967, 0.2987650095494673]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6404752218913485e-05, 0.0, 0.0, 0.0, 0.09416865623692068, -0.25583434037648656, 0.43256443070687, 0.3462598557853689, -0.0922868372413827, -0.4195835415193303, 0.37499999989671906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08990794559835226, -0.04646782800733787, 0.004710755928659174]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672678061902681, 0.0, 0.0, 0.0, 0.03716875801516868, -0.058160612280034794, 0.40364956942242664, -0.17534984302157475, 0.9119399779433843, -0.7426507725665725, -1.7002952400094844, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0474149830746284, -0.14173690921505055, 0.298157669785667]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5531242497408177e-06, 0.0, 0.0, 0.0, 0.09952742463453004, -0.011131932545419748, 0.45245298930181127, 0.2708523991481382, -0.16662888344959192, -0.43459446620667314, 0.33750000060990415, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06648568386898279, -0.028742717452817538, -0.01214679527600538]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2672677886598416, 0.0, 0.0, 0.0, 0.04221012062455142, -0.05023208802967201, 0.42352916140218994, -0.16735099118226843, 0.9031930820042944, -0.765637271686527, -1.6888550611191866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0495075221522128, -0.14257310348236066, 0.2972958166540949]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.50608529645171e-07, 0.0, 0.0, 0.0, 0.10082725218765476, 0.1585704850072557, 0.3975918395952661, 0.1599770367861263, -0.1749379187817994, -0.4597299823990891, 0.22880357780595745, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04185078155168732, -0.016723885346202106, -0.017237062631442188]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26734020057211694, 0.0, 0.0, 0.0, 0.0471748921184952, -0.03756844127608076, 0.44043144948505003, -0.16409683483252555, 0.8961284398598326, -0.7906041440932654, -1.6812453867648127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.051029118984033, -0.14282640345577632, 0.2965839015199754]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014482382455073414, 0.0, 0.0, 0.0, 0.09929542987887564, 0.2532729350718249, 0.3380457616572023, 0.06508312699485769, -0.14129284288923646, -0.49933744813476827, 0.15219348708747682, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03043193663640763, -0.005065999468313593, -0.014238302682390173]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2673496737492822, 0.0, 0.0, 0.0, 0.053407950211120804, -0.023919672019226637, 0.45060643367187764, -0.1693373739722041, 0.8944960515033644, -0.8143480563721461, -1.6737162169464406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0527607468155522, -0.14291026392618691, 0.29664692438066637]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018946354330487089, 0.0, 0.0, 0.0, 0.124661161852512, 0.2729753851370824, 0.20349968373655186, -0.10481078279357098, -0.032647767129363583, -0.4748782455776147, 0.15058339636744347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03463255663038461, -0.001677209408211578, 0.0012604572138201781]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267349270413409, 0.0, 0.0, 0.0, 0.060716823599136396, -0.013035780258000208, 0.45030415164943766, -0.1849544899156498, 0.9020459169196785, -0.8347188376894084, -1.6625175516666062, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.055483176438664, -0.14323655997044038, 0.29783163255613987]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.066717463969515e-06, 0.0, 0.0, 0.0, 0.14617746776031176, 0.21767783522452855, -0.006045640448799572, -0.3123423188689141, 0.15099730832628083, -0.40741562634524386, 0.22397330559668746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05444859246223539, -0.006525920885069489, 0.02369416350946983]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666993182001273, 0.0, 0.0, 0.0, 0.06918975246137374, -0.008666765870488511, 0.44310173887093596, -0.2092187531418781, 0.9191281504958037, -0.850763021019942, -1.64389939093797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0598751515753833, -0.14424490287914335, 0.2997541717312688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044265633891, 0.0, 0.0, 0.0, 0.16945857724474692, 0.0873802877502339, -0.14404825557003353, -0.4852852645245656, 0.34164467152250333, -0.3208836666106708, 0.37236321457272503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08783950273438278, -0.020166858174059544, 0.038450783502578655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2660493680745376, 0.0, 0.0, 0.0, 0.07931083777804265, -0.0112032508467941, 0.4327466477073343, -0.24063015713242164, 0.9443814658989877, -0.8648835069993985, -1.61713425994735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.065768848811053, -0.14622362562767066, 0.3022065175804674]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299900251179483, 0.0, 0.0, 0.0, 0.20242170633337822, -0.05072969952611178, -0.2071018232720332, -0.6282280798108708, 0.5050663080636824, -0.282409719589131, 0.5353026198124031, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11787394471339796, -0.039574454970546236, 0.04904691698397297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2659790864415243, 0.0, 0.0, 0.0, 0.08988154005043986, -0.016895235187067877, 0.42282640181923664, -0.2754387018875065, 0.9740558631297752, -0.8804292683674004, -1.585972158694668, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0723851056086113, -0.1487572542545514, 0.3045636701971443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056326602661963, 0.0, 0.0, 0.0, 0.2114140454479441, -0.11383968680547557, -0.19840491776195296, -0.6961708951016982, 0.5934879446157484, -0.310915227360038, 0.6232420250536403, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13232513595116682, -0.05067257253761478, 0.04714305233353856]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26598463582006526, 0.0, 0.0, 0.0, 0.1005426792323239, -0.021992718891490095, 0.4170910012049413, -0.3098943874073358, 1.0044013422306168, -0.8985706734331053, -1.5541630871797827, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0789400156206352, -0.1514401466710619, 0.3062006766701767]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011098757081907593, 0.0, 0.0, 0.0, 0.21322278363768093, -0.10194967408844437, -0.11470801228590674, -0.6891137103965859, 0.6069095820168339, -0.36282810131409715, 0.6361814302977065, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13109820024047678, -0.053657848330209514, 0.03274012946064741]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.265986956050085, 0.0, 0.0, 0.0, 0.11004553941453311, -0.022745701960128418, 0.4192904456323106, -0.34024721369199673, 1.0316679032017129, -0.91606350647762, -1.525457045402653, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0846461697311, -0.15387312982907067, 0.3066349167344261]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6404600394674066e-05, 0.0, 0.0, 0.0, 0.19005720364418419, -0.015059661372766445, 0.0439888885473855, -0.6070565256932183, 0.5453312194219213, -0.3498566608902943, 0.574120835542591, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11412308220929764, -0.04865966316017532, 0.008684801284988285]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26645170931755635, 0.0, 0.0, 0.0, 0.11808485654125497, -0.015404189538562669, 0.42567473664782446, -0.36274718256441396, 1.052105551183496, -0.9327901824731928, -1.5036040326774196, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0887662154040214, -0.15580955020504425, 0.3061375173192031]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009295065349427537, 0.0, 0.0, 0.0, 0.16078634253443716, 0.14683024843131492, 0.12768582031027698, -0.44999937744834423, 0.40875295963566144, -0.33453351991145475, 0.43706025450467034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0824009134584273, -0.03872840751947182, -0.009947988304460337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26651245478170627, 0.0, 0.0, 0.0, 0.12485400997473534, -0.002240363480865159, 0.43249388984173126, -0.37641158910368455, 1.0655646990812049, -0.9468752319172226, -1.49235404701758, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0908605211992874, -0.1575791746567504, 0.3052237478342747]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0012149092829978215, 0.0, 0.0, 0.0, 0.13538306866960723, 0.26327652115395017, 0.1363830638781357, -0.2732881307854116, 0.26918295795417496, -0.28170098888059564, 0.22499971319679335, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04188611590531978, -0.03539248903412296, -0.01827538969856722]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650987715918983, 0.0, 0.0, 0.0, 0.13045128949025236, 0.012998209742899685, 0.4390684470008469, -0.38395654840750587, 1.07473673649581, -0.9583882860898785, -1.4890689643040282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915149373302167, -0.15917698368703545, 0.30421689359418935]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.155245032836169e-05, 0.0, 0.0, 0.0, 0.11194559031034036, 0.30477146447529685, 0.1314911431823128, -0.1508991860764266, 0.18344074829210388, -0.23026108345311927, 0.06570165427103683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013088322618584253, -0.03195618060570103, -0.0201370848017068]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650817774269087, 0.0, 0.0, 0.0, 0.13465775701949295, 0.02758872767393902, 0.44386480315165316, -0.38765268695102595, 1.0801743857550692, -0.9669865528785562, -1.4906704246464735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091374534237445, -0.16056735725836377, 0.3032821783469575]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.398832997986964e-05, 0.0, 0.0, 0.0, 0.0841293505848115, 0.2918103586207867, 0.09592712301612491, -0.07392277087040194, 0.1087529851851813, -0.17196533577355455, -0.032029206848906214, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002808061855433811, -0.027807471426566453, -0.018694304944637297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650801389506806, 0.0, 0.0, 0.0, 0.13652320198273493, 0.03984645679054772, 0.4431329716366639, -0.38952518044809853, 1.0781276674822544, -0.9702801150218332, -1.4965825306653382, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0910792508765204, -0.1617111529092108, 0.302494627699685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.276952455996106e-06, 0.0, 0.0, 0.0, 0.037308899264839324, 0.245154582332174, -0.014636630299785597, -0.03744986994145168, -0.040934365456297125, -0.06587124286554033, -0.1182421203772961, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005905667218492524, -0.02287591301694061, -0.015751012945449602]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26650803118988836, 0.0, 0.0, 0.0, 0.13666704482363795, 0.05008067345029109, 0.4368678244660211, -0.3901706510562476, 1.0701030944865366, -0.9701011564872696, -1.5051706319344276, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0907575862402097, -0.16263451250884597, 0.3018495883197592]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.458964064437773e-07, 0.0, 0.0, 0.0, 0.002876856818060443, 0.20468433319486734, -0.125302943412855, -0.012909412162981061, -0.1604914599143541, 0.003579170691273517, -0.17176202538178553, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0064332927262117055, -0.01846719199270374, -0.012900787598515191]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665080978805647, 0.0, 0.0, 0.0, 0.13568531702724146, 0.05914434915414227, 0.42725388003563197, -0.38971459154112875, 1.0586131074142202, -0.9684068699763376, -1.5155581877737405, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0903957821890682, -0.16338066031397486, 0.3013166444802918]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3338135262684832e-06, 0.0, 0.0, 0.0, -0.019634555927929745, 0.18127351407702347, -0.19227888860778286, 0.00912119030237735, -0.22979974144633025, 0.03388573021863844, -0.20775111678625907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007236081022829653, -0.014922956102577895, -0.01065887678934925]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665081863534346, 0.0, 0.0, 0.0, 0.13391103084956862, 0.06795480547931773, 0.4157879777469817, -0.38811134525111096, 1.0450879208182193, -0.9665444965990493, -1.5276315614571991, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0899599595868004, -0.16398814343855117, 0.30086138408588115]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7694573978541509e-06, 0.0, 0.0, 0.0, -0.03548572355345654, 0.1762091265035094, -0.22931804577300557, 0.032064925800355436, -0.2705037319200173, 0.037247467545766466, -0.24146747366917187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00871645204535687, -0.012149662491526091, -0.00910520788821287]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665461799089997, 0.0, 0.0, 0.0, 0.13146126483273446, 0.07652825355701467, 0.4033085088511127, -0.38493420886485125, 1.030109522441329, -0.9653533812905258, -1.5426434886649438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0894425177304805, -0.16447574832831285, 0.3004563918844879]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007598711113021792, 0.0, 0.0, 0.0, -0.04899532033668302, 0.17146896155393884, -0.24958937791737912, 0.06354272772519484, -0.29956796753780474, 0.023822306170469723, -0.3002385441548945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010348837126396788, -0.009752097795233455, -0.008099844027864473]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26666554148599386, 0.0, 0.0, 0.0, 0.12830129192905287, 0.08399149483096947, 0.39032995285917793, -0.37922906302824866, 1.0137527008210865, -0.9653894799001311, -1.563471781331054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.08883459839963, -0.1648471955320758, 0.30007671002592917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023872315398834527, 0.0, 0.0, 0.0, -0.06319945807363181, 0.1492648254790959, -0.259571119838695, 0.11410291673205217, -0.3271364324048506, -0.0007219721921052878, -0.41656585332220303, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012158386617011855, -0.007428944075259162, -0.007593637171174897]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26728141662187876, 0.0, 0.0, 0.0, 0.12362690604217573, 0.08790674566505206, 0.377660390136164, -0.36724591972114223, 0.9935813288175968, -0.968288932200734, -1.5919881189700735, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0877719270490034, -0.1650705714123232, 0.2996123806173295]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01231750271769835, 0.0, 0.0, 0.0, -0.09348771773754293, 0.0783050166816517, -0.2533912544602793, 0.2396628661421287, -0.4034274400697956, -0.05798904601205637, -0.5703267527803932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.021253427012531825, -0.00446751760494782, -0.00928658817199441]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2679313688641265, 0.0, 0.0, 0.0, 0.11672231334943953, 0.08895280918422309, 0.3690498205105754, -0.34600996860866495, 0.9658454065507099, -0.9720786424499401, -1.626801189077347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0857484200495358, -0.16464695637973825, 0.29884700218737964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044844954996, 0.0, 0.0, 0.0, -0.138091853854724, 0.020921270383420384, -0.17221139251177167, 0.4247190222495453, -0.5547184453377353, -0.07579420498412379, -0.6962614021454696, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04047013998935348, 0.008472300651699011, -0.015307568598996395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2685813209868043, 0.0, 0.0, 0.0, 0.10954378873053226, 0.08632890300778437, 0.36824824319515637, -0.31927120912332546, 0.9342949205563862, -0.9746179452513145, -1.666651645003287, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.083023045803578, -0.16301433752773437, 0.29795106993247233]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042453556677, 0.0, 0.0, 0.0, -0.1435704923781454, -0.05247812352877451, -0.016031546308380135, 0.5347751783570656, -0.6310097198864753, -0.05078605602748728, -0.7970091185188022, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.054507484919151944, 0.032652377040077986, -0.017918645098145985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2686516005904908, 0.0, 0.0, 0.0, 0.10428669769076393, 0.07628502935485647, 0.3778661248090947, -0.2907796419992226, 0.9026798680829154, -0.9749350605070586, -1.7077894870913664, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0803772640896978, -0.16058746384860462, 0.29754491614625755]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014055920737299395, 0.0, 0.0, 0.0, -0.10514182079536669, -0.2008774730585581, 0.19235763227876723, 0.569831342482057, -0.6323010494694157, -0.0063423051148813955, -0.8227568417615871, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05291563427760489, 0.0485374735825949, -0.008123075724295943]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2680016483551084, 0.0, 0.0, 0.0, 0.10120005714688729, 0.05666513464448504, 0.3941534653575288, -0.26428526666878654, 0.8747502491298513, -0.9738854034217097, -1.7464647153416544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0785893570405622, -0.15778290809208018, 0.2981955306441437]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904470764783, 0.0, 0.0, 0.0, -0.061732810877532934, -0.39239789420742854, 0.32574681096868274, 0.5298875066087217, -0.5585923790612817, 0.02099314170697731, -0.7735045650057581, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03575814098271052, 0.05609111513048871, 0.013012289957723605]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26735169611146326, 0.0, 0.0, 0.0, 0.0998178908111847, 0.0295421638946813, 0.4133602648408667, -0.2435380831318183, 0.8542560636761456, -0.9716952597636777, -1.7789273297542452, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0784322110847508, -0.1550145897605769, 0.2998406061759964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044872903367, 0.0, 0.0, 0.0, -0.027643326714051994, -0.5424594149960748, 0.384135989666757, 0.4149436707393648, -0.40988370907411387, 0.043802873160641013, -0.6492522882518164, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0031429191162277333, 0.05536636663006559, 0.03290151063705326]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2667017438697361, 0.0, 0.0, 0.0, 0.1001433583102512, -0.0013338828950555381, 0.4317365232665286, -0.23228809137699552, 0.8446761278672981, -0.9718978569206328, -1.801427330329476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.080208217203486, -0.1528358414127333, 0.30222599318340193]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044834542712, 0.0, 0.0, 0.0, 0.00650934998133007, -0.6175209357947367, 0.36752516851323896, 0.22499983509645563, -0.19159871617695112, -0.004051943139103384, -0.4500000115046202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03552012237470164, 0.04357496695687174, 0.04770774014811027]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663145878135147, 0.0, 0.0, 0.0, 0.1003896990353625, -0.03221302221213588, 0.4495087733319046, -0.22678535658697724, 0.8422605188034552, -0.9782431100087028, -1.8177145525521616, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0832051460660506, -0.15080666112179647, 0.3047267424477459]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014057017676928265, 0.0, 0.0, 0.0, 0.004926814502226014, -0.6175827863416068, 0.3554450013075192, 0.1100546958003655, -0.048312181276856714, -0.12690506176140057, -0.32574444445370865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05993857725129234, 0.04058360581873642, 0.05001498528687954]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663701285766606, 0.0, 0.0, 0.0, 0.10066821527059135, -0.059345319480718445, 0.46795462079216266, -0.2232800766204568, 0.8447696823538957, -0.9893224560443802, -1.8315389503451034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.086715213005737, -0.1487528885116559, 0.30671856726873703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011108152629218829, 0.0, 0.0, 0.0, 0.005570324704576973, -0.5426459453716512, 0.3689169492051616, 0.07010559933040919, 0.05018327100881037, -0.2215869207135483, -0.2764879558588347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0702013387937271, 0.04107545220281098, 0.03983649641982247]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666393348969601, 0.0, 0.0, 0.0, 0.10106625856097351, -0.0789811700823969, 0.4859279750664324, -0.21949268893248491, 0.8504107768447529, -1.0018168073624552, -1.8466503729488057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0901412217082123, -0.14685547234691923, 0.30804024879157227]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.644078588155616e-05, 0.0, 0.0, 0.0, 0.007960865807643372, -0.3927170120335691, 0.35946708548539574, 0.07574775375943775, 0.11282188981714397, -0.24988702636149876, -0.30222845207404747, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06852017404950696, 0.037948323294733535, 0.026433630456705208]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666395126421156, 0.0, 0.0, 0.0, 0.10151917057584567, -0.09096536996056655, 0.5021154127540256, -0.21625335040936575, 0.8586376931413159, -1.0138747924524636, -1.8628949719753696, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.092892375155402, -0.14531665009654368, 0.30884473506810733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.554903110104712e-06, 0.0, 0.0, 0.0, 0.009058240297443152, -0.2396839975633929, 0.32374875375186407, 0.06478677046238328, 0.16453832593125972, -0.24115970180016766, -0.32489198053127477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05502306894379624, 0.030776445007510755, 0.016089725530701524]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663948310447894, 0.0, 0.0, 0.0, 0.10199896648580115, -0.09745289120196635, 0.5160305093123795, -0.21387645984880052, 0.8683736623579553, -1.0254458895115903, -1.8781802723931698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0948532708576688, -0.1441345547822357, 0.30932463884584244]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.907527334535394e-07, 0.0, 0.0, 0.0, 0.009595918199109509, -0.12975042482799598, 0.2783019311670768, 0.04753781121130425, 0.19471938433278854, -0.23142194118253395, -0.3057060083560046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.039217914045336366, 0.02364190628615989, 0.00959807555470248]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394749221178, 0.0, 0.0, 0.0, 0.10250291276434123, -0.10029625955514684, 0.5278037406056814, -0.21230141392716348, 0.878831873912644, -1.0369847058741137, -1.8911470338992138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.096251360829597, -0.1431893674730238, 0.3096244347067119]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6364722233934188e-07, 0.0, 0.0, 0.0, 0.01007892557080161, -0.05686736706361008, 0.23546462586603673, 0.031500918432740985, 0.20916423109377233, -0.23077632725047026, -0.25933523012087856, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027961799438562425, 0.018903746184238047, 0.005995917217389561]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947445039915, 0.0, 0.0, 0.0, 0.10303521376321989, -0.10073400735190223, 0.5378115622510466, -0.21135050183611298, 0.8895404049215837, -1.048897898220159, -1.9013420621546255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0973195155287607, -0.14237014097222597, 0.3098349992986931]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.434373712878155e-09, 0.0, 0.0, 0.0, 0.010646019977573178, -0.008754955935107625, 0.20015643290730634, 0.019018241821010154, 0.21417062017879587, -0.2382638469209087, -0.2039005651082354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021363093983276005, 0.016384530015956262, 0.004211291839624496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394744803509, 0.0, 0.0, 0.0, 0.1035744501797725, -0.09940582361540297, 0.5460806789377122, -0.21086393963492173, 0.9007521518355773, -1.0615263475782342, -1.908811016539398, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.098222297250128, -0.14160265492798974, 0.3100074373788788]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.990351826313005e-10, 0.0, 0.0, 0.0, 0.010784728331052153, 0.02656367472998524, 0.16538233373331096, 0.009731244023825199, 0.22423493827987162, -0.25256898716149906, -0.149379087695453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01805563442734626, 0.015349720884724733, 0.003448761603714218]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394744980217, 0.0, 0.0, 0.0, 0.1041376044930153, -0.09678128062280042, 0.552898682656787, -0.21078042593764734, 0.912221670666274, -1.075108040923779, -1.913878862912966, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0990878398188548, -0.14082473494293618, 0.31017517162864056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5341606329656277e-10, 0.0, 0.0, 0.0, 0.011263086264856028, 0.05249085985205092, 0.13636007438149636, 0.0016702739454878077, 0.22939037661393472, -0.2716338669108946, -0.10135692747135597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01731085137453581, 0.01555839970107092, 0.00335468499523483]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947469190663, 0.0, 0.0, 0.0, 0.10475113924275939, -0.09313250334395277, 0.5585958113039441, -0.21111173608415368, 0.9236329839616089, -1.0899769087187847, -1.9168992577640986, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1000283664753507, -0.13997562096400307, 0.31036370424577114]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.877698386723558e-09, 0.0, 0.0, 0.0, 0.012270694994881804, 0.07297554557695296, 0.11394257294314156, -0.006626202930126687, 0.22822626590669687, -0.2973773559001125, -0.06040789702265616, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018810533129916214, 0.016982279578662333, 0.0037706523426117985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394747384194, 0.0, 0.0, 0.0, 0.10544734103966462, -0.0885293516690003, 0.5634293707154018, -0.2119510158948703, 0.9346379340855314, -1.1067951180099072, -1.918131772821261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1011742403059177, -0.13897479027663898, 0.3106003258346873]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.302561045884131e-10, 0.0, 0.0, 0.0, 0.013924035938104477, 0.09206303349904948, 0.09667118822915322, -0.01678559621433242, 0.22009900247845024, -0.33636418582244876, -0.024650301143245325, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022917476611338188, 0.020016613747281843, 0.004732431778322373]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947482430383, 0.0, 0.0, 0.0, 0.10628750632194282, -0.08270416728780662, 0.5675233070829718, -0.21356522344892667, 0.9446931563219226, -1.127143991421212, -1.9176399243147473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1027535693918114, -0.13766703995064183, 0.3109321384918999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7176884297616065e-09, 0.0, 0.0, 0.0, 0.016803305645564075, 0.11650368762387371, 0.08187872735140111, -0.03228415108112746, 0.2011044447278249, -0.40697746822609626, 0.009836970130274764, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.031586581717873985, 0.026155006519942833, 0.0066362531442522585]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666394750031692, 0.0, 0.0, 0.0, 0.10723259841335893, -0.07586443302824697, 0.5711059670323481, -0.21588617458598264, 0.953861132867947, -1.1507169923517677, -1.9155953144259321, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.10477859921867, -0.13605752488766693, 0.3113597282582764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.577307397365356e-09, 0.0, 0.0, 0.0, 0.018901841828322066, 0.13679468519119306, 0.07165319898752551, -0.04641902274111955, 0.18335953092048912, -0.47146001861111553, 0.04089219777630271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040500596537176116, 0.03219030125949828, 0.008551795327530504]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663947391426773, 0.0, 0.0, 0.0, 0.10865942933995708, -0.07176014875249087, 0.5704273509193154, -0.2226638675960555, 0.9583918639217596, -1.1737641209217982, -1.9082479434287793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1079607645274099, -0.13431765715345406, 0.31225820748069516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.1778028852162315e-08, 0.0, 0.0, 0.0, 0.028536618531963057, 0.08208568551512205, -0.013572322260652997, -0.1355538602014572, 0.0906146210762515, -0.46094257140061023, 0.14694741994305338, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06364330617479678, 0.034797354684257265, 0.01796958444837487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26663112093558483, 0.0, 0.0, 0.0, 0.11027409814355077, -0.07414131241423617, 0.5647859895171783, -0.2330747114197279, 0.9586646977241573, -1.1925353772853342, -1.8923501355117325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.111927299926172, -0.13262485006143357, 0.31336316022259253]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0001670595736584105, 0.0, 0.0, 0.0, 0.03229337607187374, -0.047623273234906116, -0.11282722804274309, -0.20821687647344822, 0.005456676047955619, -0.37542512727072297, 0.31795615834093655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07933070797524053, 0.033856141840409915, 0.02209905483794688]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665729533781325, 0.0, 0.0, 0.0, 0.11209662238980313, -0.08064335120819682, 0.5572353646644999, -0.24596585946947658, 0.9574012102468038, -1.2050367284324257, -1.869260795220862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1161728880092183, -0.13102792739809824, 0.3145060657513225]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011633511490462473, 0.0, 0.0, 0.0, 0.03645048492504721, -0.13004077587921303, -0.15101249705356914, -0.2578229609949733, -0.025269749547069398, -0.25002702294183066, 0.4617868058174091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08491176166092719, 0.03193845326670661, 0.022858110574599782]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665655334932147, 0.0, 0.0, 0.0, 0.11430989209163614, -0.08751626513610261, 0.551525476301931, -0.2575873117492882, 0.9583514011242869, -1.2143878047284404, -1.8427299225554783, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.120137761290782, -0.1298249453901871, 0.3150619241168444]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00014839769835631135, 0.0, 0.0, 0.0, 0.04426539403666038, -0.13745827855811565, -0.11419776725137558, -0.23242904559623215, 0.01900381754966158, -0.18702152592029314, 0.5306174533076717, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07929746563127339, 0.0240596401582226, 0.01111716731043802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26656588231141, 0.0, 0.0, 0.0, 0.11665870778568183, -0.09306539416236148, 0.5512407506352881, -0.2656888694296548, 0.9652652550290952, -1.2207129665355423, -1.8165075169741374, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1232140844241048, -0.12916738707117403, 0.3151512416882477]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.9763639052446245e-06, 0.0, 0.0, 0.0, 0.04697631388091366, -0.11098258052517734, -0.0056945133328581005, -0.16203115360733247, 0.1382770780961669, -0.1265032361420368, 0.5244481116268199, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06152646266645549, 0.013151166380261205, 0.0017863514280658868]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26656609628160016, 0.0, 0.0, 0.0, 0.11873341763145234, -0.09354074957168348, 0.5541901095692269, -0.26773828995836224, 0.9751935851927864, -1.2263234009311401, -1.7943435761581585, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1247651852460623, -0.12911934008385495, 0.31475238201008143]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.27940380375049e-06, 0.0, 0.0, 0.0, 0.04149419691541047, -0.00950710818644003, 0.058987178678774635, -0.04098841057414922, 0.19856660327382422, -0.1122086879119565, 0.44327881631957866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.031022016439150257, 0.0009609397463816553, -0.007977193563325016]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2665661163703244, 0.0, 0.0, 0.0, 0.12029367255144623, -0.08897512639969976, 0.5583093217689795, -0.2661175847189831, 0.9860490494462002, -1.2326694659354682, -1.7799880898911347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.124993528837271, -0.12946907370462055, 0.3141244588885657]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.0177448482741343e-07, 0.0, 0.0, 0.0, 0.031205098399877576, 0.09131246343967446, 0.08238424399505269, 0.03241410478758261, 0.21710928506827631, -0.12692130008656408, 0.2871097253404775, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004566871824174354, -0.006994672415312128, -0.012558462430313902]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26656611426012494, 0.0, 0.0, 0.0, 0.12140860503693514, -0.08093946354724181, 0.5625433647990794, -0.263380120082581, 0.9967065781364572, -1.2408256349942755, -1.7722594960880946, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1244587143820655, -0.1299159472178867, 0.31351420090667553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.220398944589155e-08, 0.0, 0.0, 0.0, 0.022298649709778257, 0.16071325704915906, 0.08468086060199743, 0.05474929272804286, 0.21315057380514052, -0.16312338117614517, 0.15457187606080014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010696289104109857, -0.008937470265323284, -0.012205159637803139]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26659687367740176, 0.0, 0.0, 0.0, 0.12203534824559277, -0.07067589824227796, 0.5664280901444293, -0.26061309543780914, 1.0063229247224652, -1.252901838734886, -1.7681370241177639, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1237138679863203, -0.13013871840631835, 0.31313111853589076]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006151883455367837, 0.0, 0.0, 0.0, 0.012534864173152627, 0.20527130609927693, 0.07769450690699686, 0.05534049289543743, 0.1923269317201573, -0.2415240748122098, 0.08244943940661416, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014896927914903466, -0.0044554237686326836, -0.007661647415695828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666008979926753, 0.0, 0.0, 0.0, 0.12177275055561299, -0.05807443302727744, 0.5662135594415285, -0.25636078146715124, 1.0111481260218944, -1.2651480931702654, -1.771088187183669, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1229549194196509, -0.130543171332653, 0.3128518990146296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.04863054709588e-05, 0.0, 0.0, 0.0, -0.005251953799595598, 0.25202930430001047, -0.004290614058015119, 0.08504627941315808, 0.096504025988582, -0.2449250887075872, -0.05902326131810244, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015178971333388695, -0.008089058526692911, -0.005584390425223259]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666007510666907, 0.0, 0.0, 0.0, 0.12100280862888602, -0.04526934340964283, 0.5603666017652729, -0.251526664499642, 1.009913251422739, -1.2738152461760386, -1.7788392941006013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1221218740693075, -0.13121248376351222, 0.31260484406327055]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9385196917752006e-06, 0.0, 0.0, 0.0, -0.01539883853453951, 0.25610179235269215, -0.11693915352511344, 0.09668233935018507, -0.024697491983109054, -0.17334306011546274, -0.15502213833864364, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01666090700686577, -0.01338624861718422, -0.004941099027181387]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2666848100756695, 0.0, 0.0, 0.0, 0.1199574079682994, -0.03371951263850336, 0.551531415170722, -0.2462664246414506, 1.0047330815632545, -1.2774814331579278, -1.7928485007855726, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1212609276320598, -0.13201021098312754, 0.31237340901825184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016811801795773593, 0.0, 0.0, 0.0, -0.02090801321173233, 0.2309966154227894, -0.17670373189101793, 0.10520479716382841, -0.10360339718969075, -0.07332373963778388, -0.2801841336994271, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01721892874495362, -0.015954544392306473, -0.0046287009003737195]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2673347622718793, 0.0, 0.0, 0.0, 0.11865122438732395, -0.024030130294738897, 0.5434579992235014, -0.23683006194940895, 0.9971435604710508, -1.2790764761625824, -1.8157728396034851, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1203187623303152, -0.13284064164857118, 0.31213266422047764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904392419585, 0.0, 0.0, 0.0, -0.02612367161950905, 0.19378764687528932, -0.16146831894441435, 0.18872725384083294, -0.15179042184407257, -0.031900860093091066, -0.4584867763582513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.018843306034891618, -0.016608613308873012, -0.004814895955483367]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.267417901791194, 0.0, 0.0, 0.0, 0.11902230517772423, -0.01995119632189494, 0.5358855538820204, -0.22696757638535278, 0.9908946879467333, -1.2808863187324109, -1.8438623105702705, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1200824984091418, -0.1341069017486618, 0.3123133084187358]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016627903862944174, 0.0, 0.0, 0.0, 0.0074216158080056965, 0.08157867945687913, -0.1514489068296178, 0.19724971128112317, -0.12497745048634938, -0.03619685139657097, -0.5617894193357071, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004725278423468242, -0.025325202001812486, 0.0036128839651624056]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26676794954895106, 0.0, 0.0, 0.0, 0.12166656484254655, -0.025232710719865332, 0.5250640792485602, -0.22042896794922842, 0.9897364639899123, -1.2834635398719514, -1.8733669136859443, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1213403956761445, -0.136210589434846, 0.3130765427891761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044844858806, 0.0, 0.0, 0.0, 0.05288519329644632, -0.1056302879594079, -0.21642949266920317, 0.13077216872248743, -0.02316447913642021, -0.05154442279080832, -0.5900920623134763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025157945340053757, -0.04207375372368444, 0.01526468740880673]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26611799742068276, 0.0, 0.0, 0.0, 0.12578515940349042, -0.03869112004879706, 0.5072435960886068, -0.2209642364473661, 0.9974188880018383, -1.2858962439721608, -1.9005366489680777, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1243700683666964, -0.1388888171362498, 0.31423990260231954]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999042565365907, 0.0, 0.0, 0.0, 0.08237189121887734, -0.2691681865786345, -0.35640966319906897, -0.01070536996275362, 0.15364848023852062, -0.04865408200418961, -0.5433947056426673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06059345381103688, -0.05356455402807532, 0.023267196262868835]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26546804518680944, 0.0, 0.0, 0.0, 0.13075018130111515, -0.05657642431246232, 0.48297273742143093, -0.23232338181811893, 1.0119183324996015, -1.2879729767645547, -1.9216215164222221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1287291581252799, -0.14162405911959472, 0.3156199152378934]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044677466806, 0.0, 0.0, 0.0, 0.09930043795249452, -0.3577060852733051, -0.48541717334351786, -0.22718290741505645, 0.28998888995526245, -0.04153465584787596, -0.4216973490828876, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08718179517167013, -0.05470483966689882, 0.02760025271147748]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26481809299343073, 0.0, 0.0, 0.0, 0.135818968472395, -0.0751386235201285, 0.45559596792010215, -0.2523273539266939, 1.029484797501975, -1.2918491914925134, -1.932871516063369, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1341689123566445, -0.1438356262809585, 0.31719308234527926]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904386757372, 0.0, 0.0, 0.0, 0.10137574342559665, -0.37124398415332344, -0.5475353900265761, -0.40007944217149927, 0.35132930004747, -0.07752429455917591, -0.22499999282293798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10879508462729372, -0.044231343227275566, 0.03146334214771683]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26474781076378506, 0.0, 0.0, 0.0, 0.14060011729301136, -0.0906277177018237, 0.42886328745564545, -0.277226152783736, 1.0527379302855, -1.30000824604525, -1.9380366478782074, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1398978798105304, -0.14512438020162943, 0.31843549499344914]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056445929130704, 0.0, 0.0, 0.0, 0.09562297641232702, -0.3097818836339041, -0.5346536092891339, -0.4979759771408415, 0.46506265567050176, -0.163181091054731, -0.10330263629676915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11457934907771532, -0.025775078413418917, 0.024848252963397918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475336198326654, 0.0, 0.0, 0.0, 0.14593744984608215, -0.09929382794533224, 0.4065246674569948, -0.3032697816340956, 1.0788418743028663, -1.3087001795186268, -1.9408669086119057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1454728142690553, -0.14615455240260572, 0.318729443041711]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011102438962940072, 0.0, 0.0, 0.0, 0.10674665106141537, -0.17332220487017067, -0.4467723999730137, -0.5208725770071918, 0.5220788803473267, -0.1738386694675371, -0.056605214673967945, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11149868917049918, -0.020603444019525664, 0.005878960965238145]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475568247334863, 0.0, 0.0, 0.0, 0.15113248240327118, -0.10300930815599448, 0.391918430165455, -0.3267082437849521, 1.1045703119431944, -1.3148458242623713, -1.9451122961155005, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.150289226977121, -0.14709371681787667, 0.3184515016600449]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6409801641558184e-05, 0.0, 0.0, 0.0, 0.10390065114378041, -0.07430960421324469, -0.2921247458307956, -0.4687692430171295, 0.5145687528065628, -0.12291289487488968, -0.08490775007189472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09632825416131231, -0.01878328830541886, -0.005558827633323268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475585939415497, 0.0, 0.0, 0.0, 0.1557595325640012, -0.10427926184610248, 0.3839272248065305, -0.34513218754787406, 1.1280210112986042, -1.3190541266713047, -1.9513351349853454, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1538211978124717, -0.14803428605984023, 0.3179542479553117]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.538416126590643e-06, 0.0, 0.0, 0.0, 0.09254100321460045, -0.025399073802160055, -0.1598241071784906, -0.36847887525843925, 0.46901398710819336, -0.08416604817866853, -0.12445677739689606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07063941670701401, -0.018811384839271427, -0.009945074094664006]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558295821085, 0.0, 0.0, 0.0, 0.15958299641283583, -0.1039096139271208, 0.38073863529279217, -0.35835464332263395, 1.1482155265850664, -1.3226050966802707, -1.9596537804434433, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1561227720412133, -0.14895503079596983, 0.3173980767623391]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.962409291951285e-07, 0.0, 0.0, 0.0, 0.07646927697669201, 0.007392958379633649, -0.0637717902747666, -0.2644491154951975, 0.4038903057292426, -0.07101940017931986, -0.16637290916195768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04603148457483186, -0.01841489472259184, -0.011123423859451843]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475581554977595, 0.0, 0.0, 0.0, 0.16265616411282718, -0.10269688849069691, 0.3809062433273441, -0.367478584409937, 1.1652728078396457, -1.326112684408923, -1.9687258566556634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1575137478171047, -0.14979371930473845, 0.3168727558922333]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.806466512971204e-07, 0.0, 0.0, 0.0, 0.06146335399982743, 0.024254508728477515, 0.00335216069103815, -0.18247882174606134, 0.34114562509158686, -0.07015175457304522, -0.18144152424440052, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027819515517827964, -0.016773770175372207, -0.010506417402115886]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264755813025721, 0.0, 0.0, 0.0, 0.16514459481174038, -0.10135686416622813, 0.3834151663969018, -0.37383777163558324, 1.1797935015316907, -1.3297155596236636, -1.976997251546014, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.158334486209964, -0.15049953255602447, 0.3164258923415723]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.048109882255089e-08, 0.0, 0.0, 0.0, 0.04976861397826402, 0.026800486489375747, 0.050178461391155144, -0.12718374451292472, 0.29041387384090206, -0.07205750429480978, -0.1654278978070107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016414767857187818, -0.01411626502572041, -0.008937271013219575]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558103342911, 0.0, 0.0, 0.0, 0.16720366730878633, -0.10023468418418392, 0.387581004949629, -0.3783838932854358, 1.1924034154309011, -1.3334027330575022, -1.983780112118894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1588127363106104, -0.15106330532837506, 0.31606874728641027]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.382859816940282e-08, 0.0, 0.0, 0.0, 0.041181449940919164, 0.02244359964088426, 0.0833167710545432, -0.09092243299705197, 0.2521982779842101, -0.07374346867677095, -0.1356572114576017, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009565002012928484, -0.011275455447012025, -0.007142901103241041]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475581003790605, 0.0, 0.0, 0.0, 0.1689560534499147, -0.09946748047982665, 0.3929354016428149, -0.38176000404298466, 1.203631860081062, -1.337124530814242, -1.9889109910060323, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1590906123981022, -0.15149739828487205, 0.3157953616895498]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.927700740377247e-09, 0.0, 0.0, 0.0, 0.03504772282256774, 0.015344074087145602, 0.10708793386371737, -0.06752221515097692, 0.2245688930032171, -0.07443595513479569, -0.10261757774276611, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00555752174983281, -0.008681859129940064, -0.005467711937209329]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558100359005, 0.0, 0.0, 0.0, 0.1704995671065108, -0.09915159157186919, 0.39914801918122544, -0.3844682955935468, 1.213907261524332, -1.340824481944231, -1.9922957843781004, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1592723526652995, -0.1518137834527632, 0.3155972009139256]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.011177440788874e-11, 0.0, 0.0, 0.0, 0.030870273131921606, 0.0063177781591493044, 0.1242523507682113, -0.054165831011242185, 0.20550802886540154, -0.07399902259977635, -0.06769586744136027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003634805343945794, -0.006327703357823181, -0.003963215512484091]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558085662291, 0.0, 0.0, 0.0, 0.17187651630342948, -0.09910888493655559, 0.40599657218995844, -0.38661304314915096, 1.2234811349818342, -1.3445168438227446, -1.9945790920520396, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1593678890644947, -0.15205208981785018, 0.31545194982204594]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9393427582632583e-08, 0.0, 0.0, 0.0, 0.027538983938373562, 0.0008541327062720509, 0.13697106017466001, -0.04289495111208375, 0.19147746915004307, -0.07384723757027259, -0.04566615347878475, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0019107279839029878, -0.004766127301739837, -0.002905021837593614]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26475580785935104, 0.0, 0.0, 0.0, 0.1730934420791447, -0.0990235219309919, 0.4133330266427755, -0.3880618826063071, 1.2324878441260727, -1.348245002933955, -1.996783590690115, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1593319341255943, -0.1522665946227727, 0.31533119435951523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4137561068418236e-08, 0.0, 0.0, 0.0, 0.02433851551430429, 0.0017072601112737692, 0.14672908905634102, -0.0289767891431228, 0.18013418288477226, -0.07456318222420621, -0.0440899727615052, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0007190987780078869, -0.004290096098450377, -0.002415109250613951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558077968646, 0.0, 0.0, 0.0, 0.17409877817007832, -0.09825174536053224, 0.42107658077326215, -0.38823293621845884, 1.2409137450418013, -1.352089004642658, -2.0008772461536632, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1590155722611426, -0.15255415325309543, 0.31518905518415047]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2497287464934408e-09, 0.0, 0.0, 0.0, 0.020106721818672502, 0.01543553140919305, 0.1548710826097334, -0.0034210722430344717, 0.16851801831457158, -0.07688003417406002, -0.08187310927096186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006327237289034513, -0.005751172606454401, -0.002842783507295123]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558079949703, 0.0, 0.0, 0.0, 0.1748339895669449, -0.09620155172155666, 0.4291823538818404, -0.38653914581903037, 1.2487351388307413, -1.3560677409044783, -2.008690443186472, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1582706405482894, -0.15300899871025844, 0.3149833490622006]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.962113489348294e-09, 0.0, 0.0, 0.0, 0.014704227937331824, 0.0410038727795118, 0.16211546217156517, 0.03387580798856945, 0.15642787577880118, -0.07957472523640675, -0.15626394065617882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014898634257065224, -0.009096909143260206, -0.004114122438997861]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647558080231777, 0.0, 0.0, 0.0, 0.17516484739264052, -0.09180184680902725, 0.4376559402450063, -0.38178444469816747, 1.2558001968204227, -1.3601565229409203, -2.0233859408392267, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1568147441090033, -0.15379350374650566, 0.3146458029882803]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.641483867872276e-10, 0.0, 0.0, 0.0, 0.006617156513912412, 0.08799409825058811, 0.16947172726331852, 0.0950940224172579, 0.1413011597936278, -0.08177564072883751, -0.2939099530550925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.029117928785723154, -0.015690100724944367, -0.006750921478405622]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26540576026701346, 0.0, 0.0, 0.0, 0.1754279068716065, -0.08334579121692463, 0.44832620853288535, -0.37021883285598434, 1.2583589190130209, -1.3640906853814472, -2.0468821888828677, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1542454763484162, -0.15569340651474145, 0.3137680676992551]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044876714992, 0.0, 0.0, 0.0, 0.005261189579319909, 0.16912111184205253, 0.21340536575758065, 0.23131223684366256, 0.05117444385196604, -0.07868324881053776, -0.46992496087282276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05138535521174349, -0.03799805536471586, -0.017554705780504908]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654907859183264, 0.0, 0.0, 0.0, 0.1731709251874777, -0.07458338494419613, 0.45744315876276215, -0.3555923102917338, 1.2601613018153504, -1.3641202364107963, -2.0754291873177264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1509633414978186, -0.15791999451793395, 0.3129751423110955]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017005130262588899, 0.0, 0.0, 0.0, -0.0451396336825758, 0.17524812545457014, 0.18233900459753638, 0.2925304512850105, 0.03604765604658902, -0.0005910205869804203, -0.5709399686971779, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06564269701195061, -0.04453176006385011, -0.01585850776319133]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548716522068505, 0.0, 0.0, 0.0, 0.16856883971401374, -0.06926462798863547, 0.4612567909493772, -0.34165487700385033, 1.2609730931345458, -1.3578559968187738, -2.1052769361442403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1473719052439906, -0.1596879368646509, 0.3128920267594651]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.241395282739653e-05, 0.0, 0.0, 0.0, -0.09204170946927914, 0.10637513911121295, 0.07627264373230136, 0.27874866575767004, 0.016235826383906346, 0.12528479184045083, -0.5969549765302816, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07182872507656154, -0.035358846934339196, -0.001662311032608249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548475405059074, 0.0, 0.0, 0.0, 0.1631413419816036, -0.07113944345195383, 0.4583551862894037, -0.33215650330077373, 1.2609642874566485, -1.3489459464432183, -2.132675438210116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.143874290743903, -0.16021487611798102, 0.3141437184010465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.822340188646102e-05, 0.0, 0.0, 0.0, -0.10854995464820284, -0.03749630926636703, -0.05803209319947028, 0.18996747406153158, -0.00017611355794367942, 0.17820100751111112, -0.5479700413175117, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06995229000175233, -0.010538785066602385, 0.025033832831627675]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654845205228911, 0.0, 0.0, 0.0, 0.1583296919722795, -0.07837526292245249, 0.4518060035575307, -0.32908284116992875, 1.260096844384238, -1.3386520392613326, -2.1538747281159676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.141255101454644, -0.15990244748928684, 0.3161052210830155]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.67055399237876e-06, 0.0, 0.0, 0.0, -0.09623300018648182, -0.14471638940997328, -0.13098365463746003, 0.06147324261689949, -0.017348861448211395, 0.2058781436377146, -0.42398579811703146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.052383785785181984, 0.006248572573883645, 0.03923005363937987]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548453780614667, 0.0, 0.0, 0.0, 0.15446749555267678, -0.08889892552038234, 0.4442355712850151, -0.3297943525881716, 1.2595494542619827, -1.324626565985125, -2.1674459669903485, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1394476634199182, -0.15941609228721562, 0.31815173156266324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4566511142357926e-07, 0.0, 0.0, 0.0, -0.07724392839205443, -0.21047325195859684, -0.15140864545031196, -0.014230228364857003, -0.010947802445103506, 0.28050946552414846, -0.2714247774876201, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0361487606945131, 0.009727104041424363, 0.040930209592955534]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548142273267195, 0.0, 0.0, 0.0, 0.15182016214011365, -0.10175673598711157, 0.43939379155620334, -0.3323149796161467, 1.263071911592247, -1.306785838672453, -2.17622992441997, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1379686260378619, -0.15928187046328035, 0.3198697033409628]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.23014694947478e-05, 0.0, 0.0, 0.0, -0.05294666825126235, -0.2571562093345846, -0.09683559457623514, -0.05041254055950254, 0.07044914660528818, 0.35681454625344333, -0.1756791485924284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02958074764112502, 0.0026844364787054122, 0.034359435565991754]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.265481014694849, 0.0, 0.0, 0.0, 0.15027430449716725, -0.11374025049856382, 0.4410259780839107, -0.3365164917066845, 1.273422641355929, -1.2888798076265053, -2.1804901952978764, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.13674121135096, -0.1591684852935765, 0.3212235456848956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.160756457979803e-06, 0.0, 0.0, 0.0, -0.030917152858928196, -0.23967029022904482, 0.03264373055414685, -0.08403024181075607, 0.20701459527364163, 0.35812062091894925, -0.08520541755812483, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024548293738037193, 0.002267703394076924, 0.027076846878655855]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654810319127324, 0.0, 0.0, 0.0, 0.14946966470417497, -0.12305942182075875, 0.4468948388792953, -0.3420547850041193, 1.2868537471179413, -1.2746582102168769, -2.180193797963985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.135978842483269, -0.15877309799065983, 0.3223042061381608]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4435766767572e-07, 0.0, 0.0, 0.0, -0.01609279585984567, -0.1863834264438988, 0.11737721590769293, -0.11076586594869536, 0.26862211524024665, 0.28443194819256845, 0.005927946677824161, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.015247377353821322, 0.007907746058333266, 0.021613209065304007]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654810433659598, 0.0, 0.0, 0.0, 0.14920359010584522, -0.13003658338046162, 0.45463507301977807, -0.3484331869417402, 1.3007274535607514, -1.2671711890763535, -2.1756836716815187, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.135739025176766, -0.1581050236647337, 0.32319198773658214]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2906454708137905e-07, 0.0, 0.0, 0.0, -0.00532149196659488, -0.13954323119405723, 0.15480468280965515, -0.1275680387524183, 0.277474128856203, 0.14974042281046887, 0.09020252564932817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004796346130062132, 0.013361486518522632, 0.017755631968426874]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654810395106448, 0.0, 0.0, 0.0, 0.1493877706102916, -0.13573758333410182, 0.4630217862685106, -0.3555927139896415, 1.314259369566811, -1.2649276677337158, -2.166980426591682, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1360143612179239, -0.15723503459111224, 0.3239529142816831]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.710630005964129e-08, 0.0, 0.0, 0.0, 0.0036836100889274977, -0.11401999907280394, 0.16773426497465, -0.14319054095802625, 0.2706383201211919, 0.044870426852752526, 0.1740649017967285, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005506720823154435, 0.01739978147242914, 0.015218530902019162]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26548099530005076, 0.0, 0.0, 0.0, 0.1500319455931379, -0.14141674075188548, 0.4716180402900231, -0.3641612357824809, 1.3275794471504883, -1.2660362715287812, -2.1528945867527365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1368770320705006, -0.15615768394320664, 0.3246606296460654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.842118807659552e-07, 0.0, 0.0, 0.0, 0.012883499656926279, -0.11358314835567314, 0.17192508043024968, -0.17137043585678793, 0.2664015516735447, -0.022172075901306335, 0.28171679677891104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017253417051536955, 0.021547012958112136, 0.014154307287645603]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264831048379349, 0.0, 0.0, 0.0, 0.1516181473741707, -0.14517144554717934, 0.4796196796977191, -0.37788875162287755, 1.3425974287436169, -1.2676756784447298, -2.1299063882774556, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1385116100787882, -0.15434066434005447, 0.32541820208253686]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012998938414034647, 0.0, 0.0, 0.0, 0.031724035620655906, -0.0750940959058772, 0.1600327881539215, -0.2745503168079332, 0.300359631862571, -0.03278813831897105, 0.4597639695056208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03269156016575021, 0.036340392063043486, 0.015151448729429232]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26418109615602237, 0.0, 0.0, 0.0, 0.1526557561660527, -0.14548000674951175, 0.4832767061474716, -0.4005252614607949, 1.3590989519071794, -1.2663331649362104, -2.099515829540973, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.140461132091098, -0.15127741481319085, 0.3261074017863471]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044466533136, 0.0, 0.0, 0.0, 0.020752175837639823, -0.006171224046648341, 0.07314052899504955, -0.45273019675834775, 0.33003046327125096, 0.026850270170387512, 0.6078111747296513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.038990440246195045, 0.06126499053727262, 0.013783994076205414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2641108141286731, 0.0, 0.0, 0.0, 0.15546218414131874, -0.13859242435891436, 0.4844254862590161, -0.42832076529623553, 1.3733340166412595, -1.2619406591225981, -2.0654729105432854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1423333750779767, -0.14776047250200158, 0.32657352661894634]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056405469850333, 0.0, 0.0, 0.0, 0.05612855950532085, 0.1377516478119476, 0.022975602230890436, -0.5559100767088119, 0.2847012946816036, 0.08785011627224446, 0.6808583799537539, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03744485973757457, 0.07033884622378545, 0.00932249665198423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26411636770054797, 0.0, 0.0, 0.0, 0.16034436920430686, -0.12160277244366503, 0.486815267220721, -0.4575252631342237, 1.381552623096373, -1.257373844915654, -2.031527631279506, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1437372053560726, -0.14458272820809948, 0.3269181714282179]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001110714374969084, 0.0, 0.0, 0.0, 0.09764370125976249, 0.3397930383049865, 0.047795619234098065, -0.5840899567597636, 0.16437212910227184, 0.09133628413888288, 0.6789055852755898, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02807660556191557, 0.06355488587804224, 0.006892896185431182]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476631991929017, 0.0, 0.0, 0.0, 0.16674118532728036, -0.09619472922739854, 0.49419604891529, -0.48438875497796163, 1.3800062601149365, -1.2553993896826732, -2.0014299917471208, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1442829653396736, -0.14253751496243677, 0.32675965379894406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044374844379, 0.0, 0.0, 0.0, 0.12793632245946995, 0.5081608643253299, 0.14761563389138044, -0.537269836874759, -0.030927259628728276, 0.03948910465961735, 0.6019527906477051, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010915199672019359, 0.040904264913253774, -0.0031703525854760058]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2654162721625312, 0.0, 0.0, 0.0, 0.17279449348232198, -0.06611829470994807, 0.5041827975703563, -0.5051612408281536, 1.37244492767157, -1.2596745127855593, -1.9789299919458065, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1436032911273977, -0.14240867057116127, 0.32646158567424055]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044864820652, 0.0, 0.0, 0.0, 0.12106616310083249, 0.6015286903490094, 0.19973497310132757, -0.415449717003839, -0.15122664886733303, -0.0855024620577235, 0.4499999960262835, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013593484245517389, 0.0025768878255102807, -0.00596136249407027]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2660662243606415, 0.0, 0.0, 0.0, 0.17569644771705706, -0.03512346888574713, 0.5130255139688394, -0.5163404613564648, 1.362618622526514, -1.2707897565801738, -1.9673248641359316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1420893155385865, -0.14340389317892915, 0.3266489670032395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043962204684, 0.0, 0.0, 0.0, 0.058039084694701634, 0.6198965164840186, 0.17685432796966144, -0.22358441056622322, -0.1965261029011192, -0.22230487589228998, 0.23210255619750159, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030279511776224496, -0.01990445215535755, 0.0037476265799785465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26613650661828936, 0.0, 0.0, 0.0, 0.17776141533720877, -0.006960251651377317, 0.5169741982885128, -0.5216763981620784, 1.352922070579278, -1.2849951210806747, -1.9628646084558345, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.14053681844059, -0.14591647981481998, 0.32794679629544626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014056451529575586, 0.0, 0.0, 0.0, 0.04129935240303398, 0.5632643446873963, 0.07897368639346583, -0.10671873611227346, -0.19393103894471997, -0.2841072900100189, 0.08920511360193958, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.031049941959931306, -0.05025173271781655, 0.025956585844135648]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661309572553657, 0.0, 0.0, 0.0, 0.17884278056155437, 0.014621358408666508, 0.5122788541046444, -0.5235133158879759, 1.3466973636417685, -1.298540606422307, -1.961799225602026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1394207491009507, -0.1493876386880295, 0.32973007375906405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00011098725847383424, 0.0, 0.0, 0.0, 0.02162730448691199, 0.4316322012008765, -0.09390688367736919, -0.0367383545179487, -0.1244941387501864, -0.2709097068326459, 0.021307657076168995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02232138679278577, -0.0694231774641908, 0.03566554927235541]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286370482004, 0.0, 0.0, 0.0, 0.17935620579551292, 0.028100798869859958, 0.5022739707061691, -0.5238647945431902, 1.342680268703112, -1.307676220509117, -1.960835999606829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1389165275696802, -0.1530955388865337, 0.3314670906401684]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.6404143305599766e-05, 0.0, 0.0, 0.0, 0.010268504679171286, 0.269588809223869, -0.20009766796950462, -0.007029573104286382, -0.08034189877312857, -0.18271228173619752, 0.0192645199039402, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010084430625411069, -0.07415800397008415, 0.03474033762208626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661284633970455, 0.0, 0.0, 0.0, 0.17949218208518541, 0.035837503476792425, 0.49024536469148206, -0.5235923840831797, 1.339670092518184, -1.309937203688509, -1.960204681647976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1387051011851566, -0.15650412358793706, 0.3329354725451849]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.473023097933565e-06, 0.0, 0.0, 0.0, 0.0027195257934496822, 0.15473409213864933, -0.2405721202937403, 0.0054482092002119745, -0.06020352369856509, -0.04521966358783985, 0.012626359177061307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004228527690471898, -0.06817169402806678, 0.029367638100330547]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661284981773362, 0.0, 0.0, 0.0, 0.17934123962185536, 0.04012180024453085, 0.4780556923221349, -0.5230889841477239, 1.336858828188047, -1.3072920228379028, -1.9603764893145326, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1385546426827868, -0.15943026891055614, 0.3340813313490461]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.956058138763873e-07, 0.0, 0.0, 0.0, -0.003018849266600887, 0.08568593535476852, -0.2437934473869432, 0.01006799870911539, -0.056225286602738504, 0.052903617012127646, -0.0034361533311316333, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0030091700473960405, -0.05852290645238179, 0.02291717607722427]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661285740779218, 0.0, 0.0, 0.0, 0.17896097501599745, 0.04245760128382929, 0.466481105812764, -0.5225285944796508, 1.3338271375482034, -1.3017317808966946, -1.9615150794926115, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1383555406066181, -0.16186781606425044, 0.3349278257576445]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.518011712435235e-06, 0.0, 0.0, 0.0, -0.007605292117158024, 0.0467160207859688, -0.23149173018741878, 0.011207793361459979, -0.06063381279686962, 0.11120483882416278, -0.02277180356158058, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003982041523374193, -0.0487509430738856, 0.01692988817196832]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612859677635453, 0.0, 0.0, 0.0, 0.1783963394408925, 0.043709687042905426, 0.45571602384181986, -0.5219809142040578, 1.3304231847415962, -1.2945127618034795, -1.9635608096250026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1380716520722918, -0.16388160383193717, 0.33552462708938496]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.5396865505473667e-07, 0.0, 0.0, 0.0, -0.011292711502098991, 0.025041715181522775, -0.21530163941888222, 0.010953605511861971, -0.06807905613214547, 0.14438038186430266, -0.040914602647820694, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.005677770686525882, -0.04027575535373461, 0.011936026634809346]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286021093255, 0.0, 0.0, 0.0, 0.17768358330020043, 0.044349384172770866, 0.4457059759345147, -0.5214658830805912, 1.3266424561195191, -1.286306606469063, -1.9663733686309133, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.137699831340902, -0.16555630614746336, 0.33592396463254615]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0665941919858273e-07, 0.0, 0.0, 0.0, -0.014255122813841377, 0.01279394259730876, -0.20020095814610314, 0.010300622469333153, -0.07561457244154077, 0.164123106688332, -0.05625118011821406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007436414627796874, -0.033494046310523794, 0.007986750863223264]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.266128604002413, 0.0, 0.0, 0.0, 0.1768508032296661, 0.04463468611825146, 0.4363179970572665, -0.5209800964646494, 1.3225446050569358, -1.2774429898173811, -1.9698152212577897, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1372473132051102, -0.16697384534161874, 0.3361711617002469]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.786175061728433e-08, 0.0, 0.0, 0.0, -0.016655601410686907, 0.005706038909611823, -0.1877595775449645, 0.009715732318836346, -0.08195702125166435, 0.17727233303363488, -0.06883705253752985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00905036271583243, -0.028350783883107807, 0.00494394135401542]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286053185456, 0.0, 0.0, 0.0, 0.17591842394550922, 0.04471604395853678, 0.4274135675017475, -0.5205081719906879, 1.3182061822800817, -1.2680744728827371, -1.973787008982511, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1367214752784514, -0.16820517706446855, 0.33630214608133097]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6322651529538716e-08, 0.0, 0.0, 0.0, -0.018647585683137277, 0.0016271568057064324, -0.17808859111037864, 0.009438489479230776, -0.08676845553708162, 0.18737033869288172, -0.07943575449442451, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0105167585331765, -0.02462663445699628, 0.002619687621680676]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612860718853354, 0.0, 0.0, 0.0, 0.1749140854866592, 0.044518445524972916, 0.41887621293119015, -0.5201561751700677, 1.3137429876349935, -1.2582710322900612, -1.9779267781241203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1361555565014407, -0.16929291248663794, 0.3363502301535836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.739975863345121e-08, 0.0, 0.0, 0.0, -0.020086769176999978, -0.003951968671277293, -0.17074709141114747, 0.007039936412403962, -0.08926389290176222, 0.196068811853518, -0.08279538283218885, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011318375540214407, -0.021754708443387616, 0.0009616814450528837]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286077881597, 0.0, 0.0, 0.0, 0.17387796836455283, 0.04372115440864493, 0.41062272117872356, -0.5201836646418213, 1.3093275449228, -1.248041564367296, -1.9815293325154038, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1356156377746671, -0.17024985268907683, 0.33634921107113763]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1992523293527261e-08, 0.0, 0.0, 0.0, -0.020722342442127686, -0.015945822326559795, -0.16506983504933223, -0.0005497894350710826, -0.08830885424387074, 0.2045893584553037, -0.07205108782566824, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010798374535474012, -0.019138804048777897, -2.038164891970235e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612860780298714, 0.0, 0.0, 0.0, 0.17282589241290908, 0.04225619217773744, 0.4025972909436918, -0.5206411111114311, 1.3050755226590165, -1.237304222555455, -1.9844255602830192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1351144721930122, -0.17110868144739091, 0.3363163793279702]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.965487644663138e-10, 0.0, 0.0, 0.0, -0.021041519032874847, -0.02929924461814969, -0.16050860470063547, -0.00914892939219471, -0.08504044527566909, 0.2147468362368229, -0.057924555352310246, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010023311633097765, -0.017176575166281856, -0.0006566348633484282]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.266128607790855, 0.0, 0.0, 0.0, 0.17175049861533023, 0.04032392821659583, 0.3947669753271486, -0.5213655568196836, 1.3010477415752089, -1.2258739437644794, -1.987027912757261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1346020975306035, -0.171929322021282, 0.33625187890946434]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.426427501607317e-10, 0.0, 0.0, 0.0, -0.021507875951576966, -0.03864527922283224, -0.1566063123308639, -0.01448891416504988, -0.08055562167615082, 0.22860557581950927, -0.05204704948483499, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.010247493248173905, -0.016412811477821507, -0.001290008370117655]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286077952793, 0.0, 0.0, 0.0, 0.17061837293643486, 0.038447805010262646, 0.3871119337049026, -0.5219443403648791, 1.297232568552834, -1.213453041492427, -1.9904584627217712, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.13394874518036, -0.1728093116149613, 0.3361361561525302]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.848638916235128e-11, 0.0, 0.0, 0.0, -0.022642513577907114, -0.037522464126663546, -0.15310083244492018, -0.01157567090391079, -0.07630346044749525, 0.24841804544104823, -0.06861099929020445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.013067047004866834, -0.017599791873585933, -0.002314455138682981]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286078520693, 0.0, 0.0, 0.0, 0.16939237802655835, 0.03720233704577738, 0.37962643724791795, -0.5219177113987072, 1.2936216353990153, -1.1996250171017186, -1.99607636000695, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1329870857396735, -0.17386327534029775, 0.33593985776928476]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1358007199441248e-09, 0.0, 0.0, 0.0, -0.024519898197530234, -0.02490935928970535, -0.14970992913969314, 0.0005325793234389267, -0.07221866307637526, 0.2765604878141655, -0.11235794570357513, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.019233188813730803, -0.021079274506729088, -0.003925967664908161]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286081079845, 0.0, 0.0, 0.0, 0.1680186980670547, 0.03733385639633423, 0.37229647792738235, -0.5206981247985758, 1.2901486185877802, -1.1838958395047665, -2.005655615942108, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1314959989311235, -0.17523005569775693, 0.33562079509601467]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.118304105185253e-09, 0.0, 0.0, 0.0, -0.027473599190073028, 0.0026303870111370406, -0.14659918641071232, 0.024391732002629663, -0.06946033622470259, 0.3145835519390442, -0.19158511870315675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02982173617100067, -0.027335607149183525, -0.006381253465401308]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2661286081464471, 0.0, 0.0, 0.0, 0.16628230192854246, 0.04129536067804891, 0.36492397029282325, -0.5165084411754213, 1.2859841396915148, -1.1661804119108894, -2.0229462223109658, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1289789581347347, -0.1771620896137992, 0.33507599924716064]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.692524832600097e-10, 0.0, 0.0, 0.0, -0.03472792277024456, 0.07923008563429368, -0.14745015269118245, 0.08379367246309062, -0.0832895779253093, 0.3543085518775436, -0.3458121273771545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0503408159277777, -0.038640678320845265, -0.010895916977080559]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26612860768593327, 0.0, 0.0, 0.0, 0.16365280500896318, 0.04533685135836222, 0.3595579026970348, -0.5130986575639089, 1.2848781879911668, -1.1481307430884045, -2.044198179279633, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.125821176163139, -0.17886396640165067, 0.3349304695454913]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.21027691532921e-09, 0.0, 0.0, 0.0, -0.05258993839158542, 0.08082981360626615, -0.10732135191576848, 0.06819567223024758, -0.022119034006960615, 0.3609933764496965, -0.42503913937334514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06315563943191577, -0.03403753575702956, -0.002910594033386397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26547865544341726, 0.0, 0.0, 0.0, 0.15861729965043544, 0.04570832843746334, 0.35259719883503804, -0.5142187739638918, 1.2905807634851816, -1.1298557980605355, -2.0656614868481715, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1224083608714128, -0.17954334119525345, 0.3358092059897029]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044850320635, 0.0, 0.0, 0.0, -0.10071010717055476, 0.007429541582022456, -0.1392140772399357, -0.022402327999658717, 0.11405150988029539, 0.365498900557378, -0.42926615137076707, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0682563058345209, -0.013587495872055553, 0.017574728884230457]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2648287032767418, 0.0, 0.0, 0.0, 0.1513590882692843, 0.03938610560316109, 0.3415854420284019, -0.5236187903431017, 1.306582907850095, -1.1089006097417342, -2.0835861450406337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1191521733268013, -0.17849736723232482, 0.33785551515914375]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043333508736, 0.0, 0.0, 0.0, -0.14516422762302303, -0.1264444566860451, -0.22023513613272222, -0.188000327584196, 0.3200428872982689, 0.4191037663760234, -0.3584931638492422, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06512375089223192, 0.020919479258572685, 0.04092618338881697]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647584208969125, 0.0, 0.0, 0.0, 0.14372857928124702, 0.030120160017861664, 0.3302726277614276, -0.5375487148245781, 1.3306442744066598, -1.0863884010708869, -2.098092551201705, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1159982748752775, -0.17640636396652165, 0.34044439969064455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014056475965857351, 0.0, 0.0, 0.0, -0.15261017976074553, -0.18531891170598852, -0.22625628533948658, -0.2785984896295293, 0.48122733113129545, 0.45024417341694645, -0.2901281232214308, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06307796903047444, 0.041820065316063235, 0.05177769063001621]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647639705114251, 0.0, 0.0, 0.0, 0.13679217187810522, 0.02166045816364011, 0.3224087529871493, -0.5522585553625589, 1.3590149059256786, -1.0660691565381444, -2.1129293022972093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1129573181571875, -0.173927544331552, 0.34295086765248955]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011099229025160386, 0.0, 0.0, 0.0, -0.13872814806283626, -0.16919403708443104, -0.15727749548556508, -0.2941968107596152, 0.5674126303803757, 0.4063848906548504, -0.29673502191008966, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06081913436180128, 0.049576392699392874, 0.050129359236900393]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476629078783115, 0.0, 0.0, 0.0, 0.13088688378496335, 0.017089205881265043, 0.3192179508409571, -0.5639983153139854, 1.3879448027884924, -1.0516927199415205, -2.1273183575200676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.110349980893241, -0.17160775318006863, 0.3450604273843706]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.640552812165432e-05, 0.0, 0.0, 0.0, -0.11810576186283715, -0.09142504564750134, -0.0638160429238442, -0.23479519902853005, 0.5785979372562755, 0.2875287319324791, -0.28778110445716376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05214674527892915, 0.04639582302966746, 0.04219119463762132]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664683698033, 0.0, 0.0, 0.0, 0.12618364116341532, 0.01548477344034789, 0.3197168631826913, -0.5721343516816407, 1.414002076597127, -1.0424173552289444, -2.1402732799799202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1081752496622137, -0.169715780069158, 0.34671234185629807]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5516394427910082e-06, 0.0, 0.0, 0.0, -0.09406485243096056, -0.03208864881834307, 0.009978246834684762, -0.16272072735310697, 0.521145476172694, 0.18550729425152085, -0.2590984491970518, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.043494624620549746, 0.037839462218212896, 0.03303828943854946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643894308044, 0.0, 0.0, 0.0, 0.12268279512419489, 0.015488266670990337, 0.3228637195581985, -0.5774126331129201, 1.4366172759536346, -1.0363980085168762, -2.1514487671705305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.106319843092135, -0.16833337535259965, 0.34794307740963537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.88534457104509e-07, 0.0, 0.0, 0.0, -0.07001692078440862, 6.98646128489272e-05, 0.06293712751014367, -0.10556562862558684, 0.4523039871301521, 0.12038693424136139, -0.22350974381220107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03710813140157346, 0.027648094331166773, 0.02461471106674642]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643101333963, 0.0, 0.0, 0.0, 0.12025853422020397, 0.016241720084833915, 0.32788644649123194, -0.5805905067965282, 1.4562272034059378, -1.032153503687627, -2.1611514446943945, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.104648512368432, -0.16745348880586808, 0.348816358455733]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.5859481650144143e-07, 0.0, 0.0, 0.0, -0.04848521807981843, 0.015069068276871548, 0.1004545386606694, -0.06355747367216305, 0.39219854904606116, 0.08489009658498584, -0.1940535504772783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0334266144740623, 0.01759773093463136, 0.017465620921952918]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664306617872, 0.0, 0.0, 0.0, 0.11843143505295134, 0.02043383575239546, 0.3331696769770664, -0.5797033841049434, 1.4717637952572689, -1.0285313337447441, -2.17313131025325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1025834062396578, -0.1673118844682218, 0.3491999883529489]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.03104925380982e-09, 0.0, 0.0, 0.0, -0.03654198334505256, 0.08384231335123088, 0.10566460971668894, 0.017742453831696814, 0.3107318370266204, 0.07244339885765697, -0.23959731117711208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.04130212257548332, 0.002832086752925997, 0.0076725979443180835]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643180934617, 0.0, 0.0, 0.0, 0.11714304912862554, 0.02671197423583858, 0.33892061010513, -0.5760210819726153, 1.4848589641414316, -1.0245957784566169, -2.189189843862316, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0999542849324677, -0.1678682034662479, 0.3492129685258999]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.295117951156564e-08, 0.0, 0.0, 0.0, -0.02576771848651587, 0.12556276966886243, 0.1150186625612721, 0.073646042646562, 0.26190337768325467, 0.07871110576254355, -0.3211706721813176, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05258242614380167, -0.011126379960522226, 0.0002596034590194706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643199085426, 0.0, 0.0, 0.0, 0.116577213936638, 0.03156965912597852, 0.3463836163530932, -0.5723083940038088, 1.4989070368358248, -1.0180386407133397, -2.2055773209814737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0971585103480541, -0.16891545944690242, 0.3490322686819484]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.6301615963257087e-09, 0.0, 0.0, 0.0, -0.011316703839750756, 0.09715369780279869, 0.14926012495926358, 0.07425375937612802, 0.2809614538878657, 0.1311427548655441, -0.3277495423831592, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05591549168827386, -0.02094511961309063, -0.0036139968790289668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643178367376, 0.0, 0.0, 0.0, 0.1162742758385884, 0.03334246211453408, 0.35367857866147, -0.5700026507674979, 1.5133848724612957, -1.0068698998265686, -2.219296539998739, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0945471565788314, -0.17025346765464594, 0.34877300953169954]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.143609581813442e-09, 0.0, 0.0, 0.0, -0.006058761960991877, 0.03545605977111122, 0.14589924616753522, 0.046114864726218396, 0.2895567125094163, 0.22337481773542373, -0.27438438034530266, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.05222707538445559, -0.026760164154870324, -0.005185183004978082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 14\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664317347447, 0.0, 0.0, 0.0, 0.11527769354390283, 0.0314629381793694, 0.3570555241855653, -0.5702525929686189, 1.524542498087137, -0.991220411590491, -2.227902718851112, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0926232060732566, -0.17143679046359547, 0.3486075279595993]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.785813747885674e-10, 0.0, 0.0, 0.0, -0.01993164589371154, -0.03759047870329362, 0.06753891048190544, -0.004998844022419971, 0.2231525125168239, 0.31298976472155127, -0.17212357704745274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.03847901011149427, -0.023666456178990602, -0.003309631442004097]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316084939, 0.0, 0.0, 0.0, 0.11378679943433333, 0.027597220186734325, 0.356256455532495, -0.5720686936318743, 1.531278333759708, -0.9742282071442913, -2.232513891847721, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0914710831855785, -0.1723175627042114, 0.3485383525202129]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.5250156241231264e-09, 0.0, 0.0, 0.0, -0.02981788219138992, -0.07731435985270142, -0.015981373061405152, -0.03632201326510961, 0.13471671345142006, 0.3398440889239949, -0.09222345993218652, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02304245775356016, -0.0176154448123184, -0.0013835087877277063]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264766431594108, 0.0, 0.0, 0.0, 0.11299112355251571, 0.0254941426036934, 0.3550313721956987, -0.5727816188771538, 1.5373423783235054, -0.9596432852641452, -2.23544868442162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0904756681098446, -0.17303305400669133, 0.3483969850357224]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8771777683904587e-10, 0.0, 0.0, 0.0, -0.015913517636352216, -0.04206155166081847, -0.024501666735926908, -0.014258504905591919, 0.12128089127594698, 0.29169843760292, -0.05869585147798742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01990830151467944, -0.014309826049598719, -0.0028273496898103085]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664315983433, 0.0, 0.0, 0.0, 0.11291865359027885, 0.026167173886651535, 0.35713020919360755, -0.5722681122102595, 1.5441031183848033, -0.951215640475407, -2.2373747216453372, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0894594438368936, -0.17349439125857263, 0.3482204851176128]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.470578986111211e-11, 0.0, 0.0, 0.0, -0.0014493992447372414, 0.013460625659162659, 0.041976739958177633, 0.010270133337886771, 0.13521480122595625, 0.16855289577476507, -0.038520744474341354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.02032448545902065, -0.009226745037626138, -0.0035299983621923836]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664317389788, 0.0, 0.0, 0.0, 0.11324448775844541, 0.029368723826725732, 0.36132295522004887, -0.570794754547609, 1.5493744380535333, -0.9514922017230499, -2.2384344472073847, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.088654410780289, -0.1735718219474068, 0.34807898566217643]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.812709705718739e-09, 0.0, 0.0, 0.0, 0.006516683363331197, 0.06403099880148391, 0.08385492052882589, 0.029467153253010036, 0.10542639337459983, -0.00553122495285982, -0.021194511240953052, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01610066113209596, -0.0015486137766833287, -0.002829989108727092]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643172315384, 0.0, 0.0, 0.0, 0.1131380005788106, 0.03141015375478614, 0.3638596999125084, -0.5706569731349215, 1.549407444413861, -0.9567229910988146, -2.2355636355137825, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0886781869779254, -0.17313521085545588, 0.3481453620075015]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.1649906240734936e-10, 0.0, 0.0, 0.0, -0.0021297435926962913, 0.04082859856120814, 0.05073489384919036, 0.002755628253749653, 0.000660127206555769, -0.10461578751529363, 0.0574162338720494, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004755239527300171, 0.008732221839018263, 0.0013275269065020417]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316844906, 0.0, 0.0, 0.0, 0.11233490444658752, 0.030908924454804153, 0.3610029716914766, -0.5716463007756346, 1.5451614274280667, -0.9631580421880943, -2.230626308135342, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0895154754916776, -0.17251786429133562, 0.3483622577391764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.732646543988025e-10, 0.0, 0.0, 0.0, -0.01606192264446163, -0.010024585999639735, -0.05713456442063604, -0.01978655281426186, -0.0849203397158846, -0.12870102178559306, 0.09874654756880347, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016745770275043915, 0.012346931282405396, 0.004337914633497819]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316718823, 0.0, 0.0, 0.0, 0.11116961238076889, 0.027814293955794173, 0.3548633579739013, -0.5731844010115555, 1.5403854714987177, -0.9670473668165558, -2.225698641901949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0906515710796603, -0.1721328493494456, 0.3486037054106216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.52166204574048e-10, 0.0, 0.0, 0.0, -0.023305841316372478, -0.0618926099801996, -0.12279227435150651, -0.03076200471841811, -0.09551911858698153, -0.07778649256922998, 0.0985533246678646, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022721911759653123, 0.007700298837800282, 0.004828953428904187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664316841142, 0.0, 0.0, 0.0, 0.11117165016237776, 0.025324918112385665, 0.34919085416673257, -0.5723635339346635, 1.5388295719441993, -0.968840333240735, -2.2245306316726055, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915909367430834, -0.17244641191884746, 0.3484980501005215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4463783639043815e-10, 0.0, 0.0, 0.0, 4.075563217735209e-05, -0.04978751686817012, -0.11345007614337416, 0.016417341537839084, -0.03111799109036796, -0.03585932848358506, 0.023360204586867828, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018787313268462724, -0.006271251388037686, -0.0021131062020017036]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643168771546, 0.0, 0.0, 0.0, 0.11201724161563884, 0.02415343452395005, 0.34773544327052686, -0.5697582607626464, 1.5438717307767065, -0.969812063350708, -2.227247431013922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091645544246025, -0.17339510328982402, 0.3481462012440518]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.202568411930899e-11, 0.0, 0.0, 0.0, 0.01691182906522159, -0.023429671768712246, -0.02910821792411418, 0.052105463440344904, 0.10084317665014204, -0.01943460219945926, -0.054335986826331076, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001092150058831014, -0.01897382741953133, -0.007036977129393326]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643250153836, 0.0, 0.0, 0.0, 0.1132721992116631, 0.024058121153961744, 0.3501844609216766, -0.5665672772502849, 1.5522560841924036, -0.9718234442422322, -2.2311342746699547, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0911969580321144, -0.17450191787748523, 0.34772830155218526]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6276457965752105e-08, 0.0, 0.0, 0.0, 0.025099151920485063, -0.0019062673997661123, 0.04898035302299533, 0.06381967024722891, 0.16768706831394253, -0.04022761783048395, -0.07773687312064889, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008971724278209251, -0.02213629175322423, -0.008357993837330758]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664326095421, 0.0, 0.0, 0.0, 0.11445451903214579, 0.024507249900566488, 0.35370485870085017, -0.5636993872708438, 1.5603106262097637, -0.9750135662098344, -2.2343102480805372, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0907285157633746, -0.17541667469736083, 0.3473655591636725]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.1600742432189773e-09, 0.0, 0.0, 0.0, 0.023646396409653873, 0.008982574932094894, 0.07040795558347131, 0.057357799588821895, 0.16109084034720442, -0.06380243935204247, -0.06351946821164736, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009368845374796899, -0.018295136397511774, -0.00725484777025548]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643100308517, 0.0, 0.0, 0.0, 0.11458036925662182, 0.023568559564922643, 0.3545477886589088, -0.5629429394625612, 1.5642864534576193, -0.975654170043454, -2.2359529447873876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090803251414037, -0.17587178312508353, 0.3471734912259824]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.212913869202863e-08, 0.0, 0.0, 0.0, 0.002517004489520639, -0.018773806712876907, 0.016858599161172258, 0.015128956165651818, 0.07951654495711415, -0.012812076672392848, -0.03285393413700806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014947130132468016, -0.00910216855445421, -0.0038413587538018044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664305158545, 0.0, 0.0, 0.0, 0.1139299561430751, 0.021708015350115187, 0.35099867355436914, -0.5635788327219675, 1.5634141876817278, -0.9734786486704348, -2.236819993174125, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912796643580107, -0.17600537504634886, 0.3471020437186431]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.74461261590733e-09, 0.0, 0.0, 0.0, -0.01300826227093424, -0.037210884296149105, -0.07098230209079326, -0.012717865188124598, -0.01744531551783067, 0.043510427460384436, -0.01734096773474526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009528258879476517, -0.0026718384253064235, -0.0014289501467858482]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643049415943, 0.0, 0.0, 0.0, 0.11351121426930624, 0.02030305170591325, 0.346807480914311, -0.5639466852879884, 1.561443802071491, -0.9721315611981735, -2.236829857706255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0916525853239254, -0.17610880826157563, 0.3470585035099417]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.3390187051915983e-10, 0.0, 0.0, 0.0, -0.008374837475377353, -0.028099272884038733, -0.0838238528011629, -0.007357051320417162, -0.039407712204739764, 0.026941749445225534, -0.00019729064260128396, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007458419318294714, -0.0020686643045355613, -0.0008708041740279629]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643099283725, 0.0, 0.0, 0.0, 0.11384138157389646, 0.020350251236577986, 0.3457236255359675, -0.5629476134615214, 1.5621244857101886, -0.9738760046518786, -2.236542246252096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915795029734605, -0.17637459813567227, 0.34697574126655617]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.973556358390658e-09, 0.0, 0.0, 0.0, 0.00660334609180431, 0.0009439906132947054, -0.021677107566870114, 0.019981436529340316, 0.013613672773953825, -0.034888869074103185, 0.00575222908318224, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014616470092957553, -0.005315797481932686, -0.0016552448677107934]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664311102472, 0.0, 0.0, 0.0, 0.11467646501230651, 0.02139696714924933, 0.3486361645455943, -0.5610807810741122, 1.566051700203503, -0.9777340575348878, -2.2361940335188546, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0911938479043735, -0.17674195518873392, 0.34686556480455893]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.348199823777098e-09, 0.0, 0.0, 0.0, 0.01670166876820084, 0.020934318253426877, 0.058250780192535566, 0.03733664774818482, 0.07854428986628981, -0.07716105766018339, 0.006964254664826009, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007713101381740762, -0.007347141061232829, -0.002203529239944765]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.264766431107414, 0.0, 0.0, 0.0, 0.11506492907744939, 0.021530381442416792, 0.3517951149061298, -0.5601400818383483, 1.5694754664230979, -0.9799558284021133, -2.2358034551629618, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0910461259403064, -0.1769845012960689, 0.3468060587781453]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.66649237253457e-11, 0.0, 0.0, 0.0, 0.007769281302857646, 0.0026682858633492006, 0.06317900721070913, 0.01881398471527897, 0.06847532439189696, -0.04443541734450738, 0.007811567117857081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0029544392813405217, -0.004850922146699959, -0.001190120528273116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664309854784, 0.0, 0.0, 0.0, 0.1147442272670446, 0.020163529216010792, 0.35145201789756975, -0.5605863382470238, 1.568834999834427, -0.9779139570558685, -2.235455632636704, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912582431379232, -0.17707551535297095, 0.3468094533529982]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.438711943511148e-09, 0.0, 0.0, 0.0, -0.006414036208095768, -0.027337044528119976, -0.006861940171200953, -0.00892512817350979, -0.01280933177341713, 0.04083742692489569, 0.006956450525153016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004242343952335669, -0.0018202811380409682, 6.789149705782203e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643095956204, 0.0, 0.0, 0.0, 0.11427413393156692, 0.018173723836868272, 0.3497546179721089, -0.5615948958528232, 1.5669854437529516, -0.9739417135822606, -2.235173547805247, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915522614461362, -0.17713099857723627, 0.34683257617917307]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.183273236773194e-10, 0.0, 0.0, 0.0, -0.009401866709553598, -0.03979610758285038, -0.03394799850921682, -0.020171152115987852, -0.03699112162950849, 0.07944486947215787, 0.005641696629135675, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00588036616425801, -0.001109664485306548, 0.00046245652349833304]\n accelerations: []\n effort: []\n time_from_start: \n secs: 15\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664309762652, 0.0, 0.0, 0.0, 0.1145566185984655, 0.017509666579236593, 0.3504528905361901, -0.5615166227001228, 1.567676762933102, -0.9717890422235987, -2.2349554898279456, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0914172599690992, -0.1773312504451124, 0.3467967054784157]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.340625236588448e-10, 0.0, 0.0, 0.0, 0.00564969333797144, -0.013281145152633605, 0.013965451281624706, 0.001565463054006417, 0.013826383603012304, 0.04305342717323527, 0.004361159546027461, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002700029540739488, -0.0040050373575222405, -0.0007174140151477491]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664310346551, 0.0, 0.0, 0.0, 0.11541078709966017, 0.018160556628257805, 0.3547706508880259, -0.5604984059487357, 1.5713200407791421, -0.9729573057215175, -2.234762542889264, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0909833556679853, -0.17759366418276812, 0.34672200560776456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.167798485713038e-09, 0.0, 0.0, 0.0, 0.0170833700238934, 0.013017800980424227, 0.08635520703671531, 0.02036433502774195, 0.07286555692080171, -0.023365269958375366, 0.0038589387736306918, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00867808602227708, -0.005248274753114821, -0.0014939974130222802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664310381693, 0.0, 0.0, 0.0, 0.11599846791051192, 0.0187843454282189, 0.3589579205539048, -0.5598435905774848, 1.5741653219430067, -0.974188485413714, -2.2345140334742064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090709312241996, -0.1777219212204129, 0.34667602895435884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.028473286281447e-11, 0.0, 0.0, 0.0, 0.011753616217034994, 0.012475775999221846, 0.08374539331757799, 0.01309630742501846, 0.05690562327729225, -0.02462359384392793, 0.004970188301154795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0054808685197868575, -0.0025651407528952683, -0.0009195330681145696]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664309467918, 0.0, 0.0, 0.0, 0.11576679578965395, 0.018721201460101967, 0.35926513129604076, -0.5600647179329961, 1.5724649129236763, -0.972494082672975, -2.2351225623556337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0907803111973564, -0.177676031638525, 0.34667884358644474]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.8275503812316527e-09, 0.0, 0.0, 0.0, -0.004633442417159501, -0.0012628793623386536, 0.006144214842719625, -0.00442254711022487, -0.034008180386607426, 0.033888054814779564, -0.01217057762854782, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014199791072080897, 0.0009177916377579306, 5.629264171799471e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664308872581, 0.0, 0.0, 0.0, 0.11506866228233743, 0.018053558114696742, 0.356232527925416, -0.5609244622609034, 1.5677816623117127, -0.9689480506687775, -2.235940683224265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091083981761194, -0.17752209248416453, 0.34671678048290006]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1906745023300447e-09, 0.0, 0.0, 0.0, -0.013962670146330198, -0.01335286690810448, -0.06065206741249586, -0.01719488655814779, -0.09366501223927319, 0.07092064008394876, -0.016362417372625334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006073411276752258, 0.003078783087209056, 0.0007587379291066578]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 199999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664308917629, 0.0, 0.0, 0.0, 0.11485511729238716, 0.017931706509770322, 0.353610084199067, -0.5612026685594074, 1.5638655451152779, -0.967299732012413, -2.2357590380109866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912231957930703, -0.17743325405106408, 0.34673634256929214]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.009600635212578e-11, 0.0, 0.0, 0.0, -0.004270899799005339, -0.002437032098528422, -0.05244887452697968, -0.005564125970079589, -0.07832234392869553, 0.03296637312728962, 0.0036329042655682577, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0027842806375245792, 0.0017767686620091404, 0.0003912417278418097]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643089431073, 0.0, 0.0, 0.0, 0.11535827976153545, 0.018999049877875603, 0.3551477308113616, -0.560382911718757, 1.5641707192651413, -0.9693825822611004, -2.235258209301683, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0910316214632758, -0.1774680817597735, 0.34671070268202514]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.0957516246021646e-11, 0.0, 0.0, 0.0, 0.010063249382965881, 0.021346867362105608, 0.030752932245892213, 0.016395136813007544, 0.006103482997267873, -0.041657004973748246, 0.010016574186070774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003831486595889918, -0.0006965541741881628, -0.0005127977453404362]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664308927253, 0.0, 0.0, 0.0, 0.11590722482611304, 0.020120441676030287, 0.35755532971776466, -0.559512339986934, 1.5655646892786426, -0.9723358176950191, -2.2342308562155666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090844821515898, -0.1774948844662164, 0.3466880986955456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.17095045301625e-11, 0.0, 0.0, 0.0, 0.010978901291551707, 0.02242783596309367, 0.048151978128061546, 0.01741143463646015, 0.027879400270027433, -0.05906470867837435, 0.020547061722332317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0037359989475602576, -0.0005360541288577792, -0.0004520797295898358]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664307226811, 0.0, 0.0, 0.0, 0.11577413019321742, 0.020221694597589067, 0.35708497993453703, -0.559559295831013, 1.5643043881218945, -0.9725795765366342, -2.23317217155742, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0909676680126992, -0.17740693715444716, 0.34670868420814804]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.4008839616760352e-09, 0.0, 0.0, 0.0, -0.0026618926579125325, 0.0020250584311756192, -0.009406995664553067, -0.0009391168815819188, -0.025206023134960048, -0.004875176832301015, 0.021173693162934493, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024569299360261533, 0.0017589462353845434, 0.0004117102520489837]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643030597097, 0.0, 0.0, 0.0, 0.11518304029054811, 0.019599761370579498, 0.3540036170771198, -0.560225239245386, 1.56093423401713, -0.9707353792638763, -2.2322573536799926, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912902782809368, -0.17725329032808565, 0.34675639542599523]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.334201746103628e-09, 0.0, 0.0, 0.0, -0.011821798053386129, -0.012438664540191408, -0.061627257148344446, -0.01331886828746065, -0.06740308209529246, 0.036883945455158273, 0.018296357548550815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00645220536475301, 0.00307293652723054, 0.0009542243569432922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 449999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643025727264, 0.0, 0.0, 0.0, 0.11491334003232198, 0.019418422949829935, 0.3520612054242456, -0.5604450725012409, 1.5592040742383544, -0.9702816985637978, -2.231404250576391, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0914616547683167, -0.17716597262138345, 0.3467828372094147]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.73966741974502e-10, 0.0, 0.0, 0.0, -0.005394005164522714, -0.003626768414991292, -0.03884823305748317, -0.00439666511709696, -0.03460319557551171, 0.009073614001571154, 0.017062062072031474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0034275297475966616, 0.0017463541340441092, 0.0005288356683900361]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664302830495, 0.0, 0.0, 0.0, 0.11523098476711803, 0.02005383722768126, 0.35364925518427875, -0.5599316163048906, 1.5605976936933394, -0.9723401943607346, -2.2306974601120473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0913749815412719, -0.17717255644147348, 0.34677439067363364]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.1553741489976e-10, 0.0, 0.0, 0.0, 0.006352894695920986, 0.012708285557026513, 0.03176099520066221, 0.010269123927004532, 0.027872389099700162, -0.0411699159387365, 0.014135809286875516, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0017334645408973858, -0.00013167640180042947, -0.00016893071562217423]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643028057684, 0.0, 0.0, 0.0, 0.11551675927557364, 0.02061162496318783, 0.3552602385282862, -0.5594709280454054, 1.5620812612479051, -0.9742804084550046, -2.2300050352697567, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0912927545016766, -0.17718254135595407, 0.3467660468594465]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.945354146376601e-11, 0.0, 0.0, 0.0, 0.005715490169112327, 0.011155754710131418, 0.03221966688014856, 0.00921376518970403, 0.029671351091312036, -0.03880428188540073, 0.013848496845809181, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001644540791906005, -0.0001996982896116515, -0.0001668762837422621]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.26476643013503304, 0.0, 0.0, 0.0, 0.11529102842767731, 0.020483383729382607, 0.35400999178978443, -0.5595782696520546, 1.5612570586669148, -0.9740195086475434, -2.229418883587127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0913974896669885, -0.17713997337586745, 0.3467805173526685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.9108757849844204e-09, 0.0, 0.0, 0.0, -0.0045146169579267145, -0.002564824676104492, -0.0250049347700357, -0.0021468321329834276, -0.016484051619805703, 0.005217996149224476, 0.011723033652596955, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020947033062384927, 0.000851359601732346, 0.00028940986444063633]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664301155837, 0.0, 0.0, 0.0, 0.11485851486649702, 0.020067670516678727, 0.3516324465586707, -0.5599199235732419, 1.5594998543821916, -0.9727952747290967, -2.2289307583069338, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0915794143987825, -0.17707677889586718, 0.34680445938895255]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.889865402505619e-10, 0.0, 0.0, 0.0, -0.008650271223605933, -0.008314264254077584, -0.04755090462227426, -0.00683307842374694, -0.03514408569446362, 0.024484678368933577, 0.009762505603865086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003638494635879916, 0.0012638896000056546, 0.00047884072568107487]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 699999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2647664307268475, 0.0, 0.0, 0.0, 0.11475305183805688, 0.0200654512616469, 0.3511903589653456, -0.5599129043790838, 1.5592776919504603, -0.9728423362259102, -2.2285406738398224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.091635622223444, -0.17705293358484722, 0.3468125652375084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 16\n nsecs: 750000000" - }, - "execution_count": 25, - "metadata": {}, - "output_type": "execute_result" - } - ], + "execution_count": 13, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -436,42 +362,38 @@ "world_cylinder_center_feature.point = Point(0, 0, 0)\n", "\n", "# define the constraints\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cylinder_center_feature,\n", - " robot_feature=robot_point_feature,\n", - " lower_limit=0.03,\n", - " upper_limit=0.03)\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='HeightFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cylinder_center_feature,\n", - " robot_feature=robot_point_feature,\n", - " lower_limit=-0.05,\n", - " upper_limit=0.05)\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='PointingFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cylinder_center_feature,\n", - " robot_feature=robot_pointing_feature)\n", + "gs.motion_goals.add_distance(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=0.03,\n", + " upper_limit=0.03)\n", + "gs.motion_goals.add_height(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=-0.05,\n", + " upper_limit=0.05)\n", + "gs.motion_goals.add_pointing(root_link='map',\n", + " tip_link=gripper_link,\n", + " goal_point=world_cylinder_center_feature,\n", + " pointing_axis=robot_pointing_feature)\n", "# EXCERCISE SOLUTION:\n", - "robot_gripper_z_axis_feature = Vector3Stamped()\n", - "robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", - "robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "\n", - "world_cyl_z_axis_feature = Vector3Stamped()\n", - "world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", - "world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='AlignFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cyl_z_axis_feature,\n", - " robot_feature=robot_gripper_z_axis_feature)\n", + "# robot_gripper_z_axis_feature = Vector3Stamped()\n", + "# robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", + "# robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "#\n", + "# world_cyl_z_axis_feature = Vector3Stamped()\n", + "# world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", + "# world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "#\n", + "# gs.motion_goals.add_align_planes(root_link='map',\n", + "# tip_link=gripper_link,\n", + "# goal_normal=world_cyl_z_axis_feature,\n", + "# tip_normal=robot_gripper_z_axis_feature)\n", "\n", "gs.add_default_end_motion_conditions()\n", - "gs.execute()\n", + "assert gs.execute().error.code == GiskardError.SUCCESS\n", "\n", "# EXERCISE:\n", "# 1. Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.\n", @@ -498,17 +420,8 @@ }, { "cell_type": "code", - "execution_count": 20, - "outputs": [ - { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, -0.15, 0.0, -0.10001, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2006499522418266, 0.0, 0.00013138406399284356, 0.0, -0.0018911454110190373, 0.003467997502063863, 0.002261559670703244, -0.15000000000558167, 9.394081548625307e-05, -0.1000100000032556, -0.002153130433649211, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.019017857734377e-12, 0.0, 0.0, -0.1500592024683071, 0.0, -0.1000692024683071, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246093841233858, 0.0006251787189194379, 0.0006249999938137112]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044836531927, 0.0, 0.0026276812798569, 0.0, -0.037822908220380744, 0.06935995004127726, 0.045231193414064876, -1.1163372917477135e-10, 0.0018788163097250615, -6.511201788104837e-11, -0.04306260867298421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4038035715469994e-10, 0.0, 0.0, -0.0011840493661418627, 0.0, -0.0011840493661418627, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012492187682467714, 0.012503574378388756, 0.012499999876274225]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990446959206, 0.0, 0.0004934941405271855, 0.0, -0.005350422446676624, 0.009361262454469312, 0.006332831450702455, -0.1500000000508954, 0.00026247729174472435, -0.10001000003397474, -0.006102626025669795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3730638088655887e-11, 0.0, 0.0, -0.15020664513455953, 0.0, -0.10021664513455955, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.00249723430344827, 0.0015775437167409373, 0.00249999986996056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904455530908, 0.0, 0.007242201530686958, 0.0, -0.06918554071315174, 0.11786529904810897, 0.08142543559998422, -9.062747616995622e-10, 0.0033707295251694256, -6.143828286889566e-10, -0.07898991184041168, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.342324046184313e-10, 0.0, 0.0, -0.002948853325049055, 0.0, -0.002948853325049055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03745249838649769, 0.019047299956429987, 0.03749999752293697]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985671017934, 0.0, 0.0009829394491939064, 0.0, -0.009625451074185092, 0.0164101024713223, 0.011702223103185062, -0.15000000005946915, 0.0005080102959921151, -0.10001000003879015, -0.011484726567758976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9043136840312716e-11, 0.0, 0.0, -0.1503912226054937, 0.0, -0.10040122260549372, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.005930246007499822, 0.002350992783948762, 0.0058796256049771685]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044811745646, 0.0, 0.009788906173334395, 0.0, -0.08550057255016935, 0.14097680033705975, 0.10738783304965216, -1.7147478170045847e-10, 0.004910660084947813, -9.630832166644655e-11, -0.10764201084178363, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.062499750331366e-10, 0.0, 0.0, -0.00369154941868348, 0.0, -0.00369154941868348, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06866023408103104, 0.015468981344156495, 0.06759251470033216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980895180787, 0.0, 0.0015247125917483844, 0.0, -0.013684989558475105, 0.02387080971806118, 0.018452663010715478, -0.1500000000655235, 0.000893751167781702, -0.10001000004222109, -0.018528238686148626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2916338007399637e-11, 0.0, 0.0, -0.15058189005965322, 0.0, -0.10059189005965323, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010648935037852013, 0.0025713986057469182, 0.010142249711465132]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044832570441, 0.0, 0.010835462851089545, 0.0, -0.08119076968580023, 0.14921414493477758, 0.13500879815060832, -1.210867776366769e-10, 0.007714817435791737, -6.861884688315247e-11, -0.140870242367793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.746402334173857e-11, 0.0, 0.0, -0.0038133490831902387, 0.0, -0.0038133490831902387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09437378060704382, 0.004408116435963127, 0.08525248212975926]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976119520266, 0.0, 0.00205072747891782, 0.0, -0.016672511341103168, 0.03139955025506507, 0.02736721087723845, -0.15000000006708336, 0.0015372123151348443, -0.10001000004308903, -0.028156866764058104, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.569956530974065e-11, 0.0, 0.0, -0.15075750321751125, 0.0, -0.10076750321751125, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.01635039505753499, 0.002021498070780422, 0.014662872278838005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044867895668, 0.0, 0.010520297743388668, 0.0, -0.059750435652561246, 0.15057481074007778, 0.1782909573304594, -3.1197317276118474e-11, 0.012869222947062844, -1.7358919222223152e-11, -0.19257256155818953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.566454604682024e-11, 0.0, 0.0, -0.003512263157160443, 0.0, -0.003512263157160443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11402920039365956, -0.010998010699329923, 0.09041245134745743]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997134385485, 0.0, 0.0025408648649906415, 0.0, -0.018033083156050445, 0.03885291651019851, 0.03988804443326672, -0.15000000006876096, 0.002610648532880667, -0.10001000004402233, -0.041975238951710944, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.7685239490123808e-11, 0.0, 0.0, -0.15091338521862452, 0.0, -0.10092338521862454, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.022751113360734126, 0.0005604002153586066, 0.01895407434687648]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044866917026, 0.0, 0.00980274772145646, 0.0, -0.027211436298945547, 0.1490673251026688, 0.2504166711205653, -3.35520508135503e-11, 0.021468724354916452, -1.86658965237018e-11, -0.2763674437530568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.9713483607663136e-11, 0.0, 0.0, -0.0031176400222656746, 0.0, -0.0031176400222656746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12801436606398273, -0.029221957108436305, 0.08582404136076949]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966568164473, 0.0, 0.0029965907777055943, 0.0, -0.01734099759877982, 0.04606126888023213, 0.058002789644010865, -0.15000000007105113, 0.0043519333470906614, -0.10001000004529743, -0.06219227263093911, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.9095133475902258e-11, 0.0, 0.0, -0.1510532271255623, 0.0, -0.10106322712556233, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.029641037670814968, -0.001980554234652346, 0.022870813772015882]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861924228, 0.0, 0.009114518254299027, 0.0, 0.013841711145412446, 0.1441670474006725, 0.36229490421488286, -4.580346133623464e-11, 0.03482569628419989, -2.5502215580156844e-11, -0.40434067358456327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.8197879715569004e-11, 0.0, 0.0, -0.002796838138755713, 0.0, -0.002796838138755713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1377984862016168, -0.05081908900021905, 0.07833478850278802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961792498273, 0.0, 0.0034118890253128226, 0.0, -0.014443457215812451, 0.05249343132179201, 0.0831310908475063, -0.15000000007274986, 0.006470848965680013, -0.10001000004624182, -0.08956318615097353, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.0089871246348254e-11, 0.0, 0.0, -0.15117998940011299, 0.0, -0.101189989400113, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.03687803504716805, -0.005659221270354244, 0.026427564241316516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044866760167, 0.0, 0.008305964952144602, 0.0, 0.05795080765934738, 0.1286432488311975, 0.502566024069909, -3.397455259264848e-11, 0.04237831237178703, -1.8887686270923795e-11, -0.5474182704006882, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9894755408919886e-11, 0.0, 0.0, -0.0025352454910136054, 0.0, -0.0025352454910136054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14473994752706168, -0.07357334071403795, 0.07113500938601268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20584957016741257, 0.0, 0.003822800749548274, 0.0, -0.009589450287785935, 0.05778680297322593, 0.11466198197822292, -0.1500000000766933, 0.008336333026081978, -0.10001000004846573, -0.12317593973829957, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.0749430646133444e-11, 0.0, 0.0, -0.15130782365807424, 0.0, -0.10131782365807426, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.044363773981805035, -0.010311789755080687, 0.029687281644921303]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044848596453, 0.0, 0.008218234484709059, 0.0, 0.0970801385605303, 0.1058674330286784, 0.630617822614332, -7.886896624705964e-11, 0.0373096812080393, -4.447844539583911e-11, -0.672255071746521, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.3191187995703765e-11, 0.0, 0.0, -0.0025566851592250376, 0.0, -0.0025566851592250376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14971477869273975, -0.09305136969452885, 0.06519434807209575]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952240914754, 0.0, 0.004248608651217674, 0.0, -0.003205133026555734, 0.06178133828048554, 0.1516824378353661, -0.15000000008231962, 0.009773557694005897, -0.10001000005172546, -0.1620153776062251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.1081544416184297e-11, 0.0, 0.0, -0.15144544863438456, 0.0, -0.10145544863438456, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05204122702337631, -0.01574078511979557, 0.032715159305722996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044834699559, 0.0, 0.00851615803338803, 0.0, 0.127686345224604, 0.07989070614519228, 0.7404091171428636, -1.1252602139809881e-10, 0.028744493358478375, -6.519457231291811e-11, -0.7767887573585108, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.642275401017126e-12, 0.0, 0.0, -0.0027524995262060274, 0.0, -0.0027524995262060274, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15354906083142542, -0.10857990729429765, 0.06055755321603393]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2071494744950351, 0.0, 0.004843462187939546, 0.0, 0.004299473485592131, 0.06444830753945968, 0.1932887590046653, -0.15000000046769238, 0.01067892439265633, -0.10001000029102042, -0.2050869119704552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2182600888122174e-11, 0.0, 0.0, -0.15166501076302943, 0.0, -0.10167501076302944, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.059876341665892084, -0.02176118622344076, 0.035566103819730896]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999041717751068, 0.0, 0.01189707073443735, 0.0, 0.1500921302429573, 0.0533393851794828, 0.8321264233859839, -7.707454969155888e-09, 0.01810733397300869, -4.78589920034722e-09, -0.8614306872846019, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.779788705612392e-10, 0.0, 0.0, -0.0043912425728975905, 0.0, -0.0043912425728975905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15670229285031548, -0.12040802207290378, 0.057018890280158045]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2077994267376033, 0.0, 0.00546154849475136, 0.0, 0.01257838148326606, 0.06583025778954048, 0.23857381568612884, -0.1500000004713173, 0.011198482601646638, -0.10001000029305597, -0.25154413930604774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.613306950154479e-11, 0.0, 0.0, -0.1518945605480015, 0.0, -0.10190456054800148, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06784712627442557, -0.028207944594465757, 0.03828273752242274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904485136395, 0.0, 0.012361726136236298, 0.0, 0.16557815995347858, 0.027639005001615945, 0.9057011336292708, -7.249881089523998e-11, 0.010391164179806137, -4.0710942533207546e-11, -0.9291445467118509, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.2099062773154713e-10, 0.0, 0.0, -0.004590995699440854, 0.0, -0.004590995699440854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15941569217066984, -0.12893516742049993, 0.05433267405383695]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20844937897841428, 0.0, 0.006082240028599633, 0.0, 0.021383227025485313, 0.06599725415938462, 0.2868018606060743, -0.15000000047944895, 0.011483526673358195, -0.10001000029764828, -0.3007099209055795, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1406865455404655e-11, 0.0, 0.0, -0.15211903790385034, 0.0, -0.10212903790385035, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07593665318757832, -0.03494186219459571, 0.04089959488696079]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044816219928, 0.0, 0.012413830676965443, 0.0, 0.17609691084438509, 0.003339927396882776, 0.9645608983989093, -1.6263268161968243e-10, 0.005700881434231118, -9.184611526689736e-11, -0.9833156319906354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0547591907719455e-10, 0.0, 0.0, -0.004489547116977286, 0.0, -0.004489547116977286, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16179053826305503, -0.13467835200259912, 0.05233714729076094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20909933122141655, 0.0, 0.006670650904320104, 0.0, 0.030495423615918643, 0.06503905902363567, 0.3368018856169309, -0.1500000004820552, 0.011440160361093608, -0.10001000029910548, -0.35070992075212937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.3006558612131775e-11, 0.0, 0.0, -0.15232853483166567, 0.0, -0.10233853483166569, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08413105242809399, -0.04182726535714707, 0.04344111496186072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904486004547, 0.0, 0.011768217514409401, 0.0, 0.18224393180866655, -0.01916390271497888, 1.0000005002171315, -5.212497952851372e-11, -0.0008673262452917312, -2.9144014055440184e-11, -0.9999999969309965, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3199386313454186e-10, 0.0, 0.0, -0.004189938556306829, 0.0, -0.004189938556306829, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16388798481031347, -0.13770806325102714, 0.050830401497998626]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20974928346196006, 0.0, 0.007240970887316747, 0.0, 0.03969175839498482, 0.06306744187433781, 0.386801910593047, -0.1500000004912826, 0.011142185474431066, -0.10001000030430325, -0.40070992068634476, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.497529703852458e-11, 0.0, 0.0, -0.15253044088306777, 0.0, -0.10254044088306781, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09241791159321974, -0.048724268576277645, 0.045921626606422544]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044810870226, 0.0, 0.011406399659932879, 0.0, 0.1839266955813236, -0.03943234298595728, 1.0000004995223222, -1.8454778775646793e-10, -0.0059594977332508145, -1.0395538012366769e-10, -0.999999998684308, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.393747685278628e-10, 0.0, 0.0, -0.004038121028042349, 0.0, -0.004038121028042349, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16573718330251522, -0.13794006438261144, 0.04961023289123645]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21039923570296526, 0.0, 0.007732221462388101, 0.0, 0.048794427725561924, 0.06019460660459044, 0.4368019355081021, -0.15000000049922965, 0.010679004063671713, -0.10001000030875064, -0.45070992063834375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4712850532846104e-10, 0.0, 0.0, -0.15270186426513366, 0.0, -0.10271186426513369, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10078576245733886, -0.05550666059922085, 0.048349643723326334]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044820104153, 0.0, 0.009825011501427085, 0.0, 0.18205338661154202, -0.05745670539494751, 1.0000004983011015, -1.5894120516751055e-10, -0.009263628215187083, -8.894762340874952e-11, -0.9999999990399798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.443064165798729e-09, 0.0, 0.0, -0.0034284676413176727, 0.0, -0.0034284676413176727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16735701728238245, -0.1356478404588642, 0.04856034233807585]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21104918794604352, 0.0, 0.008147786332540378, 0.0, 0.05705228481887245, 0.056800807764968736, 0.48555193873788377, -0.15000000050177123, 0.01380061600121068, -0.1000100003101726, -0.500709920623694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2717270090655328e-10, 0.0, 0.0, -0.15284560293508898, 0.0, -0.102855602935089, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10920690437274234, -0.06180199580844874, 0.05069924429470897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044861565058, 0.0, 0.008311297403045492, 0.0, 0.16515714186621044, -0.0678759767924341, 0.9750000645956334, -5.08317863654895e-11, 0.06243223875077937, -2.8439096560152044e-11, -0.9999999997070046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6008839115618438e-09, 0.0, 0.0, -0.00287477339910612, 0.0, -0.00287477339910612, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684228383080697, -0.12590670418455774, 0.04699201142765273]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21169914018422958, 0.0, 0.008534478083287349, 0.0, 0.06403777050224106, 0.05321928999215028, 0.5293019426708888, -0.1500000005195259, 0.024257018781159476, -0.10001000031997744, -0.5507099205508378, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.419726178962552e-10, 0.0, 0.0, -0.15298591053575372, 0.0, -0.10299591053575374, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11765685702945115, -0.06743100837199263, 0.05295855908556127]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044763721124, 0.0, 0.007733835014939449, 0.0, 0.13970971366737228, -0.0716303554563691, 0.8749996308904224, -3.550929400220887e-10, 0.2091280555989759, -1.96096875850802e-10, -0.9999999985428758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.2959983397940833e-09, 0.0, 0.0, -0.002806152013295014, 0.0, -0.002806152013295014, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1689990531341761, -0.11258025127087788, 0.04518629581704597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21234909242042924, 0.0, 0.008919434834985456, 0.0, 0.07016762022951395, 0.0494175940147947, 0.5697185914419661, -0.15000000054176404, 0.04087900161373344, -0.10001000033265742, -0.6007099204582315, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.172261176257898e-10, 0.0, 0.0, -0.1531310030940534, 0.0, -0.1031410030940534, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12613808298481552, -0.07263779449082776, 0.05515874228157932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044723993144, 0.0, 0.007699135033962173, 0.0, 0.12259699454545765, -0.07603391954711151, 0.8083329754215461, -4.4476326808857897e-10, 0.3324396566514793, -2.535997719814049e-10, -0.9999999981478731, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5050699945906894e-09, 0.0, 0.0, -0.0029018511659931385, 0.0, -0.0029018511659931385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16962451910728726, -0.10413572237670247, 0.04400366392036104]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21299904465715247, 0.0, 0.009293039493004852, 0.0, 0.0754688364483216, 0.04559216505320407, 0.6030519081311608, -0.1500000005651568, 0.06416199520211285, -0.1000100003461419, -0.650709920371305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.445127250908072e-10, 0.0, 0.0, -0.15327506561997678, 0.0, -0.1032850656199768, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13464324815966475, -0.07752258837267564, 0.057309669372721216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044734464905, 0.0, 0.007472093160387933, 0.0, 0.10602432437615295, -0.07650857923181258, 0.6666663199529763, -4.678550080457724e-10, 0.4656598717675884, -2.696896087189137e-10, -0.9999999982614709, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.545732149300358e-09, 0.0, 0.0, -0.002881250518467983, 0.0, -0.002881250518467983, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17010330349698466, -0.09769587763695757, 0.04301854182283792]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21364899688939626, 0.0, 0.009658391636922252, 0.0, 0.07997391461622062, 0.041898905040172345, 0.6255518916748604, -0.15000000060235424, 0.09375928730575571, -0.10001000036752647, -0.7007099202590399, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.052037151899731e-09, 0.0, 0.0, -0.15341385722836937, 0.0, -0.10342385722836939, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1431656619275683, -0.08214254742847302, 0.0594179492930798]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044644875767, 0.0, 0.007307042878347957, 0.0, 0.09010156335798036, -0.07386520026063448, 0.44999967087399106, -7.439485877121285e-10, 0.591945842072857, -4.276915516720644e-10, -0.999999997754698, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.150488536178495e-09, 0.0, 0.0, -0.002775832167851572, 0.0, -0.002775832167851572, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17044827535807106, -0.09239918111594755, 0.04216559840717177]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21429894912892766, 0.0, 0.009985706783816878, 0.0, 0.0837337290217971, 0.038396160311925796, 0.6368018822133517, -0.15000000061579705, 0.12886795528830985, -0.10001000037561404, -0.7507099202145302, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3798853267769924e-09, 0.0, 0.0, -0.15353458444110352, 0.0, -0.10354458444110352, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15169634264779158, -0.0864779427160285, 0.06148597299316276]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044790628024, 0.0, 0.006546302937892518, 0.0, 0.07519628811152951, -0.07005489456493094, 0.22499981076982642, -2.6885595931816126e-10, 0.7021733596510829, -1.6175154970901431e-10, -0.9999999991098066, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.556963497545229e-09, 0.0, 0.0, -0.002414544254682828, 0.0, -0.002414544254682828, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17061361440446554, -0.08670790575110973, 0.04136047400165921]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21494890137143005, 0.0, 0.010264454243218679, 0.0, 0.08678608163424363, 0.03505861876145826, 0.6405518772939177, -0.15000000062038576, 0.1686260343332976, -0.1000100003784644, -0.8007099201998603, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6795870208000474e-09, 0.0, 0.0, -0.15363358895884927, 0.0, -0.10364358895884926, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1602220150777761, -0.09043350824202971, 0.06351113278956284]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044850047567, 0.0, 0.005574949188036019, 0.0, 0.06104705224893067, -0.06675083100935077, 0.0749999016113218, -9.177432472503254e-11, 0.7951615808997544, -5.70071178666004e-11, -0.9999999997066031, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.9940338804610954e-09, 0.0, 0.0, -0.001980090354914737, 0.0, -0.001980090354914737, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17051344859969034, -0.07911131052002421, 0.040503195928001605]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2155988536133159, 0.0, 0.010512477538606261, 0.0, 0.08917333761613773, 0.031819375692793896, 0.6405518767334001, -0.1500000006268655, 0.21212016801686073, -0.10001000038266154, -0.8507099201793282, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9436985414550135e-09, 0.0, 0.0, -0.1537173747429903, 0.0, -0.10372737474299028, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16872947233638164, -0.09391383418919608, 0.06549035882132435]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044837717048, 0.0, 0.004960465907751631, 0.0, 0.04774511963788189, -0.06478486137328723, -1.121035296536288e-08, -1.2959442582619387e-10, 0.8698826736712626, -8.394290868376176e-11, -0.9999999995893574, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.282230413099323e-09, 0.0, 0.0, -0.0016757156828205056, 0.0, -0.0016757156828205056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17014914517211085, -0.06960651894332726, 0.03958452063523034]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21624880583370626, 0.0, 0.010852328592641411, 0.0, 0.09096265279970184, 0.028608789864863603, 0.6405518797729715, -0.15000000069903854, 0.2584714183539546, -0.10001000043263603, -0.9007099200054107, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3562451393582777e-09, 0.0, 0.0, -0.15384859696269915, 0.0, -0.10385859696269913, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17721036787849695, -0.09688157501635633, 0.06742405875677049]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044407807097, 0.0, 0.006797021080703107, 0.0, 0.03578630367128222, -0.06421171655860582, 6.079142685293374e-08, -1.44346094321848e-09, 0.9270250067418772, -9.994897449842253e-10, -0.9999999965216487, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.250931958065287e-09, 0.0, 0.0, -0.0026244443941768753, 0.0, -0.0026244443941768753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1696179108423063, -0.05935481654320514, 0.03867399870892276]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21689875806718503, 0.0, 0.011300877429596479, 0.0, 0.09227873789315236, 0.02536685475345451, 0.6424268805905101, -0.15000000073163844, 0.30666902346985675, -0.10001000045630226, -0.9507099199307493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.8537136835463267e-09, 0.0, 0.0, -0.1540190682967799, 0.0, -0.10402906829677987, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.1856660076880292, -0.09939784436400441, 0.06931951751056728]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904466957562, 0.0, 0.008970976739101277, 0.0, 0.026321701869010262, -0.06483870222818186, 0.037500016350772804, -6.51997879852614e-10, 0.9639521023180428, -4.733246865006198e-10, -0.9999999985067713, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.949370883761092e-09, 0.0, 0.0, -0.0034094266816149916, 0.0, -0.0034094266816149916, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1691127961906452, -0.050325386952961446, 0.03790917507593572]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2175487103087854, 0.0, 0.011770218513646671, 0.0, 0.0932714632554926, 0.022061943787337147, 0.64523938086188, -0.15000000073901393, 0.35573319838288087, -0.10001000046195532, -1.0007099199127507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.328029080500186e-09, 0.0, 0.0, -0.15419080038758087, 0.0, -0.10420080038758084, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19410546128967338, -0.10159406944352833, 0.07118853758681834]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044832007294, 0.0, 0.009386821681003785, 0.0, 0.019854507246804855, -0.06609821932234719, 0.056250005427398664, -1.4750986883952772e-10, 0.9812834982604819, -1.1306130665252855e-10, -0.9999999996400307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.486307939077179e-09, 0.0, 0.0, -0.003434641816019505, 0.0, -0.003434641816019505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16878907203288349, -0.043924501590478456, 0.03738040152502133]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21819866255086648, 0.0, 0.012231417093476374, 0.0, 0.09406346139523418, 0.018684489860862883, 0.6485206308761887, -0.15000000074492958, 0.40480642523638716, -0.10001000046683238, -1.0507099198988972, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 3.7416997887180695e-09, 0.0, 0.0, -0.1543552077024912, 0.0, -0.10436520770249118, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20253867134741851, -0.10359818670415696, 0.07304196131361186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044841621763, 0.0, 0.009223971596594023, 0.0, 0.01583996279483155, -0.0675490785294853, 0.06562500028617337, -1.1831312535746496e-10, 0.981464537070126, -9.754100343302632e-11, -0.999999999722928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.273414164357678e-09, 0.0, 0.0, -0.00328814629820667, 0.0, -0.00328814629820667, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1686642011549027, -0.040082345212572625, 0.037068474535870324]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21884861479282602, 0.0, 0.012681963178276325, 0.0, 0.0946896242576126, 0.015264962496134796, 0.648520630748284, -0.1500000007511614, 0.45381268570763494, -0.10001000047244901, -1.100709919885822, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.089003996019543e-09, 0.0, 0.0, -0.15451122196480946, 0.0, -0.10452122196480944, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.210969653422239, -0.10547787095288377, 0.07488452190797693]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904483919091, 0.0, 0.00901092169599902, 0.0, 0.01252325724756844, -0.06839054729456173, -2.558093556426222e-09, -1.246361466178929e-10, 0.9801252094249557, -1.1233270757581111e-10, -0.999999999738495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.9460841460294794e-09, 0.0, 0.0, -0.0031202852463652567, 0.0, -0.0031202852463652567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1686196414964095, -0.03759368497453624, 0.03685121188730116]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21949856703278942, 0.0, 0.013147782374812735, 0.0, 0.09511874132783578, 0.011815420237923174, 0.6485206306468849, -0.15000000076362424, 0.5028362713185435, -0.1000100004846988, -1.1507099198571205, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.399854768709976e-09, 0.0, 0.0, -0.15467290784359775, 0.0, -0.10468290784359774, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.21939327077655743, -0.10720528731950858, 0.07671364924150878]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044799267624, 0.0, 0.009316383930728199, 0.0, 0.008582341404463636, -0.06899084516423246, -2.027981472628404e-09, -2.4925664219977295e-10, 0.9804717122181699, -2.449956832591036e-10, -0.9999999994259727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.217015453808661e-09, 0.0, 0.0, -0.0032337175757659285, 0.0, -0.0032337175757659285, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1684723470863685, -0.03454832733249622, 0.036582546670637206]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2201485192742323, 0.0, 0.013623788941061686, 0.0, 0.09531906162784433, 0.008342026567448452, 0.6485206305832516, -0.1500000007715805, 0.551943502408045, -0.10001000049336234, -1.2007099198405284, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.6742107292516785e-09, 0.0, 0.0, -0.15483629274046184, 0.0, -0.10484629274046184, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22780423022706894, -0.10874430297840229, 0.07852637152999838]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044828857465, 0.0, 0.009520131324979031, 0.0, 0.004006406000171084, -0.06946787340949447, -1.272666291182583e-09, -1.5912499862137065e-10, 0.982144621790032, -1.7327077473054033e-10, -0.9999999996681582, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.487119210834061e-09, 0.0, 0.0, -0.0032676979372821273, 0.0, -0.0032676979372821273, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16821918901023017, -0.030780313177874098, 0.03625444576979181]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22079847151555543, 0.0, 0.014110573710590914, 0.0, 0.09527248824826526, 0.004849772608454271, 0.6485206305171828, -0.1500000007799317, 0.6011589517180577, -0.10001000050357446, -1.2507099198236151, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 4.917908082290279e-09, 0.0, 0.0, -0.15500069749687434, 0.0, -0.10501069749687432, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23619897491002814, -0.11007252304077374, 0.08032091153843443]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044826462983, 0.0, 0.00973569539058459, 0.0, -0.0009314675915815165, -0.06984507917988361, -1.3213773837591944e-09, -1.6702433388508912e-10, 0.9843089862002536, -2.042423831144059e-10, -0.999999999661733, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.873947060772019e-09, 0.0, 0.0, -0.0032880951282497186, 0.0, -0.0032880951282497186, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16789489365918395, -0.026564401247428877, 0.03589080016872123]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2214484237568297, 0.0, 0.014607555872701287, 0.0, 0.09497283766926826, 0.0013440461490668407, 0.6485206304499114, -0.15000000078844067, 0.6504789457596579, -0.10001000051549594, -1.3007099198066143, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.137772956576989e-09, 0.0, 0.0, -0.15516612963298104, 0.0, -0.10517612963298102, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24457550109843162, -0.1111813882913863, 0.08209660339454215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825485388, 0.0, 0.009939643242207502, 0.0, -0.0059930115799399514, -0.07011452918774859, -1.3454284400697918e-09, -1.7017965170917594e-10, 0.9863998808320041, -2.384294710003577e-10, -0.9999999996599848, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.397297485734195e-09, 0.0, 0.0, -0.003308642722134026, 0.0, -0.003308642722134026, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16753052376806973, -0.022177305012251246, 0.03551383712215434]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2220983759980697, 0.0, 0.015113155745422463, 0.0, 0.094420946483, -0.00216903209190683, 0.6485206303817854, -0.15000000079706255, 0.6998873937161252, -0.10001000052969553, -1.3507099197898365, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.339860708042743e-09, 0.0, 0.0, -0.1553326177339662, 0.0, -0.10534261773396618, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2529327762420183, -0.11207104885059285, 0.08385345624777664]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044824800344, 0.0, 0.01011199745442348, 0.0, -0.011037823725364899, -0.0702615648194734, -1.36251809128989e-09, -1.7243747943025986e-10, 0.9881689591293462, -2.8399178713010005e-10, -0.9999999996644424, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.041755029315071e-09, 0.0, 0.0, -0.0033297620197030595, 0.0, -0.0033297620197030595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16714550287173405, -0.017793211184131, 0.03513705706468985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2227483282393383, 0.0, 0.015625098975479503, 0.0, 0.093620623594063, -0.0056826996005171024, 0.6485206303142311, -0.15000000080560133, 0.7493661217053265, -0.10001000054682253, -1.4007099197734676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.528605922436317e-09, 0.0, 0.0, -0.15549994685252458, 0.0, -0.10550994685252457, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2612702553209708, -0.11274564918306716, 0.08559178033665367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044825372041, 0.0, 0.01023886460114081, 0.0, -0.016006457778740255, -0.07027335017220546, -1.35108650252395e-09, -1.707753936836974e-10, 0.9895745597840248, -3.425400640587867e-10, -0.9999999996726217, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.77490428787147e-09, 0.0, 0.0, -0.0033465823711677648, 0.0, -0.0033465823711677648, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16674958157904987, -0.013492006649486316, 0.03476648177754073]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2233982804809964, 0.0, 0.016151811965851602, 0.0, 0.09257620564835774, -0.009156325087475159, 0.6485206302546236, -0.15000000081299195, 0.7989015240881927, -0.10001000056552993, -1.450709919756761, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.705159646365449e-09, 0.0, 0.0, -0.15567149501929897, 0.0, -0.10568149501929895, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2695849884202265, -0.11321018105902551, 0.08731132032083022]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904483316163, 0.0, 0.01053425980744193, 0.0, -0.020888358914105103, -0.06947250973916112, -1.1921506773564672e-09, -1.4781249721503265e-10, 0.9907080476573255, -3.7414794840339533e-10, -0.9999999996658693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.5310744785826864e-09, 0.0, 0.0, -0.0034309633354876598, 0.0, -0.0034309633354876598, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16629466198511336, -0.009290637519167127, 0.03439079968353114]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22404823272191543, 0.0, 0.01670179410018435, 0.0, 0.09129151724487952, -0.012500479729901572, 0.6485206301743803, -0.1500000008226585, 0.8484863196745451, -0.1000100005999739, -1.5007099197355778, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 5.878929188958743e-09, 0.0, 0.0, -0.1558516341873733, 0.0, -0.1058616341873733, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2778700636982681, -0.11346900053323304, 0.08901076988191917]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044818381131, 0.0, 0.010999642686654917, 0.0, -0.02569376806956442, -0.06688309284852827, -1.604864356320739e-09, -1.9333113324994764e-10, 0.9916959117270491, -6.888796015496336e-10, -0.999999999576335, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4753908518658475e-09, 0.0, 0.0, -0.0036027833614867763, 0.0, -0.0036027833614867763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1657015055608328, -0.005176389484150449, 0.033988991221778946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22469818496266336, 0.0, 0.01727302224630608, 0.0, 0.08976962415618728, -0.01566518389626617, 0.6485206300896822, -0.15000000083282966, 0.8981147179182369, -0.10001000066253873, -1.550709919713898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.05375263058638e-09, 0.0, 0.0, -0.15603979627678075, 0.0, -0.10604979627678074, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.28612148421272143, -0.11352576888950498, 0.09068942059720404]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044814958595, 0.0, 0.011424562922434602, 0.0, -0.03043786177384493, -0.06329408332729203, -1.6939617687373992e-09, -2.034231728748778e-10, 0.9925679648738353, -1.2512964352458322e-09, -0.9999999995664056, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.496468832552792e-09, 0.0, 0.0, -0.0037632417881488765, 0.0, -0.0037632417881488765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1650284102890669, -0.0011353671254387982, 0.03357301430569766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2253481372038179, 0.0, 0.017857883151037084, 0.0, 0.08801295913639282, -0.01864200845186594, 0.6485206300166523, -0.15000000084171888, 0.9477818768895375, -0.10001000093137014, -1.600709919695662, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.225456061526945e-09, 0.0, 0.0, -0.15623264261135686, 0.0, -0.10624264261135687, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2943383888579311, -0.1133835405829943, 0.09234727904522456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044823091095, 0.0, 0.011697218094620036, 0.0, -0.03513330039588935, -0.05953649111199532, -1.4605977778677033e-09, -1.7778429305701197e-10, 0.9933431794260119, -5.3766280833859315e-09, -0.9999999996352784, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4340686188112653e-09, 0.0, 0.0, -0.003856926691522533, 0.0, -0.003856926691522533, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16433809290419346, 0.002844566130213586, 0.033157168960410356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22599808944707864, 0.0, 0.01838578605757855, 0.0, 0.08726962042814145, -0.02148436347881346, 0.6485206299975904, -0.15000000084399806, 0.9972376593253539, -0.10149295659461942, -1.6507099196910697, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.376292362635531e-09, 0.0, 0.0, -0.15640416717991285, 0.0, -0.10641416717991285, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3026367246767601, -0.11365840896765043, 0.09410203878694091]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044865214745, 0.0, 0.010558058130829375, 0.0, -0.014866774165027269, -0.05684710053895043, -3.812375620497551e-10, -4.558357211708274e-11, 0.9891156487163273, -0.029659113264985618, -0.9999999999081556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.0167260221717253e-09, 0.0, 0.0, -0.003430491371119661, 0.0, -0.003430491371119661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16596671637658011, -0.005497367693122679, 0.0350951948343271]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22664804169059963, 0.0, 0.018840006748963932, 0.0, 0.08840492069765327, -0.024392733765289724, 0.6485206299842403, -0.15000000084544074, 1.0462943997134098, -0.10567192467666546, -1.7007099196880862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.501261782367847e-09, 0.0, 0.0, -0.1565485004968659, 0.0, -0.10655850049686588, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3111261249822649, -0.11496549237911022, 0.09610529751097581]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044870419725, 0.0, 0.009084413827707609, 0.0, 0.02270600539023654, -0.05816740572952526, -2.6700106270383326e-10, -2.8853439740065987e-11, 0.9811348077611188, -0.08357936164092075, -0.9999999999403305, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.499388394646316e-09, 0.0, 0.0, -0.0028866663390606515, 0.0, -0.0028866663390606515, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1697880061100957, -0.02614166822919553, 0.04006517448069801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2272979939338419, 0.0, 0.01922541003542927, 0.0, 0.09141088703754008, -0.027642250000865298, 0.6485206299622293, -0.15000000084759751, 1.0949260853578993, -0.11281341848140539, -1.7507099196836429, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.603990964623237e-09, 0.0, 0.0, -0.15666792998448356, 0.0, -0.10667792998448357, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.31986597720360976, -0.11775797841320136, 0.09845562635552416]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044864845568, 0.0, 0.007708065729306733, 0.0, 0.060119326797736364, -0.06499032471151148, -4.4022066378222286e-10, -4.3135235934749456e-11, 0.9726337128897881, -0.14282987609479839, -0.9999999999111359, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.0545836451077934e-09, 0.0, 0.0, -0.0023885897523536976, 0.0, -0.0023885897523536976, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17479704442689714, -0.05584972068182295, 0.0470065768909669]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22794794616049477, 0.0, 0.019663216868114303, 0.0, 0.09595724604108705, -0.031513928604466175, 0.6485206294161658, -0.1500000008953732, 1.1431581731527016, -0.122715114970351, -1.8007099195632277, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 6.800086744031778e-09, 0.0, 0.0, -0.15681312023204916, 0.0, -0.10682312023204915, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.32883625727994553, -0.12177903300371423, 0.1011975108086962]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044533057192, 0.0, 0.008756136653700739, 0.0, 0.09092718007093946, -0.07743357207201752, -1.0921269262070155e-08, -9.555133829885226e-10, 0.964641755896047, -0.19803392977891207, -0.9999999975916941, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.921915588170908e-09, 0.0, 0.0, -0.0029038049513116803, 0.0, -0.0029038049513116803, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17940560152671553, -0.08042109181025732, 0.05483768906344095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2285978983789231, 0.0, 0.02019778242038303, 0.0, 0.1015934010784249, -0.03623301233749256, 0.6485206285389342, -0.1500000009630398, 1.191034592837942, -0.1349449256109987, -1.8507099194363694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.150230432186841e-09, 0.0, 0.0, -0.15700312472854858, 0.0, -0.10701312472854857, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33802112830129416, -0.12677509839018047, 0.10432340356810274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904436856656, 0.0, 0.010691311045374498, 0.0, 0.11272310074675733, -0.09438167466052755, -1.754463174687428e-08, -1.353332621585259e-09, 0.957528393704806, -0.24459621281295374, -0.9999999974628351, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.002873763101444e-09, 0.0, 0.0, -0.0038000899299882977, 0.0, -0.0038000899299882977, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1836974204269731, -0.09992130772932467, 0.06251785518813079]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22924785061936293, 0.0, 0.020737691803928926, 0.0, 0.1079149889944046, -0.04194605310748499, 0.648520628420636, -0.15000000097183167, 1.2385907035183767, -0.1490380006997704, -1.900709919420488, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.54569605950863e-09, -1.0426903683738898e-12, -2.5514401118195656e-13, -0.15719728381705064, 0.0, -0.10720728381705065, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34741095355339363, -0.13253875137666998, 0.10778053041429005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044808796163, 0.0, 0.010798187670917945, 0.0, 0.1264317583195939, -0.11426081539984874, -2.3659661644447584e-09, -1.758371953475359e-10, 0.9511222136086955, -0.28186150177543445, -0.9999999996823721, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.909312546435763e-09, -2.0853807367477396e-11, -5.102880223639271e-12, -0.0038831817700415243, 0.0, -0.0038831817700415243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1877965050419889, -0.11527305972979002, 0.06914253692374604]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22989780285812036, 0.0, 0.02125959858857387, 0.0, 0.11459825854316781, -0.048710905661322045, 0.6485206282489472, -0.15000000098414312, 1.2858556284373268, -0.16454561561375944, -1.95070991939866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 7.94278953324394e-09, -3.0403320506258407e-12, -7.733889766789014e-13, -0.1573814351600216, 0.0, -0.1073914351600216, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.35699897437664574, -0.1389038744794559, 0.11147550916898084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044775148969, 0.0, 0.010438135692898963, 0.0, 0.13366539097526417, -0.1352970510767411, -3.4337746962637712e-09, -2.462290677275148e-10, 0.9452984983790007, -0.3101522982797803, -0.9999999995634374, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.941869474706234e-09, -3.9952833645039244e-11, -1.0364899309938878e-11, -0.003683026859419063, 0.0, -0.003683026859419063, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19176041646504177, -0.12730246205571835, 0.07389957509381602]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23054775485035695, 0.0, 0.02186462247148685, 0.0, 0.12138908799278897, -0.05649667516409468, 0.6485206158107779, -0.15000000156864474, 1.3328638233173495, -0.1810319198486464, -2.0007099189910917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 9.414842788505576e-09, -1.913049931177333e-11, -7.77090301008133e-12, -0.15759512833415784, 0.0, -0.10760512833415783, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.36677876288705563, -0.14573363422859614, 0.11527847017272014]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999039844731473, 0.0, 0.012100477658259558, 0.0, 0.1358165889924233, -0.15571539005545265, -2.487633863473451e-07, -1.1690032168508873e-08, 0.9401638976004553, -0.3297260846977389, -0.9999999918486393, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.9441065105232425e-08, -3.2180334522297096e-10, -1.3995028066804872e-10, -0.004273863482724726, 0.0, -0.004273863482724726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19559577020819743, -0.13659519498280495, 0.0760592200747859]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23119770702939135, 0.0, 0.022479608442008768, 0.0, 0.1279280117911787, -0.065121020276135, 0.6485206148580289, -0.15000000167904998, 1.379268106179796, -0.19791953321164663, -2.050709918719779, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1115903595142684e-08, -3.7857343609259916e-11, -1.6258580684052826e-11, -0.15780800249453208, 0.0, -0.10781800249453208, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37671058105571864, -0.15275282186605943, 0.11903688852937533]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043580687947, 0.0, 0.012299719410438332, 0.0, 0.13077847596779463, -0.17248690224080668, -1.9054980297925722e-08, -2.2081048098157728e-09, 0.9280856572489296, -0.33775226726000473, -0.9999999945737411, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4021216132742206e-08, -3.7453688594973177e-10, -1.6975355347942991e-10, -0.004257483207484845, 0.0, -0.004257483207484845, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19863636337325982, -0.1403837527492658, 0.07516836713310386]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23184765806519372, 0.0, 0.023097359065355757, 0.0, 0.13365869955507467, -0.0740114373450419, 0.648520609543342, -0.15000000225457907, 1.422965171830249, -0.2143799827745139, -2.098938326600579, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2753217741840951e-08, -5.477721509148242e-11, -2.479893808615554e-11, -0.15801118959641505, 0.0, -0.10802118959641506, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.38667228016511457, -0.15934750061329966, 0.12262207163908631]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999020716047414, 0.0, 0.012355012466939775, 0.0, 0.11461375527791967, -0.17780834137813792, -1.0629373828857953e-07, -1.1510581868469042e-08, 0.8739413130090581, -0.32920899125734515, -0.9645681576160031, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.2746282933965545e-08, -3.3839742964445013e-10, -1.7080714804205447e-10, -0.004063742037659556, 0.0, -0.004063742037659556, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19923398218791882, -0.1318935749448046, 0.07170366219421956]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23245135821315047, 0.0, 0.023651585936944827, 0.0, 0.13815819787098435, -0.08241848935617074, 0.6485206092120694, -0.15000000230184185, 1.4618918239728365, -0.22965107487618347, -2.1424723141088395, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4136978914913975e-08, -6.858577382316248e-11, -3.2198187894587434e-11, -0.1581851245947468, 0.0, -0.1081951245947468, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.39652166044585796, -0.16493414836225212, 0.12594494847795754]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012074002959135122, 0.0, 0.011084537431781408, 0.0, 0.08998996631819364, -0.168141040222577, -6.625452348267423e-09, -9.45255599426992e-10, 0.7785330428517518, -0.30542184203339134, -0.8706797501652095, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7675223461460466e-08, -2.761711746336011e-10, -1.4798499616863783e-10, -0.0034786999666346586, 0.0, -0.0034786999666346586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1969876056148681, -0.1117329549790489, 0.0664575367774243]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23285989429464005, 0.0, 0.02419511714977966, 0.0, 0.14131225010848045, -0.0898134535250838, 0.6485205149756879, -0.1500000089914203, 1.495152825295853, -0.24331436077630994, -2.1798187931733968, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5447162340067583e-08, -7.652653702333584e-11, -4.001337926033458e-11, -0.15834547722401884, 0.0, -0.10835547722401885, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4061537540659481, -0.1693192033094132, 0.12896743830993018]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00817072162979149, 0.0, 0.01087062425669661, 0.0, 0.06308104474992204, -0.1478992833782612, -1.884727631173058e-06, -1.3379156886403865e-07, 0.6652200264603333, -0.2732657180025293, -0.7469295812911407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.6203668503072155e-08, -1.5881526400346788e-10, -1.5630382731494277e-10, -0.0032070525854411263, 0.0, -0.0032070525854411263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19264187240180328, -0.08770109894322164, 0.06044979663945314]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23316043961107294, 0.0, 0.024683460882710104, 0.0, 0.1432128769062681, -0.09596026849169326, 0.6485205123525173, -0.15000000929612767, 1.5228839367369664, -0.2552221568668601, -2.2108423424890757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.655090754999538e-08, -8.102564817971736e-11, -4.69006156900477e-11, -0.1584821114118807, 0.0, -0.10849211141188071, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4155034423213876, -0.1725549049097725, 0.1316930425490508]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006010906328657944, 0.0, 0.009766874658608898, 0.0, 0.03801253595575331, -0.12293629933218929, -5.2463411205057644e-08, -6.0941472099821464e-09, 0.5546222288222695, -0.23815592181100403, -0.6204709863135772, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.207490419855599e-08, -8.998222312763029e-11, -1.3774472859426245e-10, -0.0027326837572372873, 0.0, -0.0027326837572372873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18699376510878926, -0.06471403200718603, 0.054512084782412214]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2333369060458328, 0.0, 0.025114299395530355, 0.0, 0.1439269508242421, -0.10083243379924917, 0.6485204510966678, -0.15000001299672583, 1.54515403048778, -0.2651015799290508, -2.2355695879325537, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.743531022887847e-08, -8.324714988240809e-11, -5.2528139737987404e-11, -0.15859639542015294, 0.0, -0.10860639542015293, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42453664662085777, -0.17471857585836037, 0.13414260325659544]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003529328695197331, 0.0, 0.008616770256405035, 0.0, 0.014281478359479665, -0.09744330615111815, -1.2251169898690067e-06, -7.401196309132527e-08, 0.4454018750162714, -0.19758846124381368, -0.4945449088695583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7688053577661782e-08, -4.443003405381462e-11, -1.1255048095879397e-10, -0.0022856801654445, 0.0, -0.0022856801654445, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18066408598940384, -0.04327341897175778, 0.0489912141508933]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23345017649183689, 0.0, 0.025562334333568262, 0.0, 0.14357636122608883, -0.10451823588294969, 0.6485101834368872, -0.15000054767467796, 1.5624187928456847, -0.2728285129098619, -2.2545327200363254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8157099414399842e-08, -8.274047766673912e-11, -5.706207400326252e-11, -0.15871208351056104, 0.0, -0.10872208351056104, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4332632851844255, -0.1759432136987451, 0.1363534142706526]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002265408920081733, 0.0, 0.008960698760758133, 0.0, -0.007011791963065454, -0.07371604167401051, -0.0002053531956116083, -1.0693559042482743e-05, 0.3452952471580932, -0.15453865961622157, -0.37926264207543503, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4435783710427439e-08, 1.0133444313378143e-11, -9.067868530550222e-11, -0.0023137618081619004, 0.0, -0.0023137618081619004, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17453277127135441, -0.024492756807694447, 0.04421622028114328]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23354709943893084, 0.0, 0.026043600688978333, 0.0, 0.1423391612726244, -0.10717185771402409, 0.6484829928122745, -0.15000157811889386, 1.575495048324172, -0.27848788988709283, -2.268675988531895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.876306294518793e-08, -7.940160949018136e-11, -6.069441931571837e-11, -0.15883498246556102, 0.0, -0.10884498246556101, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4417199197563183, -0.1764044824743997, 0.1383686839588234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001938458941878926, 0.0, 0.009625327108201341, 0.0, -0.02474399906928895, -0.0530724366214879, -0.0005438124922535102, -2.060888431814506e-05, 0.2615251095697489, -0.11318753954461916, -0.2828653699113879, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2119270615761769e-08, 6.677736353115447e-11, -7.264690624911709e-11, -0.0024579790999995853, 0.0, -0.0024579790999995853, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16913269143785647, -0.009225375513091567, 0.04030539376341641]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23364652157190524, 0.0, 0.026556752697781537, 0.0, 0.14040895031317793, -0.10897826494258968, 0.6484506764544448, -0.15000231245062512, 1.5853100379868694, -0.2822949838046462, -2.2790832430492185, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9283335534337668e-08, -7.365447402695554e-11, -6.360258672928566e-11, -0.1589653270094304, 0.0, -0.10897532700943038, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4499550693901091, -0.17628389829245467, 0.14023045577806884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0019884426594877743, 0.0, 0.010263040176064095, 0.0, -0.03860421918892897, -0.03612814457131189, -0.0006463271565940428, -1.4686634625192808e-05, 0.1962997932539462, -0.07614187835106714, -0.20814509034647016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.040545178299469e-08, 1.1494270926451437e-10, -5.8163348271345824e-11, -0.002606890877387421, 0.0, -0.002606890877387421, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16470299267581576, 0.0024116836389002534, 0.037235436384908435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23375242036731944, 0.0, 0.02701269615353316, 0.0, 0.13796471176186845, -0.11012488014858206, 0.6484420122943285, -0.15000231409845804, 1.592714475557891, -0.2844994933582057, -2.2867618159945082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.9700681088802365e-08, -6.778668525192253e-11, -6.58427538699814e-11, -0.1590799785840921, 0.0, -0.10908997858409208, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45801907665713304, -0.17574337830544842, 0.14197591694161615]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021179759082840667, 0.0, 0.009118869115032461, 0.0, -0.048884771026189856, -0.022932304119847646, -0.0001732832023256829, -3.2956658318118945e-08, 0.1480887514204333, -0.0440901910711896, -0.1535714589057927, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.346911089293952e-09, 1.1735577550066008e-10, -4.4803342813914826e-11, -0.0022930314932340158, 0.0, -0.0022930314932340158, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1612801453404785, 0.01081039974012472, 0.0349092232709461]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2338659231946939, 0.0, 0.02739183408059816, 0.0, 0.1351537360195266, -0.11077871517158902, 0.6484419114911212, -0.15000231495767824, 1.5984225593442756, -0.285403703581227, -2.2925319789193237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.0023603628948926e-08, -6.263298434069478e-11, -6.753049879912866e-11, -0.15917367500587645, 0.0, -0.10918367500587643, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4659573541300894, -0.17491238699337666, 0.14363572379574532]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022700565474893446, 0.0, 0.007582758541299972, 0.0, -0.056219514846836766, -0.013076700460139264, -2.016064146821944e-06, -1.7184403942960408e-08, 0.11416167572768893, -0.018084204460426342, -0.11540325849630509, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.458450802931198e-09, 1.0307401822455513e-10, -3.375489858294525e-11, -0.0018739284356870326, 0.0, -0.0018739284356870326, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1587655494591269, 0.016619826241435015, 0.03319613708258321]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23398556698750417, 0.0, 0.02772923012901613, 0.0, 0.1320890483878322, -0.11107868538223692, 0.6484412723115424, -0.1500023294154196, 1.6029762536193908, -0.2853156659470832, -2.2970090050427263, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.029681071934546e-08, -5.708160534809578e-11, -6.886716390910505e-11, -0.15925503418648854, 0.0, -0.1092650341864885, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4738073947305494, -0.17388639393446054, 0.1452339426197058]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002392875856205386, 0.0, 0.00674792096835945, 0.0, -0.061293752633888074, -0.005999404212957951, -1.2783591576158763e-05, -2.891548274544786e-07, 0.09107388550230336, 0.001760752682876357, -0.08954052246805287, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.464141807930622e-09, 1.1102757985198014e-10, -2.673330219952771e-11, -0.001627183612241516, 0.0, -0.001627183612241516, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15700081200920052, 0.020519861178322725, 0.031964376479209494]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23410933325183225, 0.0, 0.028041757235566504, 0.0, 0.12885354001162114, -0.11113396841962918, 0.6484407596160549, -0.15000233629890292, 1.606758771783485, -0.2845093177805187, -2.3006272165494317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.0544374693364325e-08, -5.072118956612593e-11, -6.997768868039825e-11, -0.1593288285119097, 0.0, -0.10933882851190965, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48159827706432196, -0.17273214936617354, 0.14678881974330207]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024753252865618923, 0.0, 0.006250542131007422, 0.0, -0.06471016752422128, -0.001105660747845156, -1.0253909750451642e-05, -1.3766966598552862e-07, 0.07565036328188371, 0.01612696333128955, -0.07236423013410599, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.9512794803773375e-09, 1.2720831563939715e-10, -2.2210495425864007e-11, -0.0014758865084229585, 0.0, -0.0014758865084229585, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15581764667545103, 0.02308489136573995, 0.031097542471925504]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23423554484492332, 0.0, 0.028339901647175095, 0.0, 0.1255060827783855, -0.11102612778323918, 0.6484402619865923, -0.15000234480641825, 1.6100286309160716, -0.28320582600245575, -2.303679494496613, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.0780496730469134e-08, -4.340206095585463e-11, -7.094423079902275e-11, -0.15939837859081107, 0.0, -0.10940837859081105, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4893514699409288, -0.17149484925818256, 0.1483138298766744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025242318618210954, 0.0, 0.005962888232171783, 0.0, -0.06694914466471238, 0.0021568127277997824, -9.952589251615955e-06, -1.7015030668549262e-07, 0.06539718265173003, 0.026069835561258504, -0.06104555894362565, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.7224407420962155e-09, 1.46382572205426e-10, -1.9330842372489993e-11, -0.0013910015780279055, 0.0, -0.0013910015780279055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15506385753213695, 0.02474600215981932, 0.03050020266744668]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2343629979787527, 0.0, 0.028629881713542624, 0.0, 0.12208749661852794, -0.11081339225980956, 0.6484397557360918, -0.1500023538862766, 1.6129545121371744, -0.2815713323764946, -2.3063569083418605, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1012427442448405e-08, -3.5163358655847117e-11, -7.181962946838004e-11, -0.15946573014865476, 0.0, -0.10947573014865475, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49708217220689543, -0.17020460292446507, 0.14981871818366843]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002549062676587914, 0.0, 0.0057996013273505466, 0.0, -0.06837172319715155, 0.004254710468592533, -1.0125010009834757e-05, -1.8159716706827383e-07, 0.05851762442205703, 0.032689872519222105, -0.053548276904955755, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.638614239585403e-09, 1.6477404600015038e-10, -1.7507973387145735e-11, -0.0013470311568738798, 0.0, -0.0013470311568738798, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15461404531933265, 0.025804926674350016, 0.03009776613988055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2344908947129585, 0.0, 0.02891514143485623, 0.0, 0.11862556742783333, -0.11053560118320818, 0.6484392457343992, -0.15000236267571637, 1.6156441061162783, -0.2797237903429685, -2.308781248566564, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.124305099563389e-08, -2.619252949260472e-11, -7.264496270161636e-11, -0.15953199500685766, 0.0, -0.10954199500685766, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5048007515332844, -0.16888140656508638, 0.15131041571608805]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002557934684115954, 0.0, 0.005705194426272128, 0.0, -0.06923858381389242, 0.0055558215320275954, -1.0200033852804097e-05, -1.757887952344529e-07, 0.05379187958207796, 0.036950840670521616, -0.04848680449407016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.612471063709708e-09, 1.7941658326484802e-10, -1.650666466472641e-11, -0.0013252971640581462, 0.0, -0.0013252971640581462, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.154371586527779, 0.026463927187573878, 0.029833950648392425]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23461872265981276, 0.0, 0.02919743985561392, 0.0, 0.11513892872436539, -0.11021890289895717, 0.6484387355717922, -0.15000237065113722, 1.618165247200876, -0.2777431204985583, -2.3110289223764098, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1472827714829075e-08, -1.6725966771297862e-11, -7.344981498682178e-11, -0.1595976962105436, 0.0, -0.10960769621054359, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5125140418872783, -0.16753861945170317, 0.15279378595491294]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025565589370850476, 0.0, 0.005645968415153752, 0.0, -0.06973277406935874, 0.006333965685020402, -1.0203252138787573e-05, -1.5950841693143406e-07, 0.05042282169195538, 0.039613396888204463, -0.04495347619691749, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.59553438390374e-09, 1.8933125442613705e-10, -1.6097045704108537e-11, -0.0013140240737186954, 0.0, -0.0013140240737186954, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15426580707987964, 0.02685574226766386, 0.029667404776497663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2347461471374862, 0.0, 0.029477599995726585, 0.0, 0.11163990556434744, -0.10987973971251085, 0.6484382233230851, -0.15000237756329504, 1.6205602544718025, -0.2756812906295641, -2.3131472731768437, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1701078306136764e-08, -6.993056465398058e-12, -7.425431396593362e-11, -0.15966303455978986, 0.0, -0.10967303455978986, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5202263989088121, -0.16618525114532579, 0.1542722034166537]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002548489553469015, 0.0, 0.005603202802253336, 0.0, -0.06998046320035903, 0.006783263728926491, -1.0244974141707887e-05, -1.3824315639164396e-07, 0.04790014541852751, 0.04123659737988409, -0.042367016008675464, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.56501182615382e-09, 1.9465820611799593e-10, -1.6089979582236827e-11, -0.0013067669849253284, 0.0, -0.0013067669849253284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15424714043067508, 0.0270673661275478, 0.029568349234815418]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23487293390634528, 0.0, 0.029755978211713916, 0.0, 0.1081365208677483, -0.10952797063519008, 0.6484377017612931, -0.1500023833413627, 1.6228551870399055, -0.27357077867490387, -2.3151651896169314, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.1926716644642806e-08, 2.8090770400611453e-12, -7.507133980198243e-11, -0.1597280609129997, 0.0, -0.10973806091299969, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5279404990685906, -0.16482741443172033, 0.15574798584011823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0025357353771814925, 0.0, 0.005567564319746647, 0.0, -0.07006769393198281, 0.00703538154641534, -1.0431235839951606e-05, -1.1556135324608088e-07, 0.0458986513620609, 0.04221023909320415, -0.040358328801756035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.5127667701208695e-09, 1.9604267010918394e-10, -1.6340516720975946e-11, -0.0013005270641966514, 0.0, -0.0013005270641966514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15428200319557223, 0.027156734272109136, 0.029515648469290202]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2349989021130141, 0.0, 0.0300333514128411, 0.0, 0.10463387576098314, -0.10916917013363675, 0.6484370973216877, -0.15000239042048158, 1.6250656753822348, -0.27143102121542395, -2.317099787078903, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2149321376928164e-08, 1.2553336564362067e-11, -7.591152658572583e-11, -0.15979297149496838, 0.0, -0.10980297149496836, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.535657913314235, -0.1634692395911408, 0.15722270859887044]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00251936413337637, 0.0, 0.00554746402254369, 0.0, -0.07005290213530335, 0.00717601003106655, -1.2088792106869578e-05, -1.4158237737221335e-07, 0.04420976684658694, 0.04279514918959882, -0.038691949239432324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.452094645707175e-09, 1.948851904860186e-10, -1.6803735674868066e-11, -0.0012982116393735102, 0.0, -0.0012982116393735102, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15434828491288669, 0.02716349681159085, 0.02949445517504397]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23512389711455098, 0.0, 0.030311467457312107, 0.0, 0.10113508399282219, -0.10880623805666632, 0.6484362838140256, -0.15000240293111636, 1.6272005468312238, -0.26927300752371003, -2.318960565199986, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2369780858839134e-08, 2.219962092500878e-11, -7.67876467415067e-11, -0.15985827654600593, 0.0, -0.10986827654600592, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5433795022060451, -0.16211345620762432, 0.1586974290101216]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002499900030737275, 0.0, 0.005562320889420086, 0.0, -0.0699758353632191, 0.007258641539408401, -1.627015324160636e-05, -2.502126954737701e-07, 0.042697428979782154, 0.04316027383427814, -0.03721556242165659, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.409189638219435e-09, 1.9292568721293418e-10, -1.7522403115617473e-11, -0.0013061010207512567, 0.0, -0.0013061010207512567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15443177783620432, 0.02711566767032933, 0.029494408225023354]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23524777415625286, 0.0, 0.03059189952242291, 0.0, 0.09764189813496264, -0.10844048376721195, 0.6484352335277774, -0.15000242074401485, 1.6292640292954501, -0.2671023824056519, -2.3207520248452713, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.258896989012391e-08, 3.1728884400891745e-11, -7.770987037437262e-11, -0.1599244143640249, 0.0, -0.1099344143640249, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5511056793095391, -0.16076177191939214, 0.1601728438952585]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0024775408340380013, 0.0, 0.005608641302216077, 0.0, -0.06986371715719096, 0.007315085789087459, -2.1005724963301243e-05, -3.5625796992647297e-07, 0.04126964928452708, 0.04341250236116362, -0.035829192905704674, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.383780625695489e-09, 1.9058526951765944e-10, -1.8444472657318492e-11, -0.001322756360379724, 0.0, -0.001322756360379724, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15452354206987995, 0.027033685764643694, 0.029508297702737815]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23537037467807018, 0.0, 0.030844804304131584, 0.0, 0.09415512059614983, -0.10807236438422016, 0.6484351923730954, -0.15000242148205567, 1.6312566575858614, -0.264921371051575, -2.3224754827187453, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.277676354631131e-08, 3.9821514704439934e-11, -7.851289453323425e-11, -0.1599832570734113, 0.0, -0.1099932570734113, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5588365789779075, -0.15941510406309659, 0.16164939731444897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002452010436346326, 0.0, 0.00505809563417353, 0.0, -0.06973555077625619, 0.0073623876598357466, -8.23093639646332e-07, -1.4760816422144336e-08, 0.03985256580822472, 0.04362022708153831, -0.03446915746947815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.755873123748003e-09, 1.6185260607096375e-10, -1.6060483177232553e-11, -0.0011768541877280017, 0.0, -0.0011768541877280017, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1546179933673668, 0.026933357125911103, 0.02953106838380959]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2354836315201696, 0.0, 0.031066841292699415, 0.0, 0.0906870719313321, -0.10770757186704713, 0.6484350279421831, -0.15000242320180887, 1.6331580314333565, -0.26256078061520977, -2.3241134405567734, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.2928484863876526e-08, 4.623222790995583e-11, -7.91570905998172e-11, -0.16003388303076396, 0.0, -0.11004388303076396, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5665751226248817, -0.15808307098830915, 0.16312852739624395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002265136841988309, 0.0, 0.004440739771356601, 0.0, -0.06936097329635471, 0.007295850343460581, -3.2886182473096295e-06, -3.439506419699579e-08, 0.03802747694990197, 0.04721180872730438, -0.032759156760566545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.0344263513042983e-09, 1.2821426411031797e-10, -1.2883921331658946e-11, -0.0010125191470531324, 0.0, -0.0010125191470531324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15477087293948397, 0.026640661495748903, 0.02958260163589951]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23559656211997387, 0.0, 0.03126175174443458, 0.0, 0.0872353188644252, -0.10734382767416505, 0.6484348713614603, -0.15000242499389568, 1.63495937295192, -0.2601321012863367, -2.325655742633186, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3047582135683344e-08, 5.1122738374509406e-11, -7.965204263503365e-11, -0.16007746291508265, 0.0, -0.11008746291508266, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5743205463471606, -0.15676160338141618, 0.16461014198475066]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022586119960855116, 0.0, 0.003898209034703265, 0.0, -0.06903506133813807, 0.007274883857641698, -3.131614457582905e-06, -3.584173605088328e-08, 0.03602683037127282, 0.04857358657746172, -0.030846041528253598, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3819454361363837e-09, 9.781020929107155e-11, -9.899040704328936e-12, -0.0008715976863739917, 0.0, -0.0008715976863739917, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15490847444557623, 0.026429352137859234, 0.02963229177013412]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23570915057465264, 0.0, 0.031540970928845294, 0.0, 0.08379641732109279, -0.10697830924524152, 0.6484197552576919, -0.15000285972089877, 1.6366636889471027, -0.25773627360033774, -2.327090837444873, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3170772975423448e-08, 5.4771638370600525e-11, -8.002292789821144e-11, -0.16014943596475342, 0.0, -0.11015943596475344, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5820719956248928, -0.1554453376796855, 0.16609403874555245]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022517690935752598, 0.0, 0.005584383688214324, 0.0, -0.06877803086664841, 0.0073103685784705955, -0.00030232207536811984, -8.694540062029453e-06, 0.03408631990365086, 0.047916553719978355, -0.02870189623374077, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.463816794802012e-09, 7.297799992182236e-11, -7.417705263555998e-12, -0.0014394609934156705, 0.0, -0.0014394609934156705, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15502898555464278, 0.026325314034613773, 0.029677935216036025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2358194659869966, 0.0, 0.03181854915846394, 0.0, 0.0803671521382902, -0.10661112535396337, 0.6484161242735884, -0.1500028609574039, 1.6382533810006044, -0.2554066397583302, -2.32841650797076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3278802346883926e-08, 5.745706941078317e-11, -8.02966204087127e-11, -0.16022208724964926, 0.0, -0.11023208724964927, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5898286661390962, -0.154129578309216, 0.16757998178875053]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002206308246879396, 0.0, 0.005551564592372899, 0.0, -0.06858530365605174, 0.00734367782556294, -7.261968206977143e-05, -2.4730102184566027e-08, 0.03179384107003346, 0.04659267684015055, -0.026513410517737597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.160587429209571e-09, 5.37086208036528e-11, -5.473850210025159e-12, -0.0014530256979164928, 0.0, -0.0014530256979164928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1551334102840702, 0.02631518740938986, 0.029718860863961503]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2359279954535198, 0.0, 0.03217028921619197, 0.0, 0.07694488220338354, -0.10624041162445719, 0.6483972110764464, -0.1500033694319681, 1.6397360439895363, -0.25314024043509153, -2.3296255061597675, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3403253279245123e-08, 5.94162643069729e-11, -8.049664267194146e-11, -0.1603169870954875, 0.0, -0.11032698709548751, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5975899625219483, -0.15281293508775598, 0.1690678207444054]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021705893304641262, 0.0, 0.007034801154560681, 0.0, -0.06844539869813324, 0.007414274590123609, -0.00037826394283997866, -1.016949128399572e-05, 0.02965325977863748, 0.045327986464774116, -0.024179963780147987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.489018647223943e-09, 3.918389792379487e-11, -4.000445264575243e-12, -0.0018979969167648638, 0.0, -0.0018979969167648638, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1552259276570421, 0.026332864429200485, 0.029756779113097417]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23603405254605822, 0.0, 0.03259618232668198, 0.0, 0.07352686979763058, -0.10586538433915092, 0.6483659200144282, -0.15000386058177903, 1.641110178012199, -0.25091267331839673, -2.330715621332648, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3531875170512757e-08, 6.083756754420044e-11, -8.064191314216345e-11, -0.16043288770673927, 0.0, -0.11044288770673928, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6053552688449194, -0.1514947659210473, 0.1705573698579185]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021211418507682865, 0.0, 0.008517862209800301, 0.0, -0.06836024811505906, 0.007500545706125172, -0.0006258212403663213, -9.822996218828881e-06, 0.027482680453252546, 0.04455134233389597, -0.021802303457615586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.572437825352757e-09, 2.8426064744550706e-11, -2.905409404439761e-12, -0.00231801222503555, 0.0, -0.00231801222503555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15530612645942193, 0.02636338333417354, 0.02979098227026193]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23613749610560622, 0.0, 0.03308120550237276, 0.0, 0.07011046049973069, -0.10548538707061689, 0.6483247101640359, -0.1500043808489106, 1.6423728979116206, -0.24869770796241325, -2.3316853207443002, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3658183034947667e-08, 6.18648421629815e-11, -8.074698818090143e-11, -0.16056407199672149, 0.0, -0.11057407199672148, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6131240172128315, -0.15017474753212554, 0.17204843860793395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020688711909601053, 0.0, 0.009700463513815516, 0.0, -0.06832818595799789, 0.007599945370680642, -0.0008241970078448187, -1.040534263119019e-05, 0.0252543979884313, 0.04429930711966955, -0.019393988233042676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5261572886982225e-09, 2.054549237562139e-11, -2.101500774759419e-12, -0.0026236857996440478, 0.0, -0.0026236857996440478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1553749673582423, 0.026400367778435477, 0.029821375000309066]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23623828589247167, 0.0, 0.03361081915501, 0.0, 0.06669324887728778, -0.10509973933716733, 0.6482729354688894, -0.15000500072272843, 1.6435218643866791, -0.24647506327902116, -2.3325323130044975, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.3780143809386652e-08, 6.260550923664847e-11, -8.082278475744289e-11, -0.1607054735129628, 0.0, -0.11071547351296278, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6208957313787304, -0.14885252901324492, 0.1735408530825426]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020157957373092943, 0.0, 0.010592273052744787, 0.0, -0.06834423244885818, 0.007712954668990981, -0.0010354939029294285, -1.2397476356777747e-05, 0.022979329501171496, 0.044452893667841706, -0.01693984520394583, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.4392154887796924e-09, 1.4813341473339263e-11, -1.5159315308292773e-12, -0.0028280303248260606, 0.0, -0.0028280303248260606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15543428331797998, 0.026444370377612537, 0.029848289492172976]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2363363583766248, 0.0, 0.034173608578940855, 0.0, 0.06327312385326757, -0.10470779835859415, 0.6482080378614357, -0.15000575155892074, 1.6445553163821707, -0.24423156960560957, -2.3332532328515225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.389743788551014e-08, 6.313866403826305e-11, -8.087736330003845e-11, -0.16085347614389675, 0.0, -0.11086347614389674, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6286700407631273, -0.14752756669020284, 0.17503446393720964]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001961449683062611, 0.0, 0.011255788478617176, 0.0, -0.06840250048040437, 0.007838819571463835, -0.0012979521490758517, -1.5016723846254982e-05, 0.020669039909832355, 0.04486987346823152, -0.014418396940501467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3458815224696854e-09, 1.0663096032291786e-11, -1.0915708519109832e-12, -0.002960052618679262, 0.0, -0.002960052618679262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15548618768793607, 0.026499246460841664, 0.02987221709334078]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23643099336676607, 0.0, 0.03469421185181706, 0.0, 0.05984790096871858, -0.1043104315541347, 0.6481438802900256, -0.15000576782732722, 1.6454561674367232, -0.24195538260858473, -2.333848554866085, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4000622752712e-08, 6.352202952571782e-11, -8.091661661968918e-11, -0.16098690369785373, 0.0, -0.11099690369785373, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6364465384993025, -0.14619820487101615, 0.17652909179012896]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018926998028252911, 0.0, 0.010412065457524012, 0.0, -0.06850445769097972, 0.007947336089188916, -0.0012831514282027091, -3.253681296559442e-07, 0.018017021091052285, 0.045523739940496875, -0.011906440291243128, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.063697344037216e-09, 7.667309749095432e-12, -7.850663930146427e-13, -0.002668551079139711, 0.0, -0.002668551079139711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555299547235063, 0.02658723638373394, 0.029892557058386414]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23652271196453423, 0.0, 0.03515773962880821, 0.0, 0.05641581825700634, -0.10390693159020216, 0.6480748055704058, -0.15000579359900207, 1.646223631204738, -0.23964349337978352, -2.3343118877718054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4088785496056662e-08, 6.379748942851932e-11, -8.094482545199182e-11, -0.16110189964081276, 0.0, -0.11111189964081275, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6442249777901686, -0.14486341586213425, 0.17802461808338896]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018343719553634555, 0.0, 0.00927055553982295, 0.0, -0.06864165423424481, 0.008069999278650892, -0.001381494392395647, -5.154334968332421e-07, 0.015349275360295204, 0.04623778457602429, -0.00926665811440934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.7632548668932437e-09, 5.509198056030061e-12, -5.641766460527954e-13, -0.002299918859180376, 0.0, -0.002299918859180376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15556878581732111, 0.026695780177638188, 0.02991052586519994]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23661146933644733, 0.0, 0.03557029373058668, 0.0, 0.05297528220725666, -0.10349625119698591, 0.6479889638264205, -0.15000583452581348, 1.6468621027972825, -0.23729549742437023, -2.3346345695499386, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4163582698440382e-08, 6.399532005352956e-11, -8.096508653387568e-11, -0.16120095737905724, 0.0, -0.11121095737905723, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.652005197388668, -0.14352236727052198, 0.17952095359697182]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017751474382620097, 0.0, 0.008251082035569336, 0.0, -0.0688107209949935, 0.00821360786432508, -0.0017168348797065424, -8.185362281814537e-07, 0.012769431850891818, 0.046959919108266024, -0.006453635562662793, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.4959440476744143e-09, 3.956612500204865e-12, -4.0522163767717417e-13, -0.00198115476488968, 0.0, -0.00198115476488968, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1556043919699879, 0.026820971832245542, 0.029926710271657424]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23669708826053368, 0.0, 0.035943342278203734, 0.0, 0.04952467547403197, -0.10307734121433192, 0.6478728897170454, -0.1500058983237358, 1.647376921751764, -0.2349111177422827, -2.3348069341938658, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.422705991441986e-08, 6.413735260262697e-11, -8.097963393393972e-11, -0.16128817196548875, 0.0, -0.11129817196548875, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6597870690639244, -0.14217422322784248, 0.18101801788998678]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017123784817269778, 0.0, 0.007460970952341179, 0.0, -0.06901213466449378, 0.008378199653079788, -0.0023214821875010673, -1.275958445887273e-06, 0.010296379089629937, 0.04768759364175058, -0.003447292878540187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2695443195895327e-09, 2.8406509819482697e-12, -2.9094800128094425e-13, -0.0017442917286302566, 0.0, -0.0017442917286302566, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15563743350512652, 0.026962880853590117, 0.02994128586029932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23677934705758447, 0.0, 0.036287857474012614, 0.0, 0.046062225877095436, -0.10264921892584082, 0.6477131469450845, -0.15000599582890653, 1.6477725990927503, -0.23248932388863772, -2.3348185532035006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4281202572003042e-08, 6.423930276379507e-11, -8.099007643301268e-11, -0.16136733756994978, 0.0, -0.11137733756994976, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6675704650788893, -0.14081802686696618, 0.18251572668050772]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016451759410160143, 0.0, 0.006890303916177645, 0.0, -0.06924899193873071, 0.008562445769821785, -0.0031948554392167293, -1.9501034147277403e-06, 0.00791354681972478, 0.04843587707290008, -0.0002323801927013149, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0828531516636509e-09, 2.0390032233618313e-12, -2.088499814589854e-13, -0.0015833120892204202, 0.0, -0.0015833120892204202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15566792029929752, 0.02712392721752595, 0.029954175810418638]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23685797996953833, 0.0, 0.03661240214024723, 0.0, 0.042585927378595415, -0.10221097253626045, 0.6474969974736152, -0.1500061389569156, 1.6480519616006473, -0.23002813860170257, -2.3346582431822736, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4327883417990788e-08, 6.431247136015673e-11, -8.099757112879815e-11, -0.16144130697709108, 0.0, -0.11145130697709106, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6753552401285802, -0.13945261784217633, 0.18401398482237932]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015726582390774649, 0.0, 0.006490893324692341, 0.0, -0.06952596997000039, 0.00876492779160739, -0.0043229894293870105, -2.862560181472778e-06, 0.005587250157937509, 0.049223705738702904, 0.0032062004245446305, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.336169197549133e-10, 1.4633719272332531e-12, -1.4989391570950886e-13, -0.0014793881428260666, 0.0, -0.0014793881428260666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1556955009938171, 0.027308180495797207, 0.029965162837432054]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23694933524983272, 0.0, 0.03692090864053692, 0.0, 0.03912129071603077, -0.10177092146965735, 0.6472930007813744, -0.1500061615655929, 1.648295555120316, -0.22763590586257, -2.334471431055151, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4369850617009422e-08, 6.436497859330579e-11, -8.100294957679762e-11, -0.16151137610962044, 0.0, -0.11152137610962043, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6831446155913444, -0.1380948171248175, 0.1855143891820218]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0018271056058877086, 0.0, 0.006170130005793677, 0.0, -0.0692927332512929, 0.00880102133206176, -0.004079933844816905, -4.5217354558235564e-07, 0.004871870393376985, 0.04784465478265147, 0.003736242542449828, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.393439803727027e-10, 1.0501446629811367e-12, -1.0756895998931617e-13, -0.0014013826505872567, 0.0, -0.0014013826505872567, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15578750925528548, 0.027156014347176394, 0.030008087192849576]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.237053967189467, 0.0, 0.0372963354970549, 0.0, 0.03569559470447108, -0.10133780502446062, 0.647145606078629, -0.1500068490818108, 1.648615891283768, -0.22540122350370165, -2.3344020542731534, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4469470337366317e-08, 6.440265635348307e-11, -8.100680905556043e-11, -0.161603800998119, 0.0, -0.11161380099811899, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6909424090665616, -0.13676552671915873, 0.1870187556621036]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002092638792685378, 0.0, 0.007508537130359608, 0.0, -0.06851392023119378, 0.00866232890393463, -0.0029478940549078287, -1.3750324358166132e-05, 0.006406723269042981, 0.04469364717736692, 0.001387535639947284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9923944071379195e-09, 7.53555203545504e-13, -7.718957525598696e-14, -0.00184849776997103, 0.0, -0.00184849776997103, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559558695043424, 0.02658580811317536, 0.030087329601636025]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23716700995790874, 0.0, 0.037649836222835624, 0.0, 0.032325875500911226, -0.1009200630475204, 0.6470807979878139, -0.15000685025973154, 1.6490814095551767, -0.2233481638897749, -2.334546378897069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4577118715249255e-08, 6.442969170117006e-11, -8.100957841537605e-11, -0.16169174016233745, 0.0, -0.11170174016233744, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6987512402818523, -0.13547965538677811, 0.1885282395881239]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022608553688346624, 0.0, 0.007070014515614552, 0.0, -0.06739438407119712, 0.008354839538804322, -0.0012961618163012563, -2.355841452901972e-08, 0.009310365428170915, 0.04106119227853482, -0.002886492478307489, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.152967557658776e-09, 5.407069537399379e-13, -5.538719631250855e-14, -0.0017587832843689315, 0.0, -0.0017587832843689315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15617662430581555, 0.025717426647612125, 0.030189678520405758]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23728689330894384, 0.0, 0.03795790936320141, 0.0, 0.029020474061616484, -0.10052151769536022, 0.6470680377296627, -0.15000685277017245, 1.6497464498611834, -0.22147163543840437, -2.334946160310273, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4673729038960226e-08, 6.444909010757307e-11, -8.101156549862678e-11, -0.1617673943784295, 0.0, -0.11177739437842947, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.70657252045747, -0.13424713745698122, 0.1900434252055515]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023976670207022694, 0.0, 0.006161462807315785, 0.0, -0.06610802878589483, 0.007970907043203596, -0.00025520516302466657, -5.020881834384054e-08, 0.013300806120131195, 0.037530569027410705, -0.007995628264084769, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.932206474219441e-09, 3.8796812806002264e-13, -3.9741665014556314e-14, -0.0015130843218406002, 0.0, -0.0015130843218406002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15642560351235346, 0.024650358595937956, 0.030303712348552104]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2374121141416874, 0.0, 0.038220098168286296, 0.0, 0.025781506686477353, -0.10014362129209642, 0.6470679389350972, -0.15000685411633266, 1.650638507477114, -0.21975285693195934, -2.335610003136367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4753930626889778e-08, 6.446300857988708e-11, -8.101299124839965e-11, -0.1618302017635634, 0.0, -0.11184020176356341, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7144066493666529, -0.1330728044374648, 0.19156444142263296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002504416654871073, 0.0, 0.00524377610169774, 0.0, -0.06477934750278262, 0.007557928065276126, -1.9758913116152605e-06, -2.6923203975585464e-08, 0.01784115231861218, 0.03437557012890061, -0.013276856521883288, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6040317585910414e-09, 2.783694462801319e-13, -2.851499545743918e-14, -0.001256147702678704, 0.0, -0.001256147702678704, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15668257818365813, 0.02348666039032816, 0.03042032434162919]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23754133491132326, 0.0, 0.03847602485573955, 0.0, 0.022606985453966513, -0.09978642815976205, 0.6470670882939497, -0.15000687415215558, 1.6517609984550816, -0.21817001745941372, -2.3365256386976423, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.483570033066957e-08, 6.447299503429827e-11, -8.101401422153571e-11, -0.1618912927508484, 0.0, -0.11190129275084838, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7222532819136971, -0.13195718973941656, 0.1930910971492343]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002584415392717131, 0.0, 0.0051185337490651395, 0.0, -0.06349042465021679, 0.00714386264668751, -1.701282295076455e-05, -4.007164584183582e-07, 0.022449819559353747, 0.03165678945091258, -0.01831271122550522, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6353940755958975e-09, 1.997290882238085e-13, -2.0459462721256192e-14, -0.0012218197456995996, 0.0, -0.0012218197456995996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15693265094088418, 0.022312293960964687, 0.030533114532027002]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23767345321292993, 0.0, 0.038734946213881974, 0.0, 0.019492485268102374, -0.09944917744521968, 0.6470664531591849, -0.15000687855370295, 1.65309953079513, -0.2167026156583162, -2.337669148140485, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.4911072929821587e-08, 6.448016021612105e-11, -8.101474819591653e-11, -0.16195300519398, 0.0, -0.11196300519397999, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7301116125858156, -0.13089773033098567, 0.19462300348287703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0026423660321332368, 0.0, 0.005178427162848446, 0.0, -0.06229000371728278, 0.006745014290847303, -1.2702695296726047e-05, -8.803094755277722e-08, 0.026770646800965442, 0.029348036021950696, -0.022870188856858587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5074519830402969e-09, 1.433036364556565e-13, -1.4679487616338017e-14, -0.0012342488626322355, 0.0, -0.0012342488626322355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.157166613442369, 0.021189188168617423, 0.030638126672854364]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23780769215451916, 0.0, 0.0389996394025386, 0.0, 0.016432420878018893, -0.09913048614760898, 0.6470658583478706, -0.15000688598982573, 1.6546303353034566, -0.21533310819171628, -2.339011159476304, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.497900534791497e-08, 6.448530113220493e-11, -8.101527481273555e-11, -0.16201602964371062, 0.0, -0.11202602964371061, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7379806018355602, -0.12989010105571003, 0.19615967910280058]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002684778831784691, 0.0, 0.005293863773132512, 0.0, -0.0612012878016696, 0.006373825952213957, -1.1896226285365325e-05, -1.4872245561903305e-07, 0.030616090166535246, 0.02739014933199821, -0.026840226716372956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.358648361867689e-09, 1.028183216775496e-13, -1.0532336380419762e-14, -0.0012604889946123128, 0.0, -0.0012604889946123128, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15737978499489297, 0.020152585505512726, 0.030733512398470792]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23793437483494798, 0.0, 0.039270257562083404, 0.0, 0.013432862873598447, -0.0988351530548976, 0.647064570738704, -0.15000689693617442, 1.656305693308499, -0.21392450273020136, -2.3405036724653425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.503775002572154e-08, 6.448898965165522e-11, -8.101565265161553e-11, -0.16208045904717164, 0.0, -0.11209045904717163, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7458615266003031, -0.1289383004906567, 0.1977015609680967]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002533653608576254, 0.0, 0.005412363190896057, 0.0, -0.059991160088408914, 0.005906661854227875, -2.5752183329179606e-05, -2.1892697368712006e-07, 0.03350716010084859, 0.028172109230298364, -0.029850259780770865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.17489355613138e-09, 7.377038900589769e-14, -7.556777599618792e-15, -0.0012885880692204267, 0.0, -0.0012885880692204267, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15761849529485703, 0.019036011301066927, 0.030837637305922764]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2380558716550121, 0.0, 0.03951653287050345, 0.0, 0.010473274854080988, -0.09855788135358552, 0.6470644615177139, -0.15000689796039457, 1.6580408024392035, -0.21251563550229896, -2.342058507916928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5085121274870974e-08, 6.449163609424899e-11, -8.101592374397914e-11, -0.16213816805467568, 0.0, -0.11214816805467567, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7537513492688143, -0.12802391051501136, 0.19924724590482906]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002429936401282779, 0.0, 0.004925506168400851, 0.0, -0.05919176039034919, 0.005545434026241498, -2.184419803805401e-06, -2.0484403071975876e-08, 0.03470218261409181, 0.02817734455804772, -0.031096709031709947, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.474249829886715e-10, 5.2928851875454684e-14, -5.421847272273831e-15, -0.0011541801500808344, 0.0, -0.0011541801500808344, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15779645337022263, 0.018287799512906544, 0.030913698734646916]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2381718284897342, 0.0, 0.039733785868782165, 0.0, 0.007532623497585709, -0.09829249249669303, 0.6470643088916381, -0.15000689984980092, 1.6597546799540908, -0.21113495953793207, -2.3435912519162017, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.512242295238432e-08, 6.449353486309206e-11, -8.101611824731938e-11, -0.16218795818194207, 0.0, -0.11219795818194207, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7616468507506395, -0.1271267830646287, 0.20079529440514626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002319136694441705, 0.0, 0.004345059965574409, 0.0, -0.05881302712990557, 0.0053077771378497755, -3.052521516526812e-06, -3.7788126825408766e-08, 0.03427755029774429, 0.027613519287337573, -0.030654879985479278, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.460335502669647e-10, 3.797537686151419e-14, -3.8900668048539624e-15, -0.0009958025453278953, 0.0, -0.0009958025453278953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15791002963650524, 0.017942549007652717, 0.03096097000634401]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23828369286619938, 0.0, 0.039925141323472885, 0.0, 0.0045970621033342715, -0.09803369734145027, 0.6470641036783265, -0.15000690132523006, 1.6613947498944452, -0.20978832455180396, -2.3450475299705666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5151705399777354e-08, 6.449489718955172e-11, -8.101625779938419e-11, -0.16223083521562465, 0.0, -0.11224083521562464, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7695456859017533, -0.12623309018796203, 0.20234471492147338]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022372875293038717, 0.0, 0.0038271090938143387, 0.0, -0.05871122788502875, 0.005175903104855141, -4.104266233019173e-06, -2.9508582673796067e-08, 0.03280139880709113, 0.026932699722562, -0.02912556108730081, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.856489478606596e-10, 2.7246529193296314e-14, -2.791041296221239e-15, -0.000857540673651474, 0.0, -0.000857540673651474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15797670302227584, 0.017873857533333662, 0.03098841032654215]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23839294696517774, 0.0, 0.04009528952432453, 0.0, 0.0016595941118280485, -0.0977775038604349, 0.6470638837936128, -0.15000690219464743, 1.6629371480870907, -0.20846923147196997, -2.346403193394028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5174798827901478e-08, 6.449587462916352e-11, -8.101635792497284e-11, -0.16226824858306993, 0.0, -0.11227824858306992, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7774464335341716, -0.12533591802884647, 0.20389495354478585]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021850819795672825, 0.0, 0.0034029640170327993, 0.0, -0.058749359830124456, 0.0051238696203072765, -4.3976942732905375e-06, -1.7388347267085484e-08, 0.030847963852907404, 0.026381861596679806, -0.027113268469225602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.618685624824516e-10, 1.9548792235953357e-14, -2.0025117731254598e-15, -0.0007482673489057328, 0.0, -0.0007482673489057328, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1580149526483658, 0.017943443182311315, 0.0310047724662496]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23850051047257373, 0.0, 0.04027970693617502, 0.0, -0.0012823676859697927, -0.09752114094101796, 0.6470606718189964, -0.15000691839485097, 1.6643783513862864, -0.20716813946299342, -2.3476538279579793, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5195422777408557e-08, 6.449657592044633e-11, -8.101642976287448e-11, -0.16231089901882165, 0.0, -0.11232089901882164, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.785348365437576, -0.12443317674624349, 0.20544575571273305]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021512701479197067, 0.0, 0.0036883482370097713, 0.0, -0.05883923595595682, 0.005127258388338892, -6.423949232822042e-05, -3.240040706741658e-07, 0.028824065983915008, 0.02602184017953096, -0.025012691279028, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.1247899014155206e-10, 1.4025825656271501e-14, -1.436758032719708e-15, -0.0008530087150344877, 0.0, -0.0008530087150344877, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15803863806808827, 0.018054825652059632, 0.031016043358944305]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2385791089118535, 0.0, 0.04070945381364533, 0.0, -0.004191103500659208, -0.09720707882576833, 0.6469858768993139, -0.15001773058842927, 1.6657191925305468, -0.20576797878081982, -2.3487186052535827, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5201251174111327e-08, 6.44970790803519e-11, -8.101648130485284e-11, -0.16242438576830404, 0.0, -0.11243438576830402, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7930621885287543, -0.12355046813332551, 0.20695150126858516]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001571968785595383, 0.0, 0.008594937549406611, 0.0, -0.05817471629378831, 0.006281242304992622, -0.0014958983936505762, -0.00021624387156589654, 0.026816822885207803, 0.028003213643471962, -0.021295545912070956, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1656793405538502e-10, 1.0063198111297377e-14, -1.0308395672842973e-15, -0.002269734989647506, 0.0, -0.002269734989647506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15427646182356555, 0.017654172258359645, 0.030114911117042422]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23855916294368004, 0.0, 0.0412605141634229, 0.0, -0.0068981787135183725, -0.09652119380136231, 0.6467647590299413, -0.15018230247866987, 1.6668591514487319, -0.20375379571193902, -2.3493944102048627, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.520041657304294e-08, 6.449744008560816e-11, -8.101651828505279e-11, -0.16256674648453034, 0.0, -0.11257674648453031, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7999681252670063, -0.12277785928491476, 0.20826629303660676]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003989193634688676, 0.0, 0.01102120699555136, 0.0, -0.05414150425718327, 0.013717700488120417, -0.004422357387449625, -0.0032914378048123916, 0.02279917836370264, 0.040283661377615854, -0.013516099025603395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6692021367754102e-11, 7.220105125156111e-15, -7.39603998989827e-16, -0.0028472143245259532, 0.0, -0.0028472143245259532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1381187347650393, 0.015452176968215032, 0.026295835360431875]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23850003676858564, 0.0, 0.04187740545815657, 0.0, -0.009298877520243078, -0.09520415745930672, 0.6463696843368351, -0.150681696800619, 1.667811871249101, -0.20089212698893252, -2.3496485561515863, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.519713351460739e-08, 6.449769909835557e-11, -8.101654481748601e-11, -0.1627205903254521, 0.0, -0.11273059032545207, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8056272364561627, -0.1222070616239461, 0.2093269206922065]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011825235018879466, 0.0, 0.012337825894673426, 0.0, -0.04801397613449412, 0.026340726841112105, -0.007901493862125138, -0.009987886438982605, 0.019054396007381996, 0.057233374460130076, -0.005082918934475392, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.566116871097933e-11, 5.180254948248252e-15, -5.306486645214548e-16, -0.0030768768184353825, 0.0, -0.0030768768184353825, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11318222378312782, 0.011415953219373456, 0.021212553111994412]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23842679292425567, 0.0, 0.04256808962752821, 0.0, -0.01139874574971478, -0.09318967368164892, 0.6458035848140842, -0.15154195489827857, 1.668636637528928, -0.19712033553124284, -2.3495261346015544, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5192838108900896e-08, 6.449788493386587e-11, -8.101656385389674e-11, -0.16288298692115025, 0.0, -0.11289298692115021, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8099905857784119, -0.12186895257894735, 0.2101335633174297]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0014648768865993826, 0.0, 0.01381368338743295, 0.0, -0.04199736458943404, 0.04028967555315601, -0.011321990455017831, -0.017205161953191352, 0.016495325596539833, 0.07543582915379365, 0.002448431000639662, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.590811412986605e-11, 3.716710206194925e-15, -3.807282146549976e-16, -0.003247931913962711, 0.0, -0.003247931913962711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08726698644498368, 0.00676218089997487, 0.016132852504464196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2383494442874209, 0.0, 0.04332166618809267, 0.0, -0.013280649876254188, -0.09057434615366274, 0.6450855883832823, -0.1526339767004589, 1.6694095146016994, -0.19243266962334843, -2.349106357244482, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5188463195453017e-08, 6.449801826642675e-11, -8.10165775120736e-11, -0.163051818405543, 0.0, -0.11306181840554297, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8132209317535184, -0.12176093203240787, 0.2107206514979358]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0015469727366958026, 0.0, 0.01507153121128907, 0.0, -0.03763808253078816, 0.052306550559723705, -0.01435992861603611, -0.021840436043606574, 0.015457541455426596, 0.09375331815788829, 0.008395547141451704, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.749826895755961e-11, 2.6666512174467505e-15, -2.7316353720508656e-16, -0.003376629687855254, 0.0, -0.003376629687855254, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06460691950213117, 0.0021604109307896135, 0.011741763610122628]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23827296493891417, 0.0, 0.04412842666334804, 0.0, -0.015061605238410611, -0.08754552498712952, 0.6442408202105113, -0.15373746629192575, 1.670207988872258, -0.18684153363787823, -2.348477000601857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5184455002726955e-08, 6.449811392937823e-11, -8.101658731145155e-11, -0.1632270574224112, 0.0, -0.11323705742241116, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8155615758590412, -0.12186645396733613, 0.21113490528649567]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0015295869701341643, 0.0, 0.016135209505107374, 0.0, -0.03561910724312845, 0.0605764233306643, -0.01689536345542092, -0.02206979182933732, 0.015969485411172622, 0.11182271970940424, 0.012587132852490938, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.016385452123401e-11, 1.9132590297737796e-15, -1.9598755903602465e-16, -0.0035047803373640324, 0.0, -0.0035047803373640324, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04681288211045612, -0.002110438698565111, 0.008285075771197187]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23821134778076403, 0.0, 0.0448364731781252, 0.0, -0.016889958737878713, -0.08440096834062265, 0.6433084126288573, -0.15454299155870438, 1.6710903612932089, -0.18048667400502655, -2.3477300060980086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181160497437817e-08, 6.449818256530264e-11, -8.10165943422561e-11, -0.16337889967638167, 0.0, -0.11338889967638162, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8173530249748235, -0.12214429167077728, 0.21143960217578514]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001232343163002948, 0.0, 0.014160930295543158, 0.0, -0.03656706998936207, 0.06289113293013736, -0.01864815163307969, -0.016110505335572813, 0.017647448419015683, 0.1270971926570334, 0.014939890076973304, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.589010578279081e-11, 1.3727184880824241e-15, -1.4061609108534658e-16, -0.0030368450794091085, 0.0, -0.0030368450794091085, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.035828982315646386, -0.005556754068823113, 0.006093937785789431]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23816918364416448, 0.0, 0.045426737980294375, 0.0, -0.018783030844892502, -0.08126076042368698, 0.6423803972129323, -0.15483644604411745, 1.6721930323636371, -0.17340911869362247, -2.347101555430393, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5178591121868942e-08, 6.449823180998024e-11, -8.101659938668511e-11, -0.16350338146093743, 0.0, -0.11351338146093737, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8187836578021773, -0.12260880597306174, 0.21167200475270245]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0008432827319910139, 0.0, 0.011805296043383625, 0.0, -0.0378614421402758, 0.06280415833871351, -0.0185603083185006, -0.005869089708261664, 0.022053421408565546, 0.1415511062280818, 0.012569013352308783, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.138751137752884e-11, 9.84893551928493e-16, -1.0088858021312673e-16, -0.002489635691115091, 0.0, -0.002489635691115091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0286126565470761, -0.009290286045689308, 0.004648051538346131]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2381606376727112, 0.0, 0.04596455260326306, 0.0, -0.020678581718467304, -0.07815162318287758, 0.6415906908126949, -0.15480384554402285, 1.673678229297357, -0.16574853083316782, -2.3469079863635804, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.51766382094244e-08, 6.449826714189814e-11, -8.101660300594388e-11, -0.16361614125166069, 0.0, -0.11362614125166062, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.819985722640758, -0.12329356920461947, 0.21186051932212996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00017091942906556667, 0.0, 0.010756292459373852, 0.0, -0.037911017471496056, 0.06218274481618803, -0.015794128004746506, 0.0006520100018918892, 0.029703938674400805, 0.15321175720909316, 0.0038713813362545608, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.905824889083861e-11, 7.0663835811013015e-16, -7.238517540968666e-17, -0.0022551958144651765, 0.0, -0.0022551958144651765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02404129677161392, -0.013695264631154506, 0.0037702913885501554]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23806147948840892, 0.0, 0.04647860013460228, 0.0, -0.02235478850113412, -0.07514508336845704, 0.6404631419864955, -0.15465598689688642, 1.6757765296721898, -0.1569745300262023, -2.3469703728981663, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5175215070786495e-08, 6.44982924917369e-11, -8.101660560267767e-11, -0.16373127195464066, 0.0, -0.1137412719546406, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8210807417797273, -0.12437070950815352, 0.21203705224403468]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001983163686045729, 0.0, 0.010280950626784467, 0.0, -0.033524135653336305, 0.060130796288410636, -0.02255097652398981, 0.002957172942728542, 0.04196600749665625, 0.17548001613931075, -0.0012477306917181514, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8462772758145038e-11, 5.069967750530571e-16, -5.1934675994164054e-17, -0.0023026140595994327, 0.0, -0.0023026140595994327, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021900382779387335, -0.021542806070680966, 0.003530658438094395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23797959707941402, 0.0, 0.046931317191207654, 0.0, -0.02383688585248512, -0.07222780036972551, 0.6390173175279479, -0.15446941068972608, 1.6784162134219174, -0.14781083462705305, -2.3472429999802804, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5174189127501115e-08, 6.449831067966389e-11, -8.101660746577399e-11, -0.16383652444638458, 0.0, -0.11384652444638452, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8221304829610446, -0.1257971889081446, 0.2122128067049146]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0016376481798981318, 0.0, 0.009054341132107435, 0.0, -0.029641947027019947, 0.058345659974630724, -0.028916489170951118, 0.003731524143206696, 0.05279367499455243, 0.18327390798298504, -0.005452541642283912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.0518865707617408e-11, 3.6375853978477043e-16, -3.726192610528667e-17, -0.002105049834878387, 0.0, -0.002105049834878387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020994823626345215, -0.028529587999821585, 0.0035150892175981967]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2379150761340047, 0.0, 0.04737018515739623, 0.0, -0.02517980150653813, -0.06938971432860813, 0.6373425329698833, -0.1542609685174874, 1.6814880823797178, -0.13865253310324024, -2.347706278807634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5173537493181488e-08, 6.449832372908948e-11, -8.101660880250421e-11, -0.1639469139318512, 0.0, -0.11395691393185114, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8231723374508351, -0.1275052672498991, 0.21239307830059997]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001290418908186609, 0.0, 0.008777359323771534, 0.0, -0.02685831308106021, 0.05676172082234758, -0.03349569116129063, 0.004168843444773246, 0.06143737915600869, 0.18316603047625635, -0.009265576547071096, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3032686392531367e-11, 2.609885119325376e-16, -2.6734604527142748e-17, -0.0022077897093326806, 0.0, -0.0022077897093326806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020837089795807916, -0.034161566835090425, 0.0036054319137071985]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23787405006059295, 0.0, 0.047810168675776914, 0.0, -0.026399774380870576, -0.06662749933133728, 0.6355376342844792, -0.154001502186486, 1.684967560690614, -0.1295413982008961, -2.3484404404396653, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5173189613919042e-08, 6.449833309175656e-11, -8.101660976157868e-11, -0.16406437424755904, 0.0, -0.11407437424755898, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8242373400103982, -0.12947397825626605, 0.2125833765711633]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0008205214682347839, 0.0, 0.00879967036761359, 0.0, -0.024399457486648898, 0.055244299945417026, -0.03609797370808157, 0.005189326620028344, 0.06958956621792602, 0.18222269804688251, -0.014683232640630409, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.957585248958934e-12, 1.872533414111482e-16, -1.9181489473448015e-17, -0.0023492063141566997, 0.0, -0.0023492063141566997, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02130005119126188, -0.039374220127338676, 0.00380596541126669]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2374581396269104, 0.0, 0.04823439371059147, 0.0, -0.027045718612566442, -0.06398212757705854, 0.6319647567973641, -0.15392700155081146, 1.68920989157025, -0.12123587201047556, -2.348276301633426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.517302528097271e-08, 6.449833980925964e-11, -8.101661044969364e-11, -0.1641809831975611, 0.0, -0.11419098319756106, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8253091768746338, -0.13212409494255709, 0.21279720860204598]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00831820867365106, 0.0, 0.008484500696291142, 0.0, -0.01291888463391731, 0.05290743508557498, -0.07145754974230295, 0.001490012713491127, 0.08484661759271872, 0.16611052380841104, 0.003282776124780609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.2866589266002716e-12, 1.3435006174056693e-16, -1.3762299019436379e-17, -0.002332179000041554, 0.0, -0.002332179000041554, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021436737284713306, -0.05300233372582037, 0.004276640617653853]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23706888405965348, 0.0, 0.04859973188675891, 0.0, -0.027190200554325326, -0.06146501731306316, 0.6266060602521701, -0.15386473206754722, 1.6942056046937428, -0.11337051303028078, -2.3471775340453296, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.517295099266099e-08, 6.449834462891605e-11, -8.101661094340084e-11, -0.16428185704623385, 0.0, -0.11429185704623379, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8264496060958886, -0.13545379109172787, 0.21304459499835376]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007785111345138132, 0.0, 0.007306763523348839, 0.0, -0.002889638835177658, 0.05034220527990754, -0.1071739309038792, 0.0012453896652845212, 0.09991426246985398, 0.15730717960389543, 0.021975351761930148, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4857662344209342e-12, 9.639312814930264e-17, -9.874143811283036e-18, -0.002017476973454699, 0.0, -0.002017476973454699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02280858442509562, -0.06659392298341583, 0.004947727926155823]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2364189364729939, 0.0, 0.04890294342037375, 0.0, -0.026432970767199665, -0.0591440934147112, 0.6182221200721095, -0.1540127029734837, 1.7004979970183713, -0.1096205182058791, -2.344551700842407, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5172944750529145e-08, 6.449834808691e-11, -8.101661129762465e-11, -0.16436559740764473, 0.0, -0.11437559740764466, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8277772761963251, -0.13983246099066274, 0.2133675786531118]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012998951733192042, 0.0, 0.00606423067229676, 0.0, 0.015144595742513192, 0.04641847796703924, -0.16767880360121257, -0.0029594181187297362, 0.12584784649256986, 0.07499989648803354, 0.05251666405845887, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.248426368952391e-13, 6.915987905083939e-17, -7.08447632230504e-18, -0.001674807228217531, 0.0, -0.001674807228217531, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026553402008731877, -0.0875733979786977, 0.0064596730951603076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23580295444099028, 0.0, 0.04934239882620914, 0.0, -0.024897732969668022, -0.057058020377147134, 0.6067753493787232, -0.1538129805369134, 1.7087895434861677, -0.10623590542088146, -2.341040747638808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5174456504221552e-08, 6.449835056799145e-11, -8.101661155162894e-11, -0.1644947993661789, 0.0, -0.11450479936617881, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8293274301905146, -0.14517311478526065, 0.2137953855192022]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012319640640072228, 0.0, 0.00878910811670765, 0.0, 0.030704755950632868, 0.041721460751281324, -0.2289354138677256, 0.00399444873140639, 0.16583092935592814, 0.06769225569995285, 0.07021906407197492, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.023507384810748e-11, 4.962162893567506e-17, -5.080085901064169e-18, -0.0025840391706830825, 0.0, -0.0025840391706830825, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.031003079883789197, -0.10681307589195818, 0.008556137321808741]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23531781741836325, 0.0, 0.04983347587617086, 0.0, -0.022839426765270475, -0.05513815963894009, 0.5927680916526522, -0.1531334330047597, 1.7196326040679475, -0.10266860067966216, -2.3376411447015193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5176339885549304e-08, 6.449835234813704e-11, -8.101661173380223e-11, -0.16464051629185814, 0.0, -0.11465051629185806, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8311073833783786, -0.15130866284646668, 0.21434475052403132]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009702740452540687, 0.0, 0.009821540999234416, 0.0, 0.04116612408795093, 0.038397214764140895, -0.2801451545214198, 0.013590950643073675, 0.2168612116355932, 0.07134609482438609, 0.0679920587457763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.7667626555076394e-11, 3.5602911785109e-17, -3.6434660020143004e-18, -0.0029143385135850276, 0.0, -0.0029143385135850276, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03559906375728162, -0.12271096122412083, 0.010987300096582183]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23473045900067332, 0.0, 0.0502962743123573, 0.0, -0.020390193726895968, -0.05337273434235524, 0.575683733725786, -0.15313343308732288, 1.733838455682556, -0.10266860069378002, -2.334634603625283, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5178088779464382e-08, 6.449835362536366e-11, -8.101661186447427e-11, -0.16477682090060475, 0.0, -0.11478682090060466, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8331038549726266, -0.1581317435157095, 0.21504386876240889]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.011747168353798517, 0.0, 0.009255968723728856, 0.0, 0.04898466076749011, 0.0353085059316969, -0.34168715853732584, -1.6512636639987033e-09, 0.2841170322921703, -2.8235715154867336e-10, 0.06013082152473037, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.4977878301545016e-11, 2.5544532447867728e-17, -2.613440742159875e-18, -0.0027260921749320934, 0.0, -0.0027260921749320934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03992943188495944, -0.13646161338485627, 0.013982364767551315]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2342351437550596, 0.0, 0.05083789729123829, 0.0, -0.01778349954850689, -0.051661459542758144, 0.5548785545232533, -0.1531334344914775, 1.7533075547834913, -0.10266860088559523, -2.3332438193849327, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5179569068564018e-08, 6.44983545417529e-11, -8.101661195819112e-11, -0.1649385691619342, 0.0, -0.1149485691619341, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8352980575585811, -0.1655064280638513, 0.21595217347354215]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.009906304912274158, 0.0, 0.010832459577619765, 0.0, 0.052133883567781564, 0.034225495991941975, -0.41610358405065223, -2.8083092485468662e-08, 0.3893819820187061, -3.836304276365092e-09, 0.02781568480700653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.960578199273016e-11, 1.8327784758406958e-17, -1.8743369906902994e-18, -0.0032349652265889067, 0.0, -0.0032349652265889067, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04388405171909033, -0.1474936909628363, 0.018166094222665435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23381650999693915, 0.0, 0.051390108434094924, 0.0, -0.01524607457681518, -0.049946159363868745, 0.5300078473293647, -0.15313343460470902, 1.7793145473732213, -0.10266860092263921, -2.3342904399845685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.518072380933283e-08, 6.449835519924594e-11, -8.101661202541169e-11, -0.1651018921065664, 0.0, -0.11511189210656629, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8376706499783856, -0.17331757146111232, 0.21711321936914968]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.008372675162409209, 0.0, 0.011044222857132588, 0.0, 0.05074849943383417, 0.03430600357778794, -0.49741414387777233, -2.26463025438855e-09, 0.5201398517945974, -7.408795356207471e-10, -0.020932411992714055, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.309481537626665e-11, 1.314986072273927e-17, -1.344411537600275e-18, -0.0032664588926437027, 0.0, -0.0032664588926437027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04745184839608857, -0.15622286794522044, 0.023220917912150432]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23345088197957442, 0.0, 0.05192894462552559, 0.0, -0.01292348702909611, -0.04821513247271113, 0.5012680208527509, -0.15313343470676302, 1.8113110706630198, -0.10266860095693565, -2.3378071051887663, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.518155376974784e-08, 6.44983556709859e-11, -8.101661207363034e-11, -0.165259728597969, 0.0, -0.11526972859796888, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8402036571721596, -0.18147345907425377, 0.2185550129741736]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.007312560347294455, 0.0, 0.010776723828613345, 0.0, 0.04645175095438142, 0.034620537823152275, -0.5747965295322759, -2.041080107093845e-09, 0.6399304657959682, -6.859288599761405e-10, -0.07033330408395821, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6599208300198337e-11, 9.434799262581346e-18, -9.643728371619019e-19, -0.0031567298280519157, 0.0, -0.0031567298280519157, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05066014387548029, -0.163117752262829, 0.028835872100478412]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23314386669916767, 0.0, 0.05255343483012553, 0.0, -0.0108841903113439, -0.046493324689089524, 0.46923515101853935, -0.15313343514670638, 1.848409897263824, -0.10266860117192815, -2.3433269377044916, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181860428729818e-08, 6.449835600944807e-11, -8.101661210825402e-11, -0.16544020891234335, 0.0, -0.11545020891234323, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8428735195309917, -0.1899026165046443, 0.22029552567455943]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00614030560813504, 0.0, 0.012489804091998779, 0.0, 0.04078593435504418, 0.03443615567243201, -0.6406573966842309, -8.798867167755675e-09, 0.7419765320160882, -4.299849827634146e-09, -0.11039665031450849, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.133179639540851e-12, 6.769243284460647e-18, -6.924738494794126e-19, -0.003609606287486756, 0.0, -0.003609606287486756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.053397247176640815, -0.16858314860781032, 0.034810254007716486]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23293973354060657, 0.0, 0.05314069301109785, 0.0, -0.009150408764237766, -0.044842142439771186, 0.4346039901035703, -0.15313343516988628, 1.889800634715085, -0.10266860117979193, -2.3504231787452925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181916179127113e-08, 6.449835625228658e-11, -8.10166121331093e-11, -0.16560718128925372, 0.0, -0.11561718128925362, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.845637805889954, -0.198553083440997, 0.22234215395398113]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0040826631712220385, 0.0, 0.011745163619446351, 0.0, 0.034675630942122705, 0.03302364498636672, -0.692623218299381, -4.635981512571724e-10, 0.8278147490252198, -1.5727550197246543e-10, -0.14192482081601693, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1150079458897562e-12, 4.856770027430041e-18, -4.971054858383957e-19, -0.0033394475382077637, 0.0, -0.0033394475382077637, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05528572717924705, -0.17300933872705415, 0.040932565588433834]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23279804905040558, 0.0, 0.05372844962140822, 0.0, -0.0077443522920570594, -0.04330433192886994, 0.3977747621082179, -0.15313343526907058, 1.9348246192529166, -0.10266860121426051, -2.3587334030492477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5181737703118508e-08, 6.449835642651963e-11, -8.101661215094934e-11, -0.1657718609541812, 0.0, -0.11578186095418111, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8484756015148152, -0.2073803625423391, 0.22470173716169797]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002833689804020057, 0.0, 0.011755132206207448, 0.0, 0.028121129443614123, 0.030756210218024965, -0.7365845599070487, -1.983686066882044e-09, 0.900479690756632, -6.893716284635601e-10, -0.16620448607910532, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.5695201720969874e-12, 3.4846611586276046e-18, -3.5680070773748413e-19, -0.0032935932985496542, 0.0, -0.0032935932985496542, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.056755912497224295, -0.17654558202684184, 0.04719166415433677]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2326552652305152, 0.0, 0.05434499904321462, 0.0, -0.006693863527023758, -0.04187730495939191, 0.35889486257368275, -0.15313343544644742, 1.9827844184276913, -0.10266860127955095, -2.3677035488067246, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.518120591159894e-08, 6.449835655151967e-11, -8.101661216374578e-11, -0.16594329331115923, 0.0, -0.11595329331115914, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8513995132945418, -0.21634203900043433, 0.22738767564680049]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0028556763978078627, 0.0, 0.01233098843612786, 0.0, 0.021009775300666014, 0.02854053938956064, -0.7775979906907025, -3.547536809948411e-09, 0.9591959834954956, -1.3058087762366285e-09, -0.17940291514953735, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.063583039137835e-11, 2.5000007143805996e-18, -2.559288112965856e-19, -0.0034286471395606434, 0.0, -0.0034286471395606434, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05847823559453136, -0.1792335291619046, 0.053718769702050216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23251758809107106, 0.0, 0.0549582751956504, 0.0, -0.00601734554683553, -0.0405522569370272, 0.31809257390668827, -0.1531334359443836, 2.0327844171195446, -0.1026686014353254, -2.3767441880120774, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5179780981592767e-08, 6.449835664120467e-11, -8.101661217292722e-11, -0.1661156753550082, 0.0, -0.11612567535500813, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8544229099179355, -0.22540313130934725, 0.2304134636836119]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0027535427888824315, 0.0, 0.012265523048715603, 0.0, 0.013530359603764561, 0.02650096044729424, -0.8160457733398896, -9.958724103706892e-09, 0.9999999738370651, -3.115488969568862e-09, -0.18081278410705795, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8498600123397965e-11, 1.7937001371996373e-18, -1.8362862728988284e-19, -0.003447640876979839, 0.0, -0.003447640876979839, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.060467932467873506, -0.18122184617825832, 0.06051576073622836]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23239670495160478, 0.0, 0.055571104871543896, 0.0, -0.005717475057439239, -0.03932145259086932, 0.27558216389923157, -0.15313343603283744, 2.082784416922882, -0.10266860146033742, -2.385199575622597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.517808256126718e-08, 6.449835670554005e-11, -8.101661217951566e-11, -0.16629102179167646, 0.0, -0.11630102179167638, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8575524568739482, -0.23453626960527574, 0.23379357321385966]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002417662789326012, 0.0, 0.012256593517869929, 0.0, 0.005997409787925838, 0.024616086923157705, -0.8502082001491336, -1.7690765238712583e-09, 0.999999996066756, -5.002404001877771e-10, -0.16910775221039545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.396840651174699e-11, 1.2867077399564448e-18, -1.317689186637689e-19, -0.0035069287333649776, 0.0, -0.0035069287333649776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06259093912025597, -0.18266276591856961, 0.067602190604955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23227381825161886, 0.0, 0.05632681712354841, 0.0, -0.005805880129470541, -0.03819220220020663, 0.23144470628240532, -0.15313344637082058, 2.1327844113010124, -0.1026686050655052, -2.3925374389628895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5166304218606653e-08, 6.449835675183423e-11, -8.101661218408597e-11, -0.16651448723985973, 0.0, -0.11652448723985966, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8607937855859839, -0.24371915232154473, 0.23753743680428796]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0024577339997185997, 0.0, 0.015114245040090308, 0.0, -0.001768101440626048, 0.022585007813253722, -0.8827491523365248, -2.0675966299932653e-07, 0.9999998875626009, -7.210335554302635e-08, -0.1467572668058425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.3556685321053996e-10, 9.258837416649198e-19, -9.140636719676175e-20, -0.004469308963665469, 0.0, -0.004469308963665469, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06482657424071259, -0.18365765432537987, 0.07487727180856579]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23213566192047877, 0.0, 0.05706258014776267, 0.0, -0.006299946855483313, -0.037181786036529774, 0.18562744770103873, -0.15313344644011637, 2.18278441124418, -0.10266860507880073, -2.3983620226761873, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5152664950416467e-08, 6.449835678511299e-11, -8.101661218728977e-11, -0.1667311059604873, 0.0, -0.11674110596048722, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8641534837965207, -0.2529330753899315, 0.24164826466741385]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002763126622802015, 0.0, 0.014715260484285174, 0.0, -0.009881334520255435, 0.02020832327353709, -0.9163451716273316, -1.3859157797955176e-09, 0.9999999988633524, -2.659106167568513e-10, -0.11649167426595694, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.7278536380372465e-10, 6.655752355851371e-19, -6.407597775466092e-20, -0.0043323744125510905, 0.0, -0.0043323744125510905, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06719396421073606, -0.1842784613677346, 0.08221655726251766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2319632265014764, 0.0, 0.057770482237290595, 0.0, -0.007210633493688709, -0.03631973213294236, 0.13818914692060869, -0.15313344669298617, 2.23278441103317, -0.10266860512893017, -2.402454882045091, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5140083647453425e-08, 6.449835680902302e-11, -8.101661218955329e-11, -0.16694001438630976, 0.0, -0.11695001438630967, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8676385016268215, -0.26216224946734557, 0.2461251759565754]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.003448708380047142, 0.0, 0.014158041790558417, 0.0, -0.018213732764107912, 0.01724107807174826, -0.9487660156086009, -5.057396124836962e-09, 0.9999999957797983, -1.0025887149796506e-09, -0.08185718737806773, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.5162605926087e-10, 4.782006837362797e-19, -4.5270181613603325e-20, -0.00417816851644912, 0.0, -0.00417816851644912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06970035660601767, -0.18458348154828197, 0.08953822578323085]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23173104700851133, 0.0, 0.05846259660872053, 0.0, -0.008537615134493966, -0.035648819510938186, 0.08928866755855847, -0.153133446975999, 2.2827844108598705, -0.10266860516667987, -2.40482956732299, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5129456485561246e-08, 6.449835682619347e-11, -8.101661219115731e-11, -0.16714590034106, 0.0, -0.11715590034105992, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8712558621315409, -0.2713932207399645, 0.2509657699599279]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.004643589859301954, 0.0, 0.013842287428598807, 0.0, -0.026539632816105146, 0.013418252440083479, -0.9780095872410043, -5.660256857419369e-09, 0.9999999965340128, -7.549941392500863e-10, -0.04749370555798135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.125432378435518e-10, 3.434088148950386e-19, -3.208028656262401e-20, -0.004117719095005067, 0.0, -0.004117719095005067, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07234721009438819, -0.18461942545237914, 0.09681188006705028]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23141104222420014, 0.0, 0.059088973119694965, 0.0, -0.010267722476716637, -0.03522112581361613, 0.039288643280469646, -0.1531334471910085, 2.332784410797134, -0.10266860517847731, -2.40572005513048, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5120976538340005e-08, 6.449835683852151e-11, -8.101661219230342e-11, -0.16733174840413442, 0.0, -0.11734174840413435, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8750123188430854, -0.2806144337404689, 0.25616872659930734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.006400095686223723, 0.0, 0.012527530219488686, 0.0, -0.03460214684445339, 0.008553873946441148, -1.0000004855617763, -4.300189833630929e-09, 0.9999999987452631, -2.359488490986696e-10, -0.017809756149802312, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.6959894442485648e-10, 2.465609197665229e-19, -2.2922150645620412e-20, -0.003716961261488339, 0.0, -0.003716961261488339, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07512913423088918, -0.1844242600100872, 0.10405913278758819]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23096982086437604, 0.0, 0.059610094166903445, 0.0, -0.012372415846781483, -0.035095026001020616, -0.01071138176099335, -0.15313347984193743, 2.3827844107943843, -0.10266860517907317, -2.4056047163218777, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5114476337657163e-08, 6.449835684737075e-11, -8.101661219312344e-11, -0.16748527184117812, 0.0, -0.11749527184117803, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.878913611844632, -0.2898160089782552, 0.26173669521270304]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00882442719648193, 0.0, 0.010422420944169597, 0.0, -0.04209386740129695, 0.002521996251910276, -1.0000005008292598, -6.530185785309972e-07, 0.9999999999450085, -1.191717988005431e-11, 0.002306776172042873, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.3000401365680736e-10, 1.769848048487117e-19, -1.6400296063150168e-20, -0.0030704687408736686, 0.0, -0.0030704687408736686, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0780258600309334, -0.18403150475572608, 0.11135937226791391]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23101217788753217, 0.0, 0.06013923085153734, 0.0, -0.014779847226264032, -0.03461757522126543, -0.060711405529473426, -0.15388655706051566, 2.432784409961612, -0.10266860528245277, -2.4051035767174325, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5109104446275706e-08, 6.449835685372592e-11, -8.10166121937198e-11, -0.16764292538782805, 0.0, -0.11765292538782796, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.882993401765239, -0.2989815014987048, 0.2676659597185791]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008471404631226059, 0.0, 0.010582733692677745, 0.0, -0.04814862758965098, 0.009549015595103762, -1.0000004753696015, -0.015061544371564787, 0.999999983344559, -2.0675920466798336e-09, 0.010022792088908411, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0743782762911581e-10, 1.2710339242924058e-19, -1.1927150588714577e-20, -0.003153070932998687, 0.0, -0.003153070932998687, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08159579841213978, -0.18330985040899092, 0.11858529011752081]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23166096916362228, 0.0, 0.06069844728180941, 0.0, -0.017467751485140307, -0.03315600865469124, -0.11071142628841504, -0.15609643553672656, 2.482784409488149, -0.10266860534438106, -2.4046540117080197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.510470778879998e-08, 6.449835685828496e-11, -8.101661219416032e-11, -0.16781085163138046, 0.0, -0.11782085163138035, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8872813659580655, -0.3080958760385541, 0.2739310444207709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01297582552180187, 0.0, 0.011184328605441374, 0.0, -0.053758085177525484, 0.02923133133148378, -1.0000004151788324, -0.044197569524218314, 0.9999999905307368, -1.2385659558039324e-09, 0.008991300188256925, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -8.793314951453258e-11, 9.118090776345964e-20, -8.810504044423885e-21, -0.0033585248710479576, 0.0, -0.0033585248710479576, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08575928385652976, -0.18228749079698595, 0.1253016940438357]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23231091311461602, 0.0, 0.061426229675754, 0.0, -0.020487812432683144, -0.03047972228842628, -0.16071040117553964, -0.16004312160247902, 2.532784401365805, -0.10266860677755257, -2.404459746314448, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5099470222581762e-08, 6.44983568615499e-11, -8.101661219499738e-11, -0.1680341591303878, 0.0, -0.11804415913038771, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8918067481223992, -0.31714436187886447, 0.28048703554563337]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299887901987468, 0.0, 0.014555647878891775, 0.0, -0.06040121895085673, 0.053525727325299186, -0.9999794977424918, -0.07893372131504905, 0.9999998375531234, -2.866343021772737e-08, 0.003885307871427466, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0475132436431223e-10, 6.529860755311476e-20, -1.6741185686697014e-20, -0.004466149980146987, 0.0, -0.004466149980146987, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0905076432866756, -0.1809697168062073, 0.13111982249724963]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23296086532242, 0.0, 0.06215409472709866, 0.0, -0.02392437276710368, -0.02674503752105018, -0.2105817633981625, -0.16561382731665833, 2.5827844013258225, -0.10266860678829268, -2.4046078224207066, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5094715870301405e-08, 6.449835686389057e-11, -8.10166121958493e-11, -0.1682554071836218, 0.0, -0.11826540718362172, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8966191113221037, -0.3261062062074736, 0.2872605000031366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044156079604, 0.0, 0.01455730102689316, 0.0, -0.0687312066884107, 0.07469369534752199, -0.9974272444524571, -0.1114141142835863, 0.9999999992003538, -2.1480196249001482e-10, -0.00296152212516529, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.508704560716088e-11, 4.681360479261919e-20, -1.7038482683341403e-20, -0.004424961064680123, 0.0, -0.004424961064680123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.096247263994089, -0.17923688657218223, 0.1354692891500644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23361081752388146, 0.0, 0.0628508053799112, 0.0, -0.02784263938376655, -0.022316290839102332, -0.26015412376750086, -0.1724837692456318, 2.632784401282506, -0.10266860680981145, -2.4051049133129707, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5090870728711455e-08, 6.449835686556409e-11, -8.101661219658032e-11, -0.16846612250000284, 0.0, -0.11847612250000275, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9017766306039234, -0.33495753051188176, 0.2941580202486183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044029229256, 0.0, 0.013934213056250708, 0.0, -0.0783653323332574, 0.088574933638957, -0.991447207386767, -0.1373988385794697, 0.9999999991336712, -4.3037553845922474e-10, -0.00994181784528227, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.690283179901098e-11, 3.3470416807463886e-20, -1.4620468206051482e-20, -0.004214306327620768, 0.0, -0.004214306327620768, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10315038563639398, -0.1770264860881631, 0.13795040490963484]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23426076965262405, 0.0, 0.06351808585519686, 0.0, -0.03226760423563554, -0.017605180724197828, -0.30950717241445064, -0.18027332003458044, 2.6827844011594446, -0.10266860689586754, -2.405798923004195, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5088168650476983e-08, 6.449835686676262e-11, -8.101661219716285e-11, -0.16866693605027083, 0.0, -0.11867693605027074, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9073312103521671, -0.34367564242710863, 0.3010847318330421]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042574851788, 0.0, 0.013345609505713325, 0.0, -0.08849929703737983, 0.09422220229809006, -0.9870609729389952, -0.15579101577897295, 0.999999997538778, -1.7211219437877278e-09, -0.013880193824493153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.4041564689418295e-11, 2.3970734751594266e-20, -1.1650638152869926e-20, -0.0040162710053597995, 0.0, -0.0040162710053597995, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11109159496487403, -0.17436223830453706, 0.13853423168847506]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2349107218251938, 0.0, 0.06415924023207728, 0.0, -0.03692528791703121, -0.012953309383227089, -0.35869761374305403, -0.18866355862243098, 2.7327844010755875, -0.10266860697854155, -2.406627782416584, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5086476690835496e-08, 6.449835686761823e-11, -8.101661219760747e-11, -0.16885580365123617, 0.0, -0.11886580365123608, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9131786146557287, -0.3522871118930777, 0.3078824838240916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043451394824, 0.0, 0.012823087537608186, 0.0, -0.0931536736279134, 0.09303742681941482, -0.9838088265720679, -0.16780477175701095, 0.9999999983228582, -1.6534801752684214e-09, -0.016577188247773315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.383919282975195e-11, 1.7112424024057768e-20, -8.89241380022243e-21, -0.003777352019306943, 0.0, -0.003777352019306943, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11694808607123089, -0.172229389319382, 0.13595503982099066]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23556067390849939, 0.0, 0.06478803278538864, 0.0, -0.04183456615147509, -0.008572960011633702, -0.40806390078927407, -0.19748360438472765, 2.782784400791496, -0.10266860719730213, -2.407291329752124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.508617571010874e-08, 6.449835686822646e-11, -8.101661219793906e-11, -0.16903785397931964, 0.0, -0.11904785397931955, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9193752889409146, -0.36076918614489767, 0.3144721097790261]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904166611173, 0.0, 0.01257585106622724, 0.0, -0.09818556468887765, 0.08760698743186775, -0.9873257409244003, -0.17640091524593338, 0.9999999943181707, -4.375211525270041e-09, -0.013270946710809785, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -6.019614535075065e-12, 1.2164454044679264e-20, -6.631873034439257e-21, -0.0036410065616694046, 0.0, -0.0036410065616694046, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12393348570371722, -0.16964148503639906, 0.13179251909868964]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.236210626139229, 0.0, 0.06536046745949703, 0.0, -0.04703021406689744, -0.004617444475231801, -0.45798055991983916, -0.20663595352997322, 2.832784400757068, -0.10266860721746252, -2.4074953169164655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5086509559567502e-08, 6.449835686865965e-11, -8.101661219818335e-11, -0.16920172016723956, 0.0, -0.11921172016723948, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9259853034842632, -0.36909590549573923, 0.32081066527974794]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044614591969, 0.0, 0.011448693482167727, 0.0, -0.1039129583084469, 0.07911031072803801, -0.9983331826113014, -0.1830469829049114, 0.999999999311448, -4.0320788269595363e-10, -0.004079743286827765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.676989175211572e-12, 8.663903499395061e-21, -4.885868286263472e-21, -0.003277323758398469, 0.0, -0.003277323758398469, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13220029086697233, -0.16653438701683082, 0.12677111001443597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23686057836931296, 0.0, 0.06587810156161174, 0.0, -0.0524964863405664, -0.00118270585363039, -0.5079805843462595, -0.2160950541819633, 2.882784400716864, -0.10266860724498096, -2.407250737118994, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.5087157239983762e-08, 6.449835686896832e-11, -8.101661219836138e-11, -0.1693500288244522, 0.0, -0.11936002882445211, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.933051756038837, -0.37724759518933726, 0.3268799032418193]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044601679327, 0.0, 0.010352682042294314, 0.0, -0.10932544547337934, 0.06869477243202822, -1.0000004885284073, -0.1891820130398012, 0.9999999991959225, -5.503687990429099e-10, 0.004891595949425155, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.2953608325192462e-11, 6.173382684430698e-21, -3.5605898488683896e-21, -0.002966173144252638, 0.0, -0.002966173144252638, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14132905109147714, -0.16303379387196085, 0.12138475924142719]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2375105306050451, 0.0, 0.06633846290253478, 0.0, -0.058191351775601974, 0.001668432329925141, -0.5579806092848749, -0.22587296157730907, 2.932784400696764, -0.10266860726613215, -2.4066122039332507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.508792424142453e-08, 6.449835686918893e-11, -8.101661219849074e-11, -0.16948129400264927, 0.0, -0.1194912940026492, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.940598587013591, -0.3852107926240798, 0.33268169117947183]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044714642574, 0.0, 0.009207226818460935, 0.0, -0.11389730870071137, 0.05702276367111061, -1.000000498772309, -0.19555814790691595, 0.9999999995979963, -4.2302393165950684e-10, 0.012770663714865474, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5340028815336086e-11, 4.412167855239182e-21, -2.5872104320209593e-21, -0.002625303563941781, 0.0, -0.002625303563941781, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15093661949507836, -0.15926394869485117, 0.11603575875305036]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23816048284209412, 0.0, 0.0667541920092772, 0.0, -0.06406386082224472, 0.0038888666409760144, -0.6079806341574682, -0.23600022442066063, 2.982784400676464, -0.1026686072896429, -2.405623243830887, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.508872929882969e-08, 6.44983568693467e-11, -8.101661219858393e-11, -0.16959939525107245, 0.0, -0.11960939525107236, 0.0, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9486375546909553, -0.392976246093866, 0.338231045212232]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044740980728, 0.0, 0.008314582134848038, 0.0, -0.11745018093285499, 0.044408686221017464, -1.0000004974518655, -0.2025452568670308, 0.999999999594002, -4.702149838721262e-10, 0.019779202047272564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.6101148103212668e-11, 3.1554899151547097e-21, -1.8638372708511323e-21, -0.00236202496846343, 0.0, -0.00236202496846343, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16077935354728673, -0.1553090693957241, 0.11098708065520332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23881043507849506, 0.0, 0.06713184482908141, 0.0, -0.07005742931658411, 0.005448713403224011, -0.6579806591040078, -0.2465303068168445, 3.0327844006582434, -0.10266860732529401, -2.4043287632200925, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.514282972494158e-08, 7.788045832160237e-11, -8.560329437215217e-11, -0.16970569426875323, -5.003399515739654e-13, -0.11971569384411146, 1.4031238726829678e-13, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.957150755961286, -0.4005454511699985, 0.34354279610094524]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044728018867, 0.0, 0.007553056396084257, 0.0, -0.11987136988678795, 0.031196935244959915, -1.000000498930792, -0.21060164792367753, 0.9999999996355844, -7.130221769765577e-10, 0.025889612215890707, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0820085222377747e-09, 2.6764202904510995e-10, -9.173364347136461e-11, -0.0021259803536155405, -1.0006799031479392e-11, -0.0021259718607818234, 2.8062477453659823e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17026402540661248, -0.1513841015226497, 0.10623501777426465]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.23946038731859332, 0.0, 0.06745982263114288, 0.0, -0.07608131544195283, 0.006985865514212323, -0.7079806841127956, -0.25826056162507827, 3.082784400647795, -0.10266860735227312, -2.4030800032637294, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.527012371214173e-08, 1.0864708998263817e-10, -9.677997632206264e-11, -0.16979672706752624, -1.928871302654709e-12, -0.11980672215193221, 2.847132948767664e-13, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9657424103356813, -0.40805883235209867, 0.34846876547088573]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044801965218, 0.0, 0.006559556041229219, 0.0, -0.12047772250737446, 0.030743042219766245, -1.0000005001757544, -0.23460509616467462, 0.9999999997910318, -5.395823536596364e-10, 0.02497519912726212, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.5458797440029817e-09, 6.153326332207153e-10, -2.2353363899821064e-10, -0.0018206559754603093, -2.8570627021614932e-11, -0.0018205661564150298, 2.8880181521693924e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17183308748790677, -0.15026762364200294, 0.09851938739881044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24011033953466435, 0.0, 0.0677527459816008, 0.0, -0.0822086278041773, 0.008332059250703178, -0.7579807087765827, -0.2711238912381578, 3.1327844005480205, -0.10266860778403221, -2.40184888287597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 2.7755034865294392e-08, 7.785868690170071e-10, -3.0716440175586607e-10, -0.1698771715774365, -2.1485484868957436e-11, -0.11988717645968759, 1.0751644402580919e-11, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9745247257379728, -0.4154762821353041, 0.35302023109585084]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044321420643, 0.0, 0.005858467009158569, 0.0, -0.12254624724448937, 0.026923874729817117, -1.0000004932757425, -0.25726659226159004, 0.9999999980045062, -8.635181673671529e-09, 0.024622407755194725, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.969822306305346e-08, 1.3398795580687344e-08, -4.207688508676112e-09, -0.0016088901982052723, -3.9113227132605097e-10, -0.0016090861551076078, 2.093386221540805e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17564630804582865, -0.14834899566410767, 0.09102931249930246]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24076029177653963, 0.0, 0.06800000696212856, 0.0, -0.08850112972767232, 0.009245438926171438, -0.8079807337982046, -0.28496627182260936, 3.182784400539825, -0.10266860845211243, -2.400607020048759, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0008853644981449859, 0.0002637382308716937, -7.146771891412436e-05, -0.16991038573735515, -3.8057901681006385e-06, -0.11994017298333379, 6.410525431392179e-06, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9835661110971916, -0.4227493690965445, 0.357240114665206]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044837505545, 0.0, 0.004945219610555001, 0.0, -0.12585003846990042, 0.018267593509365194, -1.0000005004324353, -0.27684761168903116, 0.9999999998360883, -1.3361604396337824e-08, 0.02483725654421454, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017706734862202412, 0.005274749045696493, -0.001429348234994452, -0.0006642831983729642, -7.611537365231539e-05, -0.001059930472923987, 0.0001282102935949555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18082770718437646, -0.1454617392248084, 0.08439767138710356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24141024400779346, 0.0, 0.06821995837171572, 0.0, -0.0954173149560193, 0.01000073734497902, -0.8579807586792207, -0.30134365245337247, 3.2327844004824087, -0.10366299380571066, -2.3993322565561144, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0034838259981374462, 0.001075278372717597, -0.00027667944712250346, -0.16989648928945758, -1.0665995980726173e-05, -0.11996402046012122, 2.9197167965890384e-05, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9928493913760116, -0.4298559632274283, 0.36113641751120923]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044625076542, 0.0, 0.004399028191743228, 0.0, -0.1383237045669394, 0.015105968376151637, -1.0000004976203232, -0.32754761261526155, 0.9999999988516667, -0.019887707071964605, 0.02549526985289202, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05196922999984921, 0.01623080283691807, -0.004104234564167582, 0.0002779289579515554, -0.0001372041162525107, -0.0004769495357487722, 0.0004557328506899641, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1856656055764004, -0.14213188261767673, 0.07792605692006413]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24206019613726515, 0.0, 0.06844892257533174, 0.0, -0.10322994962341195, 0.010567485483468524, -0.9075581646694126, -0.3211754490286886, 3.2827844001377096, -0.10633739946830738, -2.3980102125129936, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.008058275001504144, 0.0025849065857914445, -0.0006273671868806639, -0.16984517458562104, -1.2865576887126398e-05, -0.1199655901757444, 7.827617340695497e-05, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.002277444823715, -0.4368164476217162, 0.3646931690708545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999042589433643, 0.0, 0.004579284072320237, 0.0, -0.15625269334785297, 0.011334962769790083, -0.991548119803838, -0.39663593150632304, 0.9999999931060182, -0.05348811325193439, 0.02644088086241625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09148898006733396, 0.030192564261476942, -0.007013754795163208, 0.0010262940767309845, -4.399161812800449e-05, -3.139431246344614e-05, 0.0009815801088212915, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18856106895406935, -0.13920968788575774, 0.07113503119290501]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24271014735545668, 0.0, 0.06874787293089735, 0.0, -0.11181246122470045, 0.010638263384989207, -0.9554400727506829, -0.3439572753134275, 3.3326272902367324, -0.11046176732430736, -2.3970411778031595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.014346171413594525, 0.004781437238488289, -0.001093286566429616, -0.1697671830920926, -5.143484210272699e-07, -0.11995945014555565, 0.0001601188828169425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0117325946551383, -0.4436048593179186, 0.367901924948681]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999024363830792, 0.0, 0.005979007111312021, 0.0, -0.17165023202577, 0.001415558030413662, -0.9576381616254037, -0.4556365256947775, 0.9968578019804555, -0.08248735711999969, 0.01938069419667847, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12575792824180765, 0.04393061305393689, -0.009318387590979044, 0.0015598298705688132, 0.00024702456932198255, 0.0001228006037750317, 0.0016368541881997506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1891029966284642, -0.13576823392404802, 0.06417511755653138]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24336009339077383, 0.0, 0.06911208095133353, 0.0, -0.12099454928451607, 0.009981495898837137, -1.0006596649569814, -0.3688756086609181, 3.3810430897276267, -0.115549810000113, -2.3965219742173796, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.021883030718840388, 0.007597610194436255, -0.0016255953109058428, -0.16967183363533161, 3.899153842424246e-05, -0.11994583942864961, 0.0002810481335930513, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.021152593009951, -0.45012953612448153, 0.37078823184861237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998920706342829, 0.0, 0.007284160408723626, 0.0, -0.18364176119631218, -0.01313534972304141, -0.9043918441259705, -0.4983666669498118, 0.9683159898178832, -0.10176085351611275, 0.010384071715597262, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15073718610491732, 0.05632345911895931, -0.010646174889524532, 0.001906989135219824, 0.0007901177369053946, 0.0002722143381207434, 0.0024185850155221756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18839996709625273, -0.13049353613125858, 0.05772613799862674]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24401002931767685, 0.0, 0.06946716407447735, 0.0, -0.13055268892902452, 0.008567826833572266, -1.042635096401456, -0.3951894306300189, 3.4269709053959825, -0.12108094654226279, -2.3964675101427266, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.030065438380500825, 0.010867464926444501, -0.0021724210901542295, -0.16957195787056895, 0.00011163290802802163, -0.1199259998091317, 0.00044033565941127486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0304155316776218, -0.45627700787687003, 0.37337495995121656]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012998718538060115, 0.0, 0.007101662462876497, 0.0, -0.19116279289016927, -0.028273381305297413, -0.8395086288894891, -0.5262764393820148, 0.918556313367119, -0.11062273084299575, 0.0010892814930561785, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16364815323320875, 0.06539709464016491, -0.010936515584967731, 0.0019975152952533327, 0.0014528273920755832, 0.00039679239035833916, 0.003185750516364471, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18525877335341703, -0.12294943504777, 0.05173456205208357]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.244638702843577, 0.0, 0.06978804516974647, 0.0, -0.14040087030306717, 0.006448096426094984, -1.0812562667377443, -0.422451826607268, 3.470079183003775, -0.1266889878617854, -2.3967128688421995, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.03825354936564267, 0.014322797706453073, -0.002693697588982673, -0.16947901728164144, 0.00021026515893878347, -0.11990413138896315, 0.0006255164001956976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0394773062351537, -0.46197947039692067, 0.3756935510841205]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01257347051800293, 0.0, 0.006417621905382441, 0.0, -0.19696362748085303, -0.04239460814954563, -0.7724234067257669, -0.5452479195449826, 0.8621655521558496, -0.11216082639045233, -0.004907173989460893, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16376221970283675, 0.06910665560017146, -0.010425529976568869, 0.0018588117785499649, 0.001972645018215237, 0.00043736840337090893, 0.0037036148156884526, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18123549115063742, -0.11404925040101271, 0.04637182265807928]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24521164753546607, 0.0, 0.0701124514909792, 0.0, -0.15048005099341588, 0.003668936385990456, -1.1166898960705396, -0.4503286082028579, 3.51042808204057, -0.13211725877888528, -2.397085287389989, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.04599629838649692, 0.017741987431692453, -0.0031660547062997567, -0.1693960804693822, 0.0003251188479035395, -0.11988091627021663, 0.0008232653127037202, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0483350999634555, -0.46721675674792207, 0.3777807302028416]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011458893837781238, 0.0, 0.006488126424654437, 0.0, -0.20158361380697404, -0.055583200802090574, -0.7086725866559038, -0.5575356319117981, 0.8069779807359055, -0.10856541834199768, -0.007448370955783039, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15485498041708512, 0.06838379450478758, -0.009447142346341674, 0.0016587362451847408, 0.0022970737792951195, 0.00046430237493036197, 0.0039549782501604545, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17715587456603915, -0.10474572702002777, 0.04174358237442136]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2457431790019066, 0.0, 0.07040995868763088, 0.0, -0.16067452973732477, 0.00017563153966600317, -1.149255173945757, -0.4785355477344434, 3.5482980481759143, -0.13728493489067795, -2.397445314253788, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05306910501452492, 0.02099266565034233, -0.0035812413581468644, -0.1693246529348996, 0.0004479016872534731, -0.11985968744810045, 0.001023492153873808, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0570138598702212, -0.47199494500861205, 0.37967848211931005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010630629328810487, 0.0, 0.005950143933033662, 0.0, -0.2038895748781779, -0.06986609692648905, -0.6513055575043484, -0.5641387906317091, 0.7573993227068856, -0.10335352223585359, -0.007200537275985317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14145613256055994, 0.06501356437299752, -0.008303733036942157, 0.0014285506896522476, 0.002455656786998673, 0.0004245764423236192, 0.004004536823401753, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17357519813531241, -0.09556376521379939, 0.03795503832936965]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24623682416306564, 0.0, 0.0707079563289476, 0.0, -0.17097816127768922, -0.003965993344349774, -1.1793135886649042, -0.5068601519058047, 3.584009944005424, -0.14200955877775331, -2.397706015072643, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.059346402304760675, 0.023983282525850323, -0.0039368151899130234, -0.16926335536480824, 0.0005715588784351379, -0.11984047213966165, 0.001217855836849493, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0655297251300402, -0.4763327419337534, 0.38141946786530345]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009872903223181125, 0.0, 0.005959952826334354, 0.0, -0.2060726308072893, -0.08283249768031553, -0.6011682943829433, -0.5664920834272266, 0.7142379165901928, -0.09449247774150715, -0.005214016377099256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12554594580471498, 0.059812337510159914, -0.007111476635323176, 0.0012259514018271096, 0.002473143823633295, 0.00038430616877598435, 0.0038872736595137016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17031730519637714, -0.08675593850282676, 0.034819714919868]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24669917137160294, 0.0, 0.07110854400390651, 0.0, -0.18137351165665375, -0.008684082437152647, -1.207210518394995, -0.5351144908109712, 3.6178704086659774, -0.1461332576054746, -2.3978152277781444, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06479873207702708, 0.026669539355900506, -0.004235195646961235, -0.16920638279288275, 0.0006912042298969388, -0.11984380408946914, 0.0014009040531841785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0738971398691919, -0.48025640352716864, 0.3830320746007894]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009246944170746185, 0.0, 0.008011753499178336, 0.0, -0.20790700757929045, -0.09436178185605745, -0.5579385946018167, -0.5650867781033304, 0.6772092932110652, -0.08247397655442557, -0.002184254110024381, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10904659544532808, 0.05372513660100365, -0.005967609140964243, 0.0011394514385099127, 0.002392907029236018, -6.663899614973442e-05, 0.0036609643266937108, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.167348294783036, -0.07847323186830421, 0.032252134709719396]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24713756519619012, 0.0, 0.07161662159460618, 0.0, -0.19181920751019893, -0.013928700345259247, -1.233265553849435, -0.5631305635009443, 3.650163203182221, -0.14954601950098817, -2.3977426910569237, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06945302998933739, 0.02903714207045428, -0.004481352498803809, -0.16915443471670596, 0.0008035413628995007, -0.11987115749376802, 0.0015692164366401253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.082139181069535, -0.4837964894678948, 0.3845425922683316]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008767876491743832, 0.0, 0.010161551813993414, 0.0, -0.20891391707090373, -0.104892358162132, -0.5211007090888001, -0.5603214537994627, 0.6458558903248711, -0.06825523791027158, 0.0014507344244152742, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09308595824620612, 0.0473520542910755, -0.004923137036851473, 0.0010389615235359142, 0.002246742660051237, -0.0005470680859777075, 0.0033662476691189358, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16484082400686262, -0.07080171881452249, 0.030210353350843284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2475549983023322, 0.0, 0.07221804947556329, 0.0, -0.2022520633451531, -0.019659919441386592, -1.2577479030897178, -0.5907710796410779, 3.6811187243890786, -0.15218365542740142, -2.3974697262104225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0733617952878012, 0.03108686676426193, -0.004681185346052456, -0.16911335378890563, 0.0009062177017965661, -0.11992068364232732, 0.0017205143214799351, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.090271583591517, -0.48698711607074857, 0.3859723144745219]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008348662122841936, 0.0, 0.012028557619142333, 0.0, -0.2086571166990837, -0.11462438192254687, -0.4896469848056584, -0.5528103228026722, 0.6191104241371513, -0.052752718528264936, 0.0054592969300221806, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07817530596927597, 0.04099449387615296, -0.003996656944972933, 0.0008216185560068918, 0.00205352677794131, -0.000990522971185916, 0.0030259576967961973, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16264805043963856, -0.06381253205707574, 0.02859444412380588]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2479472102594153, 0.0, 0.07277340855344801, 0.0, -0.21270860435742253, -0.0257553031992719, -1.280850752184616, -0.6179859183537935, 3.7108818047930496, -0.15394766973952503, -2.3969854451755377, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07658252679060347, 0.03282356477000636, -0.004840559327919094, -0.169082526987504, 0.000997256670763036, -0.11996193018387667, 0.0018529057847214154, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0982752839084675, -0.48987666725160606, 0.3873289843781169]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007844239141661618, 0.0, 0.011107181557694334, 0.0, -0.20913082024538823, -0.12190767515770617, -0.4620569818979646, -0.5442967742543119, 0.5952616080794234, -0.035280286242472036, 0.009685620697692944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0644146300560456, 0.0347339601148885, -0.0031874796373327595, 0.0006165360280326202, 0.001820779379329397, -0.0008249308309871879, 0.002647829264829606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.16007400633900618, -0.05779102361715019, 0.027133398071900464]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24830923659972529, 0.0, 0.07337386558499959, 0.0, -0.22313989557238184, -0.03213087247416113, -1.3026107318144924, -0.6448108712149575, 3.7394798958436555, -0.15474384723208248, -2.396321694120929, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07918110565663415, 0.034259845860057904, -0.004965314252016976, -0.16907917721218227, 0.0010753981594887685, -0.12002289436651176, 0.0019653675272334596, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1061827568793012, -0.49249649855298394, 0.3886304430224323]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007240526806199981, 0.0, 0.012009140631031652, 0.0, -0.20862582429918639, -0.12751138549778457, -0.43519959259752783, -0.5364990572232802, 0.5719618210121177, -0.015923549851149212, 0.01327502109216846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05197157732061351, 0.028725621801031002, -0.0024950984819576416, 6.699550643474877e-05, 0.0015628297745146522, -0.0012192836527016057, 0.002249234850240885, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15814945941667502, -0.05239662602755755, 0.026029172886307825]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24862463085239564, 0.0, 0.07394611704069855, 0.0, -0.2334868214356179, -0.03866522797920096, -1.3228582755315152, -0.6713233661476727, 3.766698009014485, -0.1544932762381133, -2.3956019728805495, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08119130327610846, 0.03538729570286875, -0.005060034990195667, -0.16909684923299426, 0.0011380333308511385, -0.12009141847747397, 0.0020549985450074005, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.114034749826976, -0.49486861521606895, 0.3898935680787766]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006307885053407134, 0.0, 0.011445029113979188, 0.0, -0.20693851726472104, -0.1306871101007965, -0.4049508743404586, -0.5302498986543039, 0.5443622634165884, 0.005011419879383559, 0.014394424807587222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040203952389486305, 0.02254899685621694, -0.0018944147635738193, -0.0003534404162397632, 0.0012527034272473987, -0.0013704822192443502, 0.001792620355478817, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1570398589534946, -0.04744233326170048, 0.025262501126885935]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2488902408213538, 0.0, 0.07457093937817945, 0.0, -0.24368525588475032, -0.04520949421581128, -1.3413731757562728, -0.6975442605548711, 3.792210579966983, -0.15314154581539696, -2.3950046165031367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08270418554636838, 0.03624320988858825, -0.005130517363849807, -0.16915540002066753, 0.0011861582302613296, -0.12018692375812304, 0.0021236421891056073, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.121859340624918, -0.49700967053695455, 0.39113320356853154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005312199379163104, 0.0, 0.012496446749618119, 0.0, -0.20396868898264892, -0.13088532473220646, -0.3702980044951518, -0.5244178881439672, 0.510251419049963, 0.027034608454326873, 0.011947127548261003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030257645405198496, 0.01711828371439004, -0.0014096474730828047, -0.0011710157534653807, 0.0009624979882038237, -0.0019101056129814788, 0.0013728728819641391, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1564918159588388, -0.04282110641771238, 0.024792709795098435]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24912353621340871, 0.0, 0.07513223207912516, 0.0, -0.2536772728384126, -0.05164389511143233, -1.3580907997199005, -0.7234458610861066, 3.815870628291692, -0.15080311904132584, -2.3946362752860706, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08382363593849158, 0.03687993174972081, -0.005182301129763091, -0.1692215573819852, 0.0012222202733430383, -0.12027941695465248, 0.002174979490205021, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1296698499402016, -0.4989414080898131, 0.39235947804980364]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004665907841098379, 0.0, 0.011225854018914055, 0.0, -0.19984033907324586, -0.128688017912421, -0.3343524792725566, -0.5180320106247125, 0.4732009664941699, 0.04676853548142221, 0.007366824341317696, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022389007842464094, 0.012734437222651284, -0.001035675318265673, -0.0013231472263528874, 0.0007212408616341729, -0.00184986393058882, 0.0010267460219882773, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1562101863056704, -0.03863475105717006, 0.024525489625441935]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2493344345873408, 0.0, 0.07563967632388699, 0.0, -0.26341952282290915, -0.05788128941639624, -1.3730749077115205, -0.7489794144675082, 3.837694235913039, -0.1476482398326273, -2.3945344775266433, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08471645046721596, 0.03739691089226394, -0.00522371962957432, -0.1692759901036769, 0.0012509572982918819, -0.12036386595442627, 0.002216012960644409, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1374724259383202, -0.5006880102918698, 0.3935818666634768]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004217967478641756, 0.0, 0.010148884895236805, 0.0, -0.19484499968993063, -0.12474788609927821, -0.29968215983239826, -0.5106710676280313, 0.4364721524269364, 0.06309758417397127, 0.002035955188541833, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017856290574487642, 0.01033958285086268, -0.0008283699962245744, -0.0010886544338339775, 0.0005747404989768734, -0.00168897999547589, 0.0008206694087877571, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15605151996237343, -0.03493204404113411, 0.02444777227346279]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2495291254611555, 0.0, 0.07610743309859812, 0.0, -0.27287351706422835, -0.06386007000921244, -1.386458209829742, -0.7740898896699244, 3.857787198975873, -0.14384533428484642, -2.3946901602483464, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0854231412726906, 0.03781290389683289, -0.005256584665113997, -0.16932647703724382, 0.0012736925265541322, -0.12044372794588123, 0.0022485642461374166, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1452674976683273, -0.5022771875586262, 0.39480428449718397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003893817476293535, 0.0, 0.009355135494222535, 0.0, -0.18907988482638421, -0.11957561185632395, -0.2676660423644314, -0.5022095040483245, 0.40185926125669064, 0.07605811095561746, -0.003113654434061179, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014133816109492768, 0.00831986009137887, -0.0006573007107935482, -0.0010097386713384799, 0.00045470456524500673, -0.0015972398290992655, 0.0006510257098601517, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559014346001425, -0.03178354533512671, 0.02444835667414404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.24971127897112055, 0.0, 0.07654770133877788, 0.0, -0.28202049235321547, -0.06954230839885944, -1.39841009718629, -0.7987256849465152, 3.8763066927338796, -0.13952256430313936, -2.3950737502477635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08602912661943857, 0.03818062360835884, -0.005285004379291282, -0.16936674420746403, 0.0012930472728035767, -0.12051849493030337, 0.0022764502291251396, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1530633346958712, -0.5037330045217779, 0.3960326065796455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0036430701993014174, 0.0, 0.008805364803595322, 0.0, -0.1829395057797424, -0.11364476779294014, -0.239037747130961, -0.4927159055318148, 0.37038987516012606, 0.08645539963414126, -0.0076717999883404294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012119706934959314, 0.007354394230518976, -0.0005683942835456974, -0.0008053434044043185, 0.00038709492498888734, -0.0014953396884425615, 0.0005577196597544615, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1559167405508805, -0.029116339263036313, 0.024566441649231337]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2498811997334895, 0.0, 0.07696791535210463, 0.0, -0.2908505119582744, -0.07490840292520531, -1.4091029551095644, -0.8228576862832844, 3.8934077478201807, -0.13481072107362316, -2.395636361669536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08665705109805102, 0.03857989540280461, -0.00531556344872703, -0.1693847941520483, 0.0013120614635983919, -0.12058461144070116, 0.002304393127038612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1608457475220832, -0.505076987080296, 0.39726780322278493]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0033984152473786307, 0.0, 0.008404280266535249, 0.0, -0.17660039210117842, -0.10732189052691747, -0.21385715846548894, -0.48264002673538264, 0.3420211017260203, 0.09423686459032395, -0.011252228435458242, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012558489572249167, 0.007985435888915442, -0.0006111813887149691, -0.00036099889168517233, 0.0003802838158963023, -0.0013223302079559333, 0.0005588579582694437, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15564825652424044, -0.026879651170361514, 0.02470393286278899]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25000115993437955, 0.0, 0.07737296610074557, 0.0, -0.2994051294674068, -0.07972967766969824, -1.4180548363352028, -0.846838950338786, 3.9088827022417494, -0.13076983364913178, -2.3965707066411355, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08720490750152673, 0.038934755676571946, -0.005342607987575832, -0.1694098096627433, 0.001328295122039716, -0.12065251589218774, 0.0023284500129674606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1686696930153928, -0.506346819315667, 0.3985187482679692]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023992040178016263, 0.0, 0.00810101497281858, 0.0, -0.17109235018264904, -0.09642549488985862, -0.17903762451276628, -0.4796252811100323, 0.3094990884313727, 0.08081774848982731, -0.018686899431986294, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010957128069514287, 0.007097205475346712, -0.0005408907769760367, -0.0005003102139001786, 0.00032467316882648045, -0.0013580890297316835, 0.0004811377185769764, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15647890986619267, -0.025396644707419605, 0.02501890090368525]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 599999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2501128528765304, 0.0, 0.0777500001534744, 0.0, -0.3076626574520455, -0.08398908998894464, -1.4253770195368305, -0.8706588347862696, 3.922838069795817, -0.12737373675756802, -2.3978380776517256, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08764483890791952, 0.039222283657003615, -0.00536447615485725, -0.1694426990733101, 0.0013411899074241452, -0.12071852983180784, 0.002347639966393915, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1764936350248556, -0.5075618877322114, 0.3997756683087901]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022338588430173157, 0.0, 0.0075406810545766345, 0.0, -0.16515055969277337, -0.08518824638492802, -0.14644366403255246, -0.4763976889496718, 0.27910735108136014, 0.06792193783127484, -0.025347420211802692, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008798628127855748, 0.0057505596086333995, -0.0004373633456283615, -0.0006577882113359592, 0.0002578957076885856, -0.001320278792401776, 0.0003837990685290854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15647884018925456, -0.024301368330887904, 0.02513840081641829]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.250222107023377, 0.0, 0.07814045360228958, 0.0, -0.31558675468167624, -0.08774208514845928, -1.4313363165262374, -0.8941988204587691, 3.9354755824144307, -0.12439999795243682, -2.3993514994276257, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0879830377650946, 0.03944442883754456, -0.005381352453908842, -0.16949046110548174, 0.0013510421824446128, -0.1207898433506332, 0.002362337266378826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1842733442288151, -0.5087324392257867, 0.4010299200038882]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002185082936931633, 0.0, 0.0078090689763035195, 0.0, -0.15848194459261444, -0.07505990319029297, -0.11918593978813569, -0.47079971344998894, 0.2527502523722674, 0.05947477610262393, -0.03026843551800351, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006763977143501597, 0.004442903610818798, -0.00033752598103183225, -0.0009552406434325663, 0.00019704550040935056, -0.0014262703765072612, 0.0002939459996982245, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1555941840791889, -0.023411029871505826, 0.025085033901963125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.250328588881154, 0.0, 0.07854982634512611, 0.0, -0.32314699141753994, -0.0910615018043292, -1.4362062064183352, -0.91733216606878, 3.9470054616666843, -0.1216692257614047, -2.4010303878620034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08825215548312727, 0.03962308081524697, -0.005394896921203672, -0.16954767309426985, 0.00135854048351819, -0.12086633971100932, 0.002373329976305158, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1919779116487683, -0.5098645693569425, 0.40227705819159126]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021296371555396786, 0.0, 0.008187454856730749, 0.0, -0.15120473471727355, -0.06638833311739835, -0.09739779784195622, -0.462666912200218, 0.23059758504507488, 0.054615443820642505, -0.033577768687551135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005382354360653367, 0.003573039554048211, -0.0002708893458966121, -0.0011442397757623671, 0.00014996602147154326, -0.0015299272075225496, 0.00021985419852663078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15409134839906308, -0.02264260262311428, 0.024942763754061417]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25044677443798924, 0.0, 0.0789310351508406, 0.0, -0.3303914810180706, -0.0940073642956912, -1.4402377407921465, -0.9398617550294959, 3.9577531470201572, -0.11884731069732858, -2.4029501890914604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08888131413347983, 0.0400901811739838, -0.005427818625415681, -0.16956612291601883, 0.0013690491424108756, -0.12093811006109577, 0.0023814325417555182, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1998570829218054, -0.5109465285816862, 0.4035890602598723]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0023637111367042526, 0.0, 0.007624176114289903, 0.0, -0.14488979201061272, -0.058917249827240135, -0.08063068747622665, -0.45059177921431676, 0.21495370706945977, 0.05643830128152218, -0.03839602458913788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012583173007051151, 0.00934200717473653, -0.0006584340842401881, -0.0003689964349795497, 0.00021017317785371252, -0.0014354070017288175, 0.0001620513090072111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15758342546074328, -0.02163918449487387, 0.026240041365620078]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2505532179037128, 0.0, 0.07929586903932709, 0.0, -0.3373690831277784, -0.09662755946104978, -1.4436190728065044, -0.9618473498290563, 3.9678383447307985, -0.11602930876957356, -2.4050297124221918, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08998955968594656, 0.04095211824572516, -0.005485312955795529, -0.16955045785486964, 0.0013855175680678145, -0.12100880702614375, 0.0023873497559189923, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2078212385614393, -0.5119894501275661, 0.40494748046965273]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021288693144714313, 0.0, 0.007296677769729708, 0.0, -0.13955204219415676, -0.0524039033071716, -0.06762664028715556, -0.43971189599120775, 0.2017039542128266, 0.056360038555100564, -0.04159046661462535, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022164911049334525, 0.01723874143482718, -0.0011498866075969482, 0.0003133012229841266, 0.00032936851313877607, -0.0014139393009596631, 0.00011834428326948414, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15928311279267743, -0.02085843091759814, 0.02716840419560839]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 849999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2506517634511201, 0.0, 0.07964434690229617, 0.0, -0.3440981838528044, -0.09896545280715713, -1.4464855365443796, -0.9833686960106043, 3.9773285492378303, -0.11327696969857846, -2.4071869800940253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09149077261343108, 0.04215558440115099, -0.005561708041550031, -0.16951610028338737, 0.0014084270976688182, -0.12107749989950282, 0.0023916452259841775, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2157662453581335, -0.5130047973329463, 0.4063230147980378]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001970910948145528, 0.0, 0.006969557259381621, 0.0, -0.13458201450051924, -0.046757866922146965, -0.057329274757504774, -0.43042692363096063, 0.1898040901406324, 0.05504678141990186, -0.043145353436669726, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030024258549690437, 0.02406932310851668, -0.0015279017150900452, 0.0006871514296451799, 0.0004581905920200749, -0.0013738574671815355, 8.590940130370588e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1589001359338853, -0.020306944107604495, 0.027510686567700893]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25073077200964544, 0.0, 0.07998990072013375, 0.0, -0.3505944017270404, -0.10092836899201926, -1.4486131624470993, -1.0046516812355415, 3.9861323799236494, -0.11173409333454518, -2.4095074441614486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.093225656138881, 0.043582872085159916, -0.005647984854840476, -0.1694745756994668, 0.001436726814393381, -0.12114732830509212, 0.0023947512361286475, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2236757441168256, -0.5140110164241644, 0.4077039878514745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015801711705060715, 0.0, 0.006911076356751378, 0.0, -0.12992435748471964, -0.03925832369724269, -0.04255251805439108, -0.4256597044987451, 0.17607661371638397, 0.030857527280665736, -0.04640928134846746, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.034697670508998205, 0.028545753680178514, -0.0017255362658089007, 0.0008304916784112001, 0.0005659943344912542, -0.0013965681117859027, 6.212020288940126e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15818997517384187, -0.020124381824360583, 0.027619461068734537]\n accelerations: []\n effort: []\n time_from_start: \n secs: 8\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25080897713862554, 0.0, 0.08044152588244509, 0.0, -0.35683265244203677, -0.10254953273507852, -1.4500591173518824, -1.0256942400212732, 3.9943054764795254, -0.11080557356899945, -2.411970532415023, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09502815020830883, 0.045095863809775205, -0.0057364262783810155, -0.16943151060753328, 0.0014674640722687146, -0.12123847113882608, 0.0023969914059407253, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2315238505290913, -0.5150135171297713, 0.40907919976109614]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015641025796022537, 0.0, 0.009032503246226719, 0.0, -0.12476501429992826, -0.03242327486118517, -0.02891909809566349, -0.420851175714632, 0.1634619311175191, 0.018570395310914402, -0.04926176507148528, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03604988138855673, 0.030259834492305772, -0.0017688284708107785, 0.0008613018386707719, 0.0006147451575066712, -0.0018228566746791696, 4.480339624155639e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15696212824531636, -0.02005001411213856, 0.027504238192433084]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2508890850624879, 0.0, 0.08100524882298756, 0.0, -0.3627816265074857, -0.1038992066697827, -1.450961301830525, -1.0464243796739299, 4.001949398879483, -0.11009588292026826, -2.4145292759892962, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09674234772988136, 0.04655936232039913, -0.005819631587323354, -0.16939891702274162, 0.0014978398977708535, -0.12135146157420272, 0.0023986043390263408, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2392895434752147, -0.5160131982501563, 0.4104399077604545]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016021584772469642, 0.0, 0.011274458810849406, 0.0, -0.11897948130897876, -0.026993478694083292, -0.018043689572848888, -0.4146027930531324, 0.15287844799915015, 0.014193812974623753, -0.05117487148546357, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.034283950431450314, 0.02926997021247849, -0.00166410617884676, 0.0006518716958329033, 0.0006075165100427769, -0.0022598087075329323, 3.225866171231416e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15531385892246566, -0.0199936224077015, 0.027214159987168356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25097034216354597, 0.0, 0.08166177260021829, 0.0, -0.36841965812629707, -0.10504204583639816, -1.4514528212931501, -1.0667738171180767, 4.009163851894057, -0.1094531229878194, -2.4171438679628006, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0982483854543768, 0.047863170934546416, -0.005891994913857078, -0.16939035260821336, 0.0015254787560757398, -0.12147927189906041, 0.002399764371728272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2469610358570717, -0.5170104502290385, 0.41178091879014395]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016251420211613034, 0.0, 0.01313047554461474, 0.0, -0.11276063237622722, -0.022856783332309297, -0.009830389252502328, -0.40698874888293507, 0.14428906029146818, 0.012855198648977249, -0.05229183947008239, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030120754489908776, 0.026076172282945655, -0.001447266530674482, 0.00017128829056536996, 0.0005527771660977257, -0.002556206497153667, 2.3200654038621596e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15342984763714143, -0.019945039577642314, 0.02682022059378801]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 99999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2510516357715548, 0.0, 0.08238983040672551, 0.0, -0.37373931888052986, -0.10602558405579081, -1.451636723101241, -1.0867009747543688, 4.01603035192416, -0.10883193500968162, -2.4197886274820073, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09948693644596036, 0.048946450634772765, -0.005951008406069606, -0.16941577211021777, 0.0015488419322775657, -0.12161734675395565, 0.002400598089741445, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.254533728220507, -0.5180055434121742, 0.4131003434909167]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016258721601768171, 0.0, 0.014561156130144581, 0.0, -0.10639321508465598, -0.019670764387852938, -0.003678036161818359, -0.39854315272584195, 0.13733000060206949, 0.012423759562755585, -0.05289519038413486, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024771019831671338, 0.021665594004527042, -0.0011802698442505623, -0.0005083900400883748, 0.0004672635240365183, -0.0027614970979048443, 1.66743602634637e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15145384726870115, -0.019901863662714202, 0.026388494015454202]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25113072350251936, 0.0, 0.08316671079778903, 0.0, -0.3787508502494209, -0.10688322005335406, -1.4515869401346837, -1.1061933967026125, 4.022612574827478, -0.10822091811416548, -2.4224489235976785, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10053413447045423, 0.04988432002366384, -0.005999585616683752, -0.16945239851070754, 0.0015700793208370388, -0.12176085185538293, 0.0024011969863292843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2620070597950388, -0.5189962436291196, 0.41440058186838186]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015817546192903593, 0.0, 0.015537607821270526, 0.0, -0.10023062737782079, -0.017152719951264925, 0.0009956593311480954, -0.3898484389648758, 0.13164445806636133, 0.0122203379103227, -0.05320592231342597, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020943960489877154, 0.01875738777782148, -0.0009715442122829234, -0.0007325280097954905, 0.00042474777118946125, -0.0028701020285455936, 1.1977931756787476e-05, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14946663149063966, -0.019814004338908293, 0.026004767549303406]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2512077498607559, 0.0, 0.0839713417336497, 0.0, -0.3834689862330269, -0.10763782587574927, -1.451355323004704, -1.1252540856565276, 4.028958131534314, -0.107617741291297, -2.425117053713206, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10147049914294587, 0.05075968485744288, -0.006040501133580966, -0.16948162472260203, 0.0015917127048957383, -0.12190581397054183, 0.0024016270487705743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.269383188225902, -0.5199805547105066, 0.41568456181060137]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015405271647306608, 0.0, 0.016092618717213278, 0.0, -0.09436271967211937, -0.015092116447904307, 0.0046323425995925885, -0.3812137790783025, 0.1269111341367286, 0.012063536457369524, -0.05336260231055568, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018727293449832948, 0.017507296675580795, -0.0008183103379442784, -0.0005845242378898277, 0.0004326676811739879, -0.0028992423031777956, 8.60124882580174e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1475225686172621, -0.019686221627741023, 0.02567959884439042]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.251283236033724, 0.0, 0.08479005777822772, 0.0, -0.38790778189684416, -0.1083058200306391, -1.4509789226886234, -1.1438934086373465, 4.03510267516589, -0.10702201970933443, -2.4277888905085194, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10234422242273204, 0.051623360896634586, -0.006075212121652766, -0.1694977923462712, 0.0016153865240984893, -0.12205108457547734, 0.0024019358010884543, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2766659403596534, -0.520957336272515, 0.41695457405971925]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015097234593617792, 0.0, 0.01637432089156036, 0.0, -0.08877591327634525, -0.013359883097796562, 0.0075280063216146, -0.37278645961637474, 0.12289087263149716, 0.011914431639251375, -0.053436735906265645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017474465595723514, 0.017273520783834154, -0.0006942197614360065, -0.0003233524733833357, 0.00047347638405502006, -0.002905412098710196, 6.1750463575958035e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14565504267503143, -0.019535631240165788, 0.025400244982357947]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2513703706317501, 0.0, 0.08560233792714313, 0.0, -0.3914653755268149, -0.10931767661229519, -1.4507202372460386, -1.1615040248686999, 4.041158377999453, -0.10654860150192653, -2.4301595814278203, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1031288662475863, 0.05243549333754934, -0.006103568646617251, -0.16950768721629408, 0.001639416326786855, -0.12218852114892764, 0.002402157440366706, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2836370479254333, -0.5218648214860184, 0.41818741861312614]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017426919605227206, 0.0, 0.016245602978308123, 0.0, -0.07115187259941413, -0.020237131633121935, 0.005173708851696833, -0.35221232462706936, 0.12111405667127985, 0.009468364148158047, -0.04741381838601609, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01569287649708517, 0.016242648818295107, -0.0005671304992897088, -0.00019789740045794504, 0.0004805960537673125, -0.0027487314690060973, 4.432785565032481e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13942215131559713, -0.018149704270070434, 0.024656891068137697]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 349999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2514493477059554, 0.0, 0.08640735379958592, 0.0, -0.39438074012575397, -0.11049767667883857, -1.4504846749983493, -1.1783168217661624, 4.047082425270099, -0.10607602053762469, -2.4323485184059135, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10377882459292853, 0.05312604794312293, -0.006125675547297737, -0.16953006966577958, 0.001660681765869331, -0.12231718792113701, 0.002402316536536641, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.290366203080503, -0.522726583551331, 0.41938837891773134]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015795414841060628, 0.0, 0.016100317448855914, 0.0, -0.05830729197878151, -0.023600001330867752, 0.0047112449537853734, -0.33625593794924863, 0.11848094541290272, 0.009451619286036819, -0.04377873956186737, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999166906844536, 0.01381109211147179, -0.000442138013609722, -0.00044764898970960467, 0.0004253087816495207, -0.002573335444187243, 3.1819233987016685e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13458310310139543, -0.017235241306249663, 0.024019206092104273]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25152137726965274, 0.0, 0.08720634056188904, 0.0, -0.39694784194128746, -0.11162860504159947, -1.4501588634515525, -1.1946168612284684, 4.052821441536157, -0.10557201341794838, -2.4345032700530007, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10428696804614308, 0.05367333725153169, -0.006142384585304982, -0.16957305959306138, 0.001677872515588735, -0.12243918994024111, 0.002402430735385223, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2969443548080073, -0.5235699844072766, 0.42056598276904816]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014405912739470898, 0.0, 0.01597973524606254, 0.0, -0.05134203631067011, -0.02261856725521791, 0.0065162309359357, -0.3260007892461209, 0.11478032532116444, 0.010080142393526175, -0.043095032941743765, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010162869064290963, 0.010945786168175216, -0.00033418076014491024, -0.0008597985456360133, 0.00034381499438808144, -0.0024400403820820237, 2.283976971636982e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1315630345500841, -0.016868017118913503, 0.023552077026336955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2515895710968562, 0.0, 0.0880038827582948, 0.0, -0.3993571841106828, -0.11257883366699989, -1.4496816148891083, -1.210593772390229, 4.058349833211235, -0.10504560859337787, -2.436714636904913, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10467167667315536, 0.05409095446687562, -0.0061547810938733264, -0.1696364071515194, 0.0016911370611455193, -0.1225578246515458, 0.0024025127075675574, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3034319885042374, -0.5244112287965328, 0.42172666944960296]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0013638765440694791, 0.0, 0.015950843928114994, 0.0, -0.04818684338790619, -0.019004572508008532, 0.009544971248885994, -0.3195382232352094, 0.1105678335015558, 0.010528096491410037, -0.04422733703824354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00769417254024549, 0.008352344306878529, -0.00024793017136688064, -0.001266951169160405, 0.0002652909111356853, -0.00237269422609373, 1.6394436466893464e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12975267392460157, -0.016824887785123616, 0.023213733611096164]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25165601234981977, 0.0, 0.08880089468677174, 0.0, -0.401705488789894, -0.1133000700511799, -1.4490392919174342, -1.2263534536172123, 4.0636714740434945, -0.10450946944429648, -2.439020364341578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10495738436931493, 0.05440259411510896, -0.00616387180010065, -0.16971616977015389, 0.0017011019588030409, -0.12267484113871391, 0.0024025715499868044, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.309863737621459, -0.5252574072474873, 0.42287490214630613]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001328825059271803, 0.0, 0.015940238569538967, 0.0, -0.04696609358422449, -0.014424727683600187, 0.012846459433482135, -0.31519362453966826, 0.1064328166451877, 0.010722782981627706, -0.046114548733295097, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005714153923191549, 0.006232792964666921, -0.00018181412454647971, -0.0015952523726895276, 0.00019929795315043014, -0.0023403297433622454, 1.1768483849375868e-06, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12863498234443288, -0.016923569019088508, 0.022964653934063783]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2517219213707762, 0.0, 0.08959692641837808, 0.0, -0.4040318788854549, -0.11379782598094786, -1.4482468582261694, -1.2419516666479182, 4.068810329934335, -0.10397090018157328, -2.441425229518321, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1051670366962163, 0.05463196907567788, -0.0061704887764203395, -0.16980790546699992, 0.0017084671356192808, -0.12279099914833805, 0.0024026137926661424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3162600404018567, -0.5261104736086814, 0.42401411325666877]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0013181804191289956, 0.0, 0.015920634632126774, 0.0, -0.046527801911218455, -0.009955118595359247, 0.015848673825296693, -0.31196426061411814, 0.10277711781681553, 0.01077138525446414, -0.04809730353485539, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0041930465380275225, 0.004587499211378467, -0.00013233952639378027, -0.001834713936920466, 0.0001473035363247965, -0.002323160192482847, 8.448535867620403e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12792605560795595, -0.017061327223881526, 0.02278422220725272]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2517840488892214, 0.0, 0.09039297018418435, 0.0, -0.40630606864495844, -0.11411205211729392, -1.4473502195253878, -1.2572288224036132, 4.073756731239998, -0.10345794360184131, -2.4438787299850278, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10531970381947169, 0.05479932512941808, -0.006175281855884739, -0.1699069376050367, 0.0017138553512427996, -0.12290575888644863, 0.002402644124272723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.322566528822441, -0.5269582940592794, 0.42513566619088144]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0012425503689035401, 0.0, 0.01592087531612536, 0.0, -0.045483795190071334, -0.006284522726921066, 0.017932774015629895, -0.3055431151138978, 0.09892802611325544, 0.010259131594639375, -0.04907000933413865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0030533424651077615, 0.0033471210748039436, -9.586158928800168e-05, -0.0019806427607356797, 0.00010776431247037722, -0.0022951947622115894, 6.066321316070164e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12612976841168577, -0.01695640901196175, 0.022431058684253727]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25183727523967014, 0.0, 0.09119556850064582, 0.0, -0.4084545037617362, -0.11426976033160821, -1.446363843843916, -1.2718783429389067, 4.078442060445556, -0.10345794448060475, -2.4463114158162225, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10543032182927176, 0.05492074213525353, -0.006178742706730733, -0.1700105953147811, 0.0017177713789608316, -0.1230194154144146, 0.0024026659077364685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.328668161853654, -0.527779465347189, 0.42622071250203813]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010645270089745392, 0.0, 0.016051966329229284, 0.0, -0.042968702335555255, -0.0031541642862857613, 0.019727513629438115, -0.29299041070586773, 0.0937065841111725, -1.7575268808009414e-08, -0.04865371662389525, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002212360196001326, 0.0024283401167090176, -6.921701691987132e-05, -0.002073154194888001, 7.832055436064079e-05, -0.002273130559319578, 4.356692749107305e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12203266062425996, -0.016423425758191737, 0.021700926223133937]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25188632138037004, 0.0, 0.09199312407180757, 0.0, -0.4104344778220663, -0.11431874173510428, -1.445330607035161, -1.2857098174264168, 4.0828465877999625, -0.10345796685082784, -2.4486646599606727, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10551021025493314, 0.055008504621742386, -0.006181236334337058, -0.1701118036766566, 0.0017206052593020298, -0.12312699821340828, 0.0024026815574602627, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3344899417979879, -0.5285604612246441, 0.427256897305005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000980922813997596, 0.0, 0.015951111423234965, 0.0, -0.03959948120660225, -0.0009796280699214416, 0.020664736175099035, -0.2766294897502025, 0.08809054708812164, -4.47404461851312e-07, -0.047064882889001985, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015977685132274944, 0.0017552497297770408, -4.987255212649948e-05, -0.002024167237509806, 5.667760682396388e-05, -0.002151655979873508, 3.129944758833179e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1164355988866781, -0.015619917549100942, 0.02072369605933734]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25193259810809177, 0.0, 0.09278820432177419, 0.0, -0.4122345390668309, -0.11429809020395595, -1.444285667178183, -1.2986649594626347, 4.086977892304263, -0.1034579780376268, -2.450908647744438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1055677810459542, 0.055071786407828775, -0.00618303051852708, -0.17020849922150671, 0.0017226502590779302, -0.12322775958521853, 0.0024026928079398384, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3400026927506534, -0.5292963329792928, 0.42823942789731456]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0009255345544342075, 0.0, 0.015901604999332252, 0.0, -0.03600122489529118, 0.0004130306229666494, 0.020898797139560794, -0.2591028407243576, 0.08262609008599407, -2.2373597916825168e-07, -0.044879755675313195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011514158204211412, 0.0012656357217277964, -3.588368380043429e-05, -0.0019339108970023349, 4.0899995518008336e-05, -0.00201522743620511, 2.2500959151652763e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11025501905331306, -0.014717435092975711, 0.019650611846191005]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25197645133085544, 0.0, 0.0935816963663875, 0.0, -0.41386182325355364, -0.11423423452844325, -1.4432516187945392, -1.3107651503301205, 4.090854455940515, -0.10345799133382357, -2.453035033714539, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10560920935548486, 0.05511734266221203, -0.006184320226752285, -0.17030023203342265, 0.0017241232447840517, -0.12332207243293278, 0.002402700902757612, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.345206334836813, -0.5299872806423424, 0.42916833319696956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008770644552735947, 0.0, 0.015869840892266122, 0.0, -0.03254568373445521, 0.0012771135102540975, 0.02068096767287673, -0.24200381734971804, 0.07753127272505292, -2.659239354982059e-07, -0.042527719402013886, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008285661906132615, 0.0009111250876651154, -2.5794164504089093e-05, -0.001834656238318886, 2.9459714122430193e-05, -0.0018862569542849928, 1.618963554700398e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1040728417231917, -0.013818953260992209, 0.018578105993100516]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25201802512904803, 0.0, 0.09437350721371439, 0.0, -0.41533159913780426, -0.11414369129945529, -1.4422414406805852, -1.3220671896363245, 4.094497004565576, -0.10345800665366596, -2.4550470665662116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10563899305640094, 0.05515010352315997, -0.006185246709321951, -0.17038721990956138, 0.001725182926023902, -0.12341067731056632, 0.002402706733468948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3501149588034613, -0.5306358216989933, 0.4300459952102187]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008314759638518819, 0.0, 0.015836216946537772, 0.0, -0.02939551768501207, 0.001810864579759341, 0.020203562279080316, -0.22604078612408063, 0.07285097250122892, -3.063968478377906e-07, -0.04024065703345669, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005956740183215744, 0.0006552172189588263, -1.8529651393336408e-05, -0.0017397575227746148, 2.119362479700808e-05, -0.0017720975526707588, 1.1661422672470769e-07, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09817247933296666, -0.012970821133017278, 0.01755324026498267]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25205743042206885, 0.0, 0.09511534537836795, 0.0, -0.41666119148013675, -0.11403647702936102, -1.4412620471670474, -1.3326379436346971, 4.097925033731812, -0.10345801796062243, -2.456952720727884, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10566039137000154, 0.05517364574846635, -0.006185911978192882, -0.1704679239710023, 0.0017259446364386608, -0.1234923477552343, 0.0024027109338961247, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.354747808079967, -0.5312451854624252, 0.43087565409923045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007881058604168197, 0.0, 0.01483676329307122, 0.0, -0.026591846846650086, 0.002144285401885224, 0.019587870270755554, -0.21141507996745212, 0.06856058332472108, -2.261391292873223e-07, -0.038113083233447406, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00042796627201193273, 0.0004708445061276411, -1.3305377418628524e-05, -0.001614081228818328, 1.5234208295174606e-05, -0.0016334088933595884, 8.400854353173534e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.092656985530113, -0.012187275268638727, 0.016593177780235432]\n accelerations: []\n effort: []\n time_from_start: \n secs: 9\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25209478266337687, 0.0, 0.09580382268940926, 0.0, -0.417867120756386, -0.11391873667700812, -1.4403168377398459, -1.3425426202850292, 4.101155952106823, -0.10345803089048618, -2.4587609328367837, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10567575910908385, 0.05519055885704734, -0.006186389274443016, -0.17054339769235313, 0.0017264921452987564, -0.12356825332781896, 0.0024027139577310124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3591248277264687, -0.5318185787086221, 0.4316606702905892]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000747044826160569, 0.0, 0.013769546220826238, 0.0, -0.024118585524984592, 0.002354807047058051, 0.018904188544029758, -0.19809353300664106, 0.06461836750021278, -2.5859727492571655e-07, -0.03616424217799424, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0003073547816461414, 0.0003382621716196911, -9.545925002676019e-06, -0.0015094744270168021, 1.0950177201911116e-05, -0.0015181114516932396, 6.047669775742773e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08754039293003056, -0.011467864923938954, 0.015700323827174564]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25213020176740003, 0.0, 0.09644781796843163, 0.0, -0.41896405778651435, -0.11379437772857279, -1.4394072407810552, -1.3518404825760437, 4.104205174837294, -0.10345804408800922, -2.4604799490232026, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.105686793450238, 0.055202710253189256, -0.0061867313184017165, -0.17061512184675665, 0.001726885897461024, -0.12364000604185366, 0.0024027161337596948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.363264837340766, -0.5323589212783647, 0.4324042216085324]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007083820804633355, 0.0, 0.012879905580447286, 0.0, -0.02193874060256702, 0.00248717896870665, 0.01819193917581534, -0.18595724582029133, 0.060984454609432893, -2.6395046092535523e-07, -0.03438032372837389, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00022068682308296934, 0.00024302792283837217, -6.840879174010266e-06, -0.00143448308807027, 7.87504324535279e-06, -0.0014350542806939816, 4.3520573648267073e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08280019228594947, -0.010806851394852098, 0.014871026358864446]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2521638085368879, 0.0, 0.09705782276077676, 0.0, -0.4199646444229547, -0.11366604148758092, -1.4385335850126175, -1.3605839703643432, 4.107086456875393, -0.10345805769054033, -2.462116802260276, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10569471584084829, 0.055211445354379246, -0.006186975935433928, -0.17068431229535527, 0.001727169508173785, -0.1237089135105711, 0.002402717698137274, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3671849762902262, -0.5328687935469224, 0.4331092111379981]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.000672135389757236, 0.0, 0.012200095846902705, 0.0, -0.020011732728806915, 0.002566724819837395, 0.017473115368752734, -0.1748697557659901, 0.057625640761974926, -2.720506219336796e-07, -0.03273706474146647, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001584478122058646, 0.00017470202379983146, -4.892340644231018e-06, -0.001383808971972524, 5.672214255219063e-06, -0.0013781493743489491, 3.128755158852691e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0784027789892027, -0.010197445371154277, 0.014099790589313179]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2521957190320927, 0.0, 0.0976424300823295, 0.0, -0.4208796614173853, -0.113535639165772, -1.4376955749217215, -1.3688191362063777, 4.10981218340798, -0.1034580720575404, -2.463677319741626, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10570040500700563, 0.05521773575270602, -0.006187150028942731, -0.17075175426220437, 0.0017273746476820554, -0.12377581527194051, 0.0024027188220472426, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3709006767410337, -0.53335046266212, 0.43377826211527154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006382099040957203, 0.0, 0.011692146431054809, 0.0, -0.0183003398886113, 0.0026080464361782968, 0.016760201817921035, -0.16470331684068962, 0.05451453065173742, -2.8734000142589386e-07, -0.031210349627006723, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00011378332314690922, 0.00012580796653543233, -3.4818701760595052e-06, -0.0013488393369818215, 4.102790165410353e-06, -0.0013380352273881992, 2.2478199372823145e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07431400901615198, -0.009633382303953858, 0.013381019545468288]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2522260412962682, 0.0, 0.09820777109321628, 0.0, -0.4217182974288865, -0.11340463898947115, -1.4368925502841448, -1.3765864558089211, 4.11239356997694, -0.1034580887254969, -2.4651663246060536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10570449471598348, 0.055222297425716604, -0.006187271697649338, -0.17081796748869274, 0.0017275253881866624, -0.12384126965526704, 0.0024027196291510687, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3744258152720772, -0.5338059290210464, 0.43441374213360184]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006064452835097719, 0.0, 0.011306820217735481, 0.0, -0.016772720230024102, 0.0026200035260172143, 0.01606049275153292, -0.15534639205086667, 0.05162773137921023, -3.3335912999688724e-07, -0.029780097288547903, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.179417955707347e-05, 9.123346021165581e-05, -2.433374132141852e-06, -0.00132426452976708, 3.014810092142655e-06, -0.001309087666530551, 1.61420765195768e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.07050277062086902, -0.009109327178527787, 0.012709600366606238]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2522548058422406, 0.0, 0.09875983862538447, 0.0, -0.4224884439778365, -0.11327425704616399, -1.4361236393113403, -1.3839216504341916, 4.11484083042943, -0.10345810858862015, -2.466587867529029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10570787740080612, 0.05522890784764913, -0.006187129383718363, -0.17088291626932864, 0.001727879070378211, -0.12390601595288453, 0.00240272020857797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3777728957657804, -0.534236968969182, 0.4350178140206973]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005752909194477611, 0.0, 0.011041350643363894, 0.0, -0.0154029309790006, 0.0026076388661430507, 0.015378219456089094, -0.14670389250540808, 0.04894520904980519, -3.972624648653938e-07, -0.028430858459515016, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.765369645287906e-05, 0.00013220843865055694, 2.8462786194922073e-06, -0.0012989756127177409, 7.073643830969089e-06, -0.0012949259523497834, 1.1588538029068464e-08, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06694160987406436, -0.008620798962711979, 0.012081437741909076]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2522810826391496, 0.0, 0.09930307409840082, 0.0, -0.4231972469826839, -0.11314620245888432, -1.435387971032144, -1.3908563491443762, 4.1171638296635455, -0.10345813154746225, -2.4679453151694952, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10571719086201957, 0.05528957744876022, -0.0061831654472027054, -0.17093638905762232, 0.001732227096365462, -0.12397061135245838, 0.002402720624471051, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3809531611613457, -0.5346451588814208, 0.4355927412850681]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005255359381802212, 0.0, 0.010864709460326982, 0.0, -0.01417606009694806, 0.0025610917455933194, 0.014713365583928011, -0.13869397420369148, 0.04645998468231298, -4.591768420053064e-07, -0.027148952809317645, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018626922426898156, 0.0012133920222218725, 7.927873031315128e-05, -0.0010694557658737758, 8.69605197450229e-05, -0.0012919079914769703, 8.317861613487325e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06360530791130661, -0.008163798244776036, 0.011498545287416404]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2523049556709934, 0.0, 0.09983980817302991, 0.0, -0.4238508757583281, -0.11302190970905479, -1.4346845719963397, -1.3974186506781736, 4.119371499526478, -0.10345815587459502, -2.4692416838862883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10573817446142976, 0.055458209928084076, -0.006171656846004307, -0.17097062172381056, 0.001744471975500404, -0.12403520936971556, 0.0024027209229453526, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3839768053948955, -0.5350319506811975, 0.4361406028308413]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00047746063687615926, 0.0, 0.010734681492581877, 0.0, -0.013072575512883268, 0.0024858549965905297, 0.014067980716087454, -0.13124603067594928, 0.04415339725865123, -4.865426552131862e-07, -0.025927374335864485, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0004196719882036933, 0.003372649586477127, 0.0002301720239679806, -0.0006846533237645364, 0.0002448975826988396, -0.0012919603451435147, 5.969486031032251e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06047288467099532, -0.00773583599553198, 0.010957230915463263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25231105867045767, 0.0, 0.10032268659628076, 0.0, -0.42446746627060933, -0.11290597500680676, -1.4340071467623623, -1.4036302515566106, 4.121483163477144, -0.10345816738598954, -2.4704868561916666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10602300036644575, 0.05644840990583399, -0.006126919208253724, -0.1709647671816199, 0.0017963618162778734, -0.12409384929284009, 0.0024027211371325657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.386848340805747, -0.5353990642266322, 0.4366769460153868]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00012205998928510446, 0.0, 0.009657568465016886, 0.0, -0.012331810245624778, 0.0023186940449606845, 0.013548504679549465, -0.12423201756874025, 0.04223327901331664, -2.302278903075514e-07, -0.0249034461075673, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005696518100319927, 0.019803999554998217, 0.0008947527550116634, 0.00011709084381317724, 0.0010377968155493864, -0.0011727984624907164, 4.283744261503167e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05743070821702976, -0.00734227090869527, 0.010726863690910672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2523188094797908, 0.0, 0.10074464917216873, 0.0, -0.42504951425777376, -0.11278915832928407, -1.4333476002082248, -1.4095131832815728, 4.123499300925834, -0.10345816988190619, -2.471686254968168, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10654301939956613, 0.05814535167257401, -0.006055248380414588, -0.17093855232995553, 0.0018807993092550166, -0.1241450852309312, 0.0024027212908256275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3895767672843515, -0.5357475406306564, 0.4372017921544714]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00015501618666287543, 0.0, 0.008439251517759594, 0.0, -0.011640959743288451, 0.0023363335504536834, 0.01319093108274753, -0.11765863449924412, 0.040322748973795966, -4.991833310515157e-08, -0.023987975530022763, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010400380662407671, 0.03393883533480032, 0.0014334165567827142, 0.0005242970332873035, 0.0016887498595428655, -0.0010247187618219879, 3.0738612348291766e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.054568529572089366, -0.006969528080483983, 0.010496922781692026]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25232885862824356, 0.0, 0.10116024567945477, 0.0, -0.4255961205029673, -0.11266379064750323, -1.4327009916678688, -1.4150884027982873, 4.125418168118807, -0.10345818450485329, -2.472842467687111, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10721255203362133, 0.06027569963772623, -0.005968390000174377, -0.17090554310000322, 0.001983890023619507, -0.12419636302586053, 0.0024027214011058374, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3921711124662541, -0.5360782591893937, 0.43771177977817916]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020098296905553546, 0.0, 0.008311930145720783, 0.0, -0.010932124903870284, 0.002507353635616749, 0.012932170807119288, -0.11150439033428819, 0.03837734385944171, -2.9245894199194703e-07, -0.0231242543788592, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013390652681103975, 0.04260695930304441, 0.0017371676048042206, 0.0006601845990460799, 0.0020618142872898077, -0.0010255558985866617, 2.205604198864253e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05188690363805183, -0.006614371174744213, 0.010199752474154828]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25233978743735, 0.0, 0.10153958509369299, 0.0, -0.4261066533264455, -0.1125256081626484, -1.4320649867357211, -1.4203755507597082, 4.127239650367151, -0.10345818634608428, -2.4739570242530036, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10795575531660262, 0.0626041941710074, -0.00587603027607318, -0.1708740392195339, 0.0020940761458180975, -0.124242964716481, 0.0024027214802336723, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3946396185457506, -0.5363920878285561, 0.4382039229803152]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00021857618212894488, 0.0, 0.007586788284764475, 0.0, -0.010210656469563829, 0.0027636496970966525, 0.012720098642952277, -0.10574295922841706, 0.03642964496687413, -3.682461984830631e-08, -0.022291131317851706, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014864065659625888, 0.04656989066562343, 0.0018471944820239333, 0.0006300776093866601, 0.002203722443971815, -0.0009320338124093223, 1.5825566985773357e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04937012158993097, -0.006276572783247628, 0.009842864042720797]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25235081238131624, 0.0, 0.10188010687161837, 0.0, -0.42658151396548233, -0.11237304327453626, -1.4314387002731135, -1.425392779282794, 4.128965635970542, -0.10345818878354753, -2.4750312016139193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10872086664217569, 0.06497296374650176, -0.005784486389953149, -0.17084605420882681, 0.0022037771703792897, -0.12428444395244008, 0.0024027215370081545, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3969897165402927, -0.5366898988034393, 0.43867646379442005]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002204988793241671, 0.0, 0.006810435558507696, 0.0, -0.009497212780736777, 0.0030512977622426008, 0.012525729252154399, -0.10034457046171488, 0.034519712067826946, -4.8749265024789204e-08, -0.02148354721831199, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015302226511461223, 0.04737539150988701, 0.0018308777224006194, 0.000559700214141463, 0.002194020491223848, -0.0008295847191816055, 1.1354896463247653e-09, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04700195989084004, -0.005956219497665675, 0.009450816282096928]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2523615518493593, 0.0, 0.10218726546571343, 0.0, -0.4270219788164988, -0.1122060834171935, -1.4308219122795724, -1.4301567071834642, 4.130599386530522, -0.10345819145130036, -2.4760663295793854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10947733479528081, 0.06729055243874994, -0.0056972992032803295, -0.17082147255211852, 0.002308715574222338, -0.12432163777486833, 0.002402721577743542, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.3992281273912792, -0.536972549330397, 0.43912874478502045]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00021478936086224702, 0.0, 0.006143171881901009, 0.0, -0.008809297020328632, 0.0033391971468551946, 0.012335759870818929, -0.0952785580134033, 0.032675011199605065, -5.335505688550676e-08, -0.02070255930932595, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015129363062102306, 0.04635177384496364, 0.0017437437334563933, 0.0004916331341660921, 0.0020987680768609625, -0.0007438764485651794, 8.147077489777581e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0447682170197297, -0.005653010539153125, 0.009045619812007726]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25237180432570033, 0.0, 0.10246770684300431, 0.0, -0.4274298720423899, -0.11202549641134905, -1.430214654632429, -1.434682490214723, 4.132144917315334, -0.10345819412846476, -2.477063828051916, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.110209559510599, 0.06951168524394583, -0.005616123643615657, -0.17079966186833437, 0.0024068672006875317, -0.12435553777525776, 0.0024027216069707285, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4013609639450544, -0.5372408634039042, 0.43956087529949484]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00020504952682063983, 0.0, 0.005608827545817632, 0.0, -0.008157864517822317, 0.0036117401168888016, 0.012145152942866515, -0.09051566062517595, 0.030910615696239055, -5.3543287884058287e-08, -0.019949969450617815, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014644494306363958, 0.04442265610391772, 0.0016235111932934412, 0.0004362136756832034, 0.001963032529303876, -0.0006780000077885038, 5.845437301617798e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.042656731075501886, -0.0053662814701439816, 0.008642610289487096]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25238146729099886, 0.0, 0.10272726560371492, 0.0, -0.4278072816896573, -0.11183237069216756, -1.4296170193905635, -1.438983962857811, 4.133606548978579, -0.10345819667964753, -2.478025164345737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11091124954441599, 0.07161952821038192, -0.0055414738815414985, -0.17077999815497685, 0.002497575674379573, -0.12438697670761464, 0.0024027216279407953, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4033938203181482, -0.5374956216835886, 0.4399734245601298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00019325930597105238, 0.0, 0.00519117521421219, 0.0, -0.007548192945348385, 0.003862514383629993, 0.011952704837308318, -0.08602945286175687, 0.029232633264897296, -5.1023655601979586e-08, -0.019226725876418098, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014033800676339744, 0.0421568593287219, 0.0014929952414831674, 0.000393274267150515, 0.0018141694738408242, -0.0006287786471375757, 4.194013393674222e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040657127461877954, -0.005095165593687294, 0.008250985212698882]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.252390498619779, 0.0, 0.10297054659822659, 0.0, -0.4281563625357159, -0.11162786300695883, -1.4290290783612039, -1.4430738043909863, 4.1349886238260884, -0.10345819906531699, -2.4789518057430064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11158131597285993, 0.07361295746927608, -0.005473243221318875, -0.17076199936251932, 0.0025809316914033277, -0.12441657427680099, 0.0024027216429864484, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.405331849454142, -0.5377375581661414, 0.44036719778333466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00018062657560339655, 0.0, 0.004865619890233428, 0.0, -0.00698161692117084, 0.004090153704174718, 0.01175882058719403, -0.08179683066350556, 0.02764149695018586, -4.7713389156000937e-08, -0.018532827945387548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013401328568879003, 0.03986858517788333, 0.0013646132044524797, 0.0003599758491505228, 0.0016671203404750878, -0.0005919513837269764, 3.0091306327358426e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03876058271987631, -0.004838729651057456, 0.007875464464097757]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25239912014465093, 0.0, 0.10320074871406983, 0.0, -0.4284789728327183, -0.11141292446113953, -1.4284508411738002, -1.4469637486864482, 4.136295091832374, -0.10345820115612882, -2.479845078873402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11221675201287994, 0.07548885154843417, -0.005411099751601362, -0.17074550205563596, 0.002657228456062587, -0.12444472181421161, 0.0024027216537814127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4071799123529072, -0.5379673526596446, 0.44074284351978865]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017243049743785943, 0.0, 0.004604042316864782, 0.0, -0.006452205940048214, 0.004298770916386131, 0.011564743748072957, -0.07779888590923667, 0.026129360125708784, -4.181623651505934e-08, -0.017865462607910006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012708720800400164, 0.03751788158316165, 0.001242869394350254, 0.00032994613766736846, 0.0015259352931851925, -0.0005629507482125733, 2.1589928957066197e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03696125797530156, -0.004595889870062838, 0.007512914729080267]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25240788883287985, 0.0, 0.10341921090359552, 0.0, -0.42877628638766924, -0.11118805108569497, -1.4278822331579157, -1.4506647982331757, 4.137529094262974, -0.10345820251928418, -2.4807060067310833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11280518750251034, 0.07722351517365207, -0.005354843772584346, -0.17073082535817635, 0.0027264559802593477, -0.12447152516526674, 0.002402721661526578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4089427333317257, -0.5381856232370856, 0.4411004400034654]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017537376457820027, 0.0, 0.004369243790513728, 0.0, -0.0059462710990193166, 0.004497467508891094, 0.011372160317688475, -0.07402099093455003, 0.024680048611995072, -2.7263107276517037e-08, -0.017218557153624272, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011768709792608191, 0.034693272504357955, 0.001125119580340323, 0.00029353394919214915, 0.001384550483935208, -0.000536067021102832, 1.5490330273349073e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.035256419576371614, -0.00436541154882128, 0.007151929673534652]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524165283047511, 0.0, 0.10367626904295699, 0.0, -0.42904960059587494, -0.11095396924352419, -1.4273231563224698, -1.4541871698337983, 4.1386939108002325, -0.10345820920579682, -2.481535591477113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11333946222009197, 0.07880623630250141, -0.005303986410941733, -0.17071674179455218, 0.0027890023901728065, -0.124504331360235, 0.0024027216670835685, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4106246560266353, -0.5383929598937067, 0.4414403062931066]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00017278943742480877, 0.0, 0.005141162787229341, 0.0, -0.005466284164113492, 0.00468163684341589, 0.011181536708917477, -0.07044743201244882, 0.02329633074516376, -1.3373025259099935e-07, -0.016591694920593734, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010685494351632619, 0.03165442257698698, 0.0010171472328522554, 0.0002816712724833791, 0.0012509281982691733, -0.0006561238993651669, 1.1113980964272267e-10, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03363845389819144, -0.004146733132421199, 0.006797325792824263]\n accelerations: []\n effort: []\n time_from_start: \n secs: 10\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524247754735371, 0.0, 0.10397725529916613, 0.0, -0.42930046387087295, -0.11071150764304778, -1.4267734895842392, -1.4575403605727661, 4.139792986169174, -0.10345821955408305, -2.4823349753426234, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1138195195301069, 0.08024282762714313, -0.005257830302466809, -0.17070282362717393, 0.002845605639976733, -0.12454279676792503, 0.002402721671070587, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4122296542545412, -0.5385899313663324, 0.44176311765439663]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00016494337572021898, 0.0, 0.006019725124182855, 0.0, -0.00501726549996023, 0.00484923200952796, 0.010993334764610691, -0.06706381477935658, 0.02198150737882517, -2.0696572446165557e-07, -0.01598767731020425, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00960114620029839, 0.028731826492834293, 0.0009231221694984696, 0.00027836334756486947, 0.0011320649960785275, -0.0007693081538004969, 7.974037597446838e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0320999645581175, -0.003939429452512818, 0.006456227225800288]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25243208614273377, 0.0, 0.10427135883619229, 0.0, -0.4295309231646412, -0.11046155496924469, -1.4262330960093574, -1.4607331500367289, 4.140830075613454, -0.10345822102089722, -2.4831056354956518, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11425669845215781, 0.08156666134715308, -0.005215448235800749, -0.1706901848597512, 0.002897468501116762, -0.12457975761167994, 0.0024027216739311843, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4137612699071913, -0.5387770943321168, 0.4420701458417623]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001462133839337144, 0.0, 0.005882070740523317, 0.0, -0.004609185875365357, 0.004999053476061811, 0.010807871497634, -0.06385578927925532, 0.020741788885613857, -2.9336283382280514e-08, -0.015413203060570717, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008743578441018394, 0.02647667440019904, 0.0008476413333212132, 0.000252775348454132, 0.001037257222800585, -0.0007392168750983597, 5.7211944552818607e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.030632313053001264, -0.003743259315689659, 0.006140563747312932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524386161026168, 0.0, 0.1045927287012955, 0.0, -0.42974293641997124, -0.11020533035715467, -1.4257018210528243, -1.4637737146905603, 4.141808986840661, -0.10345823703472296, -2.4838488591929044, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1146624738036024, 0.08280884715242881, -0.005176196904034627, -0.17067732097166968, 0.0029455046386646683, -0.12462037582836553, 0.002402721675983598, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4152228835522174, -0.538954973602994, 0.4423626521076397]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00013059919766130167, 0.0, 0.006427397302064168, 0.0, -0.0042402651066003934, 0.005124492241800449, 0.01062549913066165, -0.06081129307662716, 0.019578224544135474, -3.2027651469270726e-07, -0.014864473945057242, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00811550702889161, 0.024843716105514484, 0.0007850266353224452, 0.0002572777616304568, 0.0009607227509581214, -0.000812364333711761, 4.1048279311635796e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.029232272900520426, -0.0035575854175441627, 0.005850125317548449]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25244451568747894, 0.0, 0.10489862283535707, 0.0, -0.42993816963933745, -0.10994310611565047, -1.4251794223257293, -1.4666697889232347, 4.142732716349441, -0.10345823836208652, -2.4845661404424435, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1150448657919448, 0.08398940194690599, -0.0051397788787799475, -0.1706653452387719, 0.0029902006336061685, -0.1246585288455415, 0.0024027216774561585, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4166176983244227, -0.539124057021721, 0.4426416716482021]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0001179916972422966, 0.0, 0.006117882681231457, 0.0, -0.0039046643873242755, 0.005244484830083867, 0.01044797454190189, -0.057921484653488065, 0.018474590175589518, -2.654727123789898e-08, -0.0143456249907856, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007647839766848121, 0.02361109588954369, 0.0007283605050935847, 0.00023951465795565388, 0.0008939198988300027, -0.000763060343519305, 2.9451209208577416e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027896295444105598, -0.0033816683745381375, 0.005580390811248256]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25244988641889987, 0.0, 0.10518199744623236, 0.0, -0.4301180496360858, -0.10967538557074491, -1.4246656559747581, -1.469428624463279, 4.14360414428067, -0.10345824123782917, -2.4852587040167173, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11540915481497344, 0.0851204843307938, -0.0051060637260996545, -0.17065383872086512, 0.003031811634252953, -0.12469346161789656, 0.002402721678512687, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4179487915457625, -0.5392847995178365, 0.4429080618486328]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00010741462841893505, 0.0, 0.0056674922175057865, 0.0, -0.0035975999349672234, 0.005354410898111162, 0.010275327019424232, -0.055176710800887735, 0.01742855862457895, -5.751485300868667e-08, -0.01385127148547518, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007285780460572703, 0.02262164767775639, 0.0006743030536058526, 0.00023013035813520557, 0.0008322200129356811, -0.0006986554471011754, 2.11305718614372e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.026621864426793235, -0.003214849922309842, 0.005327804008613766]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524547922057172, 0.0, 0.10544930140808326, 0.0, -0.4302838006950364, -0.10940266274535936, -1.4241602685060817, -1.4720570551915202, 4.144425933069922, -0.1034582466533407, -2.4859276357431375, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11575848211774693, 0.0862085254031375, -0.005075000365721078, -0.17064245759939803, 0.0030704631480591173, -0.124726343370833, 0.002402721679270722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4192191052832688, -0.5394376270012365, 0.44316253346337764]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 9.811573634710679e-05, 0.0, 0.005346079237017992, 0.0, -0.0033150211790126827, 0.0054544565077110155, 0.010107749373529722, -0.052568614564821745, 0.016435775785042225, -1.0831023090621251e-07, -0.013378634528403013, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.00698654605547001, 0.021760821446873916, 0.0006212672075715294, 0.00022762242934179372, 0.0007730302761232925, -0.0006576350587290871, 1.5160702567309994e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025406274750124073, -0.0030565496680004297, 0.005089432294897381]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.252459274395601, 0.0, 0.10570629192834773, 0.0, -0.4304364879411714, -0.10912528936848931, -1.4236629891980808, -1.474561544920135, 4.145200490700179, -0.10345825312111441, -2.486573972171318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11609456321952229, 0.08725641785299225, -0.005046556891630503, -0.17063119221573195, 0.0031062276650514415, -0.12475807999134682, 0.002402721679814595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.42043144158421, -0.5395829399993146, 0.44340569001868446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.964379767591536e-05, 0.0, 0.0051398104052893375, 0.0, -0.0030537449226994626, 0.005547467537400983, 0.00994558616001968, -0.050089794572297924, 0.01549115260514667, -1.293554741874651e-07, -0.01292672856361362, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006721622035506979, 0.02095784899709504, 0.0005688694818115101, 0.0002253076733215942, 0.0007152903398464851, -0.0006347324102761264, 1.0877456978425782e-11, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.024246726018825313, -0.002906259961562272, 0.004863131106137004]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524635734915108, 0.0, 0.10593104038006644, 0.0, -0.43057684410276603, -0.10884316570100643, -1.4231735090549147, -1.4769482763375057, 4.145929685259788, -0.10345825341644023, -2.487198714891492, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11641439453289071, 0.08825603321375018, -0.0050206092363928225, -0.17062125274194356, 0.00313916308548637, -0.12478562146172324, 0.0024027216802048113, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4215885267665547, -0.5397211094653114, 0.44363784764567277]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.598191819541807e-05, 0.0, 0.004494969034374295, 0.0, -0.0028071232318923945, 0.005642473349657707, 0.009789602863322599, -0.04773462834741495, 0.01458389119218786, -5.906516286848044e-09, -0.012494854403477175, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006396626267368406, 0.01999230721515869, 0.0005189531047535984, 0.0001987894757678545, 0.0006587084086985737, -0.0005508294075284662, 7.804326224009938e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.02314170364689233, -0.002763389319935588, 0.004643152539765884]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.252467739865164, 0.0, 0.10614580339440124, 0.0, -0.43070548762660604, -0.10855658712638953, -1.4226915504491129, -1.479223076025764, 4.146615470099531, -0.10345825787520677, -2.4878026118170773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11671409921661106, 0.0891979329372975, -0.00499692075396499, -0.17061166236190262, 0.0031694186990919152, -0.12481238850871189, 0.0024027216804847827, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4226929836684181, -0.5398524850348708, 0.4438592521182718]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.332747306456586e-05, 0.0, 0.004295260286696001, 0.0, -0.002572870476800208, 0.005731571492337872, 0.009639172116036777, -0.045495993765169045, 0.013715696794846284, -8.917533067036723e-08, -0.012077938511707104, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0059940936744071515, 0.018837994470946428, 0.0004737696485566646, 0.0001918076008191951, 0.0006051122721109054, -0.0005353409397728478, 5.599425198486464e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.022089138037269307, -0.002627511391187949, 0.004428089451981261]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524716859677797, 0.0, 0.10633475718654596, 0.0, -0.43082305276414157, -0.10826551205490864, -1.422216806660039, -1.481391488195598, 4.147259574200346, -0.10345825826889866, -2.4883865709276605, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11699138872585549, 0.09007709364228711, -0.004975206159162721, -0.17060329202444285, 0.0031972266101797362, -0.12483589289191199, 0.002402721680685656, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.423747262913884, -0.5399774016702159, 0.44407020923412377]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.892205231327277e-05, 0.0, 0.0037790758428943826, 0.0, -0.0023513027507103147, 0.005821501429617749, 0.009494875781479154, -0.043368243396681584, 0.012882082016302334, -7.873837879013814e-09, -0.011679182211665131, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005545790184888488, 0.017583214099792337, 0.000434291896045383, 0.00016740674919524815, 0.0005561582217564198, -0.0004700876640021326, 4.017459232354812e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.021085584909318524, -0.002498332706901068, 0.0042191423170392095]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524753745920427, 0.0, 0.10651870813228476, 0.0, -0.43093022795364755, -0.10797035308305296, -1.4217490083092552, -1.4834587127742427, 4.147863971224743, -0.10345826133416983, -2.4889513403214854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11724596007680599, 0.09089383235207912, -0.004955156674448521, -0.17059513401288232, 0.00322288605442226, -0.12485927295140747, 0.0024027216808297776, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.424753689755081, -0.5400961804005612, 0.44427111742136455]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 7.377248526034217e-05, 0.0, 0.0036790189147758, 0.0, -0.002143503790119236, 0.005903179437113761, 0.009355967015673289, -0.04134449157289196, 0.012087940487950637, -6.13054232698171e-08, -0.011295387876499889, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005091427019009989, 0.016334774195840288, 0.00040098969428398776, 0.00016316023121097875, 0.0005131888848504735, -0.0004676011899097486, 2.882434891018568e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020128536823939683, -0.002375574606904648, 0.004018163744815867]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524787788106196, 0.0, 0.10668304225041257, 0.0, -0.4310277035766627, -0.1076711703571787, -1.4212878575381216, -1.485429700571354, 4.148430397309103, -0.10345826174528196, -2.4894978236195318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11747859425597898, 0.09165100377170586, -0.004936501362399924, -0.17058793057651367, 0.0032466824113629176, -0.12488013963685018, 0.0024027216809331814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4257144489094233, -0.5402091279840887, 0.4444624133123931]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.808437153732487e-05, 0.0, 0.0032866823625562844, 0.0, -0.0019495124603028198, 0.005983654517485078, 0.009223015422672743, -0.03941975594222403, 0.011328521687197097, -8.222242744538874e-09, -0.01092966596093072, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004652683583459854, 0.015143428392534807, 0.0003731062409719403, 0.00014406872737276317, 0.00047592713881315093, -0.0004173337088542328, 2.06808094903569e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.019215183086844927, -0.0022589516705498287, 0.0038259178205714748]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524819008345845, 0.0, 0.10684616128974027, 0.0, -0.43111616885107557, -0.10736833562159828, -1.4208330848480126, -1.4873091025667247, 4.14896071589166, -0.10345826410485444, -2.490026782683878, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11769087464088479, 0.09235343662341491, -0.004918998192612217, -0.1705807873377292, 0.0032688901530525116, -0.1249012880951034, 0.0024027216810073716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4266316249459219, -0.5403165362231217, 0.4446445630982576]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 6.244047929864852e-05, 0.0, 0.003262380786553835, 0.0, -0.0017693054882575406, 0.006056694711608286, 0.009095453802178601, -0.03758803990741561, 0.010606371651151374, -4.719144959587418e-08, -0.01057918128692068, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.004245607698116235, 0.014048657034181105, 0.00035006339575414393, 0.00014286477568966547, 0.00044415483379188004, -0.00042296916506411465, 1.4838006615542238e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.018343520729972865, -0.0021481647806605364, 0.003642995717290597]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25248474625669926, 0.0, 0.10701404662060518, 0.0, -0.4311962775832543, -0.10706213025485642, -1.4203844178802578, -1.4891013276386371, 4.149456672068131, -0.10345826695097833, -2.490538988087432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11788457002442443, 0.09300611020786191, -0.00490245849495804, -0.17057363945648912, 0.0032897347396003214, -0.12492337526522385, 0.002402721681060601, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4275071979300304, -0.5404186819974677, 0.44481802595938247]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.690844229531458e-05, 0.0, 0.003357706617298197, 0.0, -0.0016021746435744832, 0.006124107334837373, 0.008973339355094466, -0.03584450143824733, 0.009919123529411322, -5.692247788077616e-08, -0.010244108071072323, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0038739076707928, 0.01305347168893981, 0.00033079395308353317, 0.00014295762480124143, 0.000416891730956194, -0.0004417434024090064, 1.0645929494327913e-12, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017511459682169783, -0.002042915486918923, 0.003469257222496691]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524873195837004, 0.0, 0.10718727730866164, 0.0, -0.4312686404900011, -0.10675272435527558, -1.4199415794425212, -1.4908105613202647, 4.149919876349894, -0.10345826981376927, -2.4910352214982967, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11806144583505773, 0.0936137367221106, -0.004886739421437854, -0.17056659356990211, 0.003309396004975799, -0.12494627637487345, 0.0024027216810987924, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4283430487038942, -0.5405158277826762, 0.44498324389653]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.1466540023485414e-05, 0.0, 0.003464613761129012, 0.0, -0.0014472581349360082, 0.006188117991616877, 0.008856768754733938, -0.03418467363255006, 0.009264085635251627, -5.725581868737553e-08, -0.009924668217298184, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0035375162126659305, 0.012152530284973817, 0.00031438147040371205, 0.00014091773174026789, 0.0003932253075095509, -0.00045802219299204323, 7.638210276439825e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.016717015477274378, -0.0019429157041698057, 0.0033043587429501444]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25248962769742034, 0.0, 0.10736433148657494, 0.0, -0.431333822634857, -0.10644019931569673, -1.419504290214717, -1.4924407791350558, 4.150351816644547, -0.10345827212079356, -2.491516263140614, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11822315837711983, 0.09418054994632133, -0.004871735877537195, -0.17055974878967384, 0.003328013877569058, -0.12496965582159764, 0.0024027216811261937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4291409658822323, -0.5406082222689998, 0.44514063666456366]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.6162274399102916e-05, 0.0, 0.0035410835582661048, 0.0, -0.0013036428971182359, 0.006250500791576933, 0.0087457845560824, -0.032604356295823055, 0.008638805893064528, -4.614048582057343e-08, -0.009620832846350106, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0032342508412419686, 0.01133626448421468, 0.0003000708780131881, 0.00013689560456526468, 0.0003723574518651859, -0.0004675889344839244, 5.480240711177716e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015958343566763726, -0.0018478897264734883, 0.003147855360673664]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249167948626344, 0.0, 0.10754306922408581, 0.0, -0.43139234430061313, -0.10612458699755443, -1.4190722732372134, -1.4939957565565247, 4.150753881996881, -0.10345827318844707, -2.491982874629639, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11837120961281215, 0.09471024616845379, -0.0048573724555174645, -0.17055316743702842, 0.0033456954258704948, -0.1249931753402874, 0.0024027216811458533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4299026529050363, -0.5406961010189989, 0.44529060023858547]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 4.103577686229883e-05, 0.0, 0.0035747547502174557, 0.0, -0.0011704333151225726, 0.006312246362845803, 0.008640339550071258, -0.03109954842937842, 0.00804130704667184, -2.135307021638489e-08, -0.009332229780496977, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0029610247138464915, 0.010593924442649278, 0.0002872684403946214, 0.0001316270529081837, 0.00035363096602873624, -0.0004703903737952492, 3.9319470425399304e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.015233740456079944, -0.0017575749999807853, 0.002999271480435555]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524934911260325, 0.0, 0.10772249826139851, 0.0, -0.4314446864618676, -0.10580604919695182, -1.4186452695148812, -1.4954790630762134, 4.151127467039792, -0.10345827410380912, -2.4924357233240344, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11850695535402547, 0.09520608139217204, -0.004843593926912102, -0.1705470186276672, 0.0033625245338653235, -0.12501671743944043, 0.0024027216811599588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4306297411069726, -0.5407796869910159, 0.44543350951879745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.623279538113905e-05, 0.0, 0.0035885807462540343, 0.0, -0.0010468432250894868, 0.006370756012052337, 0.008540074446642143, -0.02966613039377476, 0.007471700858234771, -1.830724096789972e-08, -0.00905697388790408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0027149148242662773, 0.009916704474364987, 0.0002755705721072495, 0.00012297618722484092, 0.00033658215989657356, -0.00047084198306061474, 2.821081843409112e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.014541764038728505, -0.0016717194403401657, 0.0028581856042399407]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249507368369367, 0.0, 0.10790216023418471, 0.0, -0.4314912916425668, -0.10548477808715775, -1.4182230299738428, -1.496894084327711, 4.151473919356777, -0.10345827501599586, -2.4928754267687028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11863159711450412, 0.09567087061012845, -0.004830360970047671, -0.17054144756277034, 0.0033785659604634423, -0.1250402426708643, 0.002402721681170079, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4313237897442812, -0.5408591913684799, 0.44556971772598714]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.165115322443363e-05, 0.0, 0.003593239455723793, 0.0, -0.0009321036139827227, 0.006425422195881235, 0.008444790820768258, -0.028300425029951996, 0.006929046339684343, -1.824373477070205e-08, -0.008794068893368898, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.002492835209573, 0.009295784359128147, 0.00026465913728860755, 0.00011142129793676669, 0.00032082853196237427, -0.00047050462847774235, 2.0240615372600666e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.013880972746170357, -0.0015900875492814758, 0.0027241641437940113]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524964366796926, 0.0, 0.10808181540993243, 0.0, -0.43153256628691666, -0.1051609532564025, -1.4178053117320677, -1.498244037227448, 4.151794518855292, -0.1034582759460892, -2.4933025732228913, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11874619447415971, 0.09610704663542627, -0.004817645697155328, -0.17053655410781382, 0.0033938700611185904, -0.12506373684919642, 0.0024027216811773403, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4319862876542928, -0.5409348142978782, 0.44569955731604965]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7259919979148523e-05, 0.0, 0.0035931035149544504, 0.0, -0.0008254928869975312, 0.006476496615105239, 0.00835436483549922, -0.02699905799473933, 0.006411989970306879, -1.8601866734863772e-08, -0.008542929083766054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0022919471931118207, 0.008723520505956296, 0.00025430545784686375, 9.786909913044658e-05, 0.00030608201310296235, -0.00046988356664205504, 1.4522177436833575e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01324995820023286, -0.0015124585879634838, 0.0025967918012505995]\n accelerations: []\n effort: []\n time_from_start: \n secs: 11\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524975897731293, 0.0, 0.1082613245810364, 0.0, -0.43156888390044784, -0.10483474255969862, -1.4173918780831523, -1.4995319795682136, 4.152090481723463, -0.10345827693153219, -2.4937177233840915, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11885168415373029, 0.09651673421248405, -0.0048054277491277105, -0.17053240220673796, 0.0034084770949922806, -0.1250871945495201, 0.00240272168118255, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4326186565664267, -0.5410067455283744, 0.44582334161554116]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.3061868733526988e-05, 0.0, 0.003590183422079326, 0.0, -0.0007263522706236663, 0.006524213934077648, 0.008268672978310567, -0.02575884681531397, 0.005919257363424423, -1.9708859711931857e-08, -0.008303003224001432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0021097935914117273, 0.008193751541155599, 0.00024435896055235415, 8.303802151746029e-05, 0.00029214067747380094, -0.0004691540064737523, 1.0419329339563495e-13, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012647378242680194, -0.0014386246099239112, 0.002475685989830201]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249854263872257, 0.0, 0.10844059233646682, 0.0, -0.43160058812608276, -0.10450631084444476, -1.4169824992484992, -1.5007608179600203, 4.152362968614254, -0.10345827799900396, -2.49412140859432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11894889820507813, 0.0969018145221682, -0.004793691364773112, -0.1705290299851458, 0.0034224205400884117, -0.12511061230370477, 0.002402721681186288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4332222545990734, -0.5410751649934131, 0.4459413664627785]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.905731186535969e-05, 0.0, 0.003585355108608104, 0.0, -0.0006340845126982769, 0.006568634305077152, 0.008187576693060727, -0.024576767836132874, 0.005449737815820441, -2.134943542660433e-08, -0.008073704204571095, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0019442810269567703, 0.007701606193682989, 0.00023472768709197734, 6.744443184321146e-05, 0.0002788689019226203, -0.0004683550836933626, 7.475629903089368e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012071960652933986, -0.0013683893007750431, 0.0023604969447464145]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249930505025237, 0.0, 0.10861956606690039, 0.0, -0.4316279956097521, -0.10417583216528904, -1.4165769534495283, -1.5019333146888618, 4.152613094531208, -0.10345827915103799, -2.494514127359418, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1190385797522423, 0.09726397687264945, -0.004782423291103255, -0.17052645997797503, 0.003435729514873332, -0.12513398978184814, 0.00240272168118897, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4337983797537546, -0.541140243342709, 0.44605391172283676]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.5248230595957057e-05, 0.0, 0.003579474608671497, 0.0, -0.0005481496733869447, 0.006609573583114158, 0.008110915979417566, -0.023449934576831845, 0.005002518339096259, -2.3040680536778058e-08, -0.007854375301952859, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0017936309432833955, 0.007243247009625181, 0.00022536147339713804, 5.140014341561327e-05, 0.0002661794956984067, -0.00046754956286728007, 5.3635930523944134e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.011522503093624452, -0.0013015669859192287, 0.002250905201165234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524998883945725, 0.0, 0.10879840095990594, 0.0, -0.43165139913500833, -0.10384353283451074, -1.4161750304355354, -1.503052090635296, 4.15284195579909, -0.10345828049217003, -2.4948963284139, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11912139826657485, 0.09760476824587222, -0.0047716110186357035, -0.17052472744838323, 0.0034484308682004414, -0.12515735561646552, 0.002402721681190894, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4343482746843161, -0.5412021423929178, 0.44616124302137655]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.1666886402755246e-05, 0.0, 0.0035766978601109024, 0.0, -0.00046807050512428713, 0.006645986615565914, 0.00803846027985905, -0.022375518928682902, 0.0045772253576376425, -2.6822640793726503e-08, -0.007644021089639064, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016563702866510554, 0.006815827464455172, 0.00021624544935104276, 3.465059183604228e-05, 0.00025402706654218657, -0.00046731669234727766, 3.848255036555525e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010997898611231634, -0.0012379810041748445, 0.0021466259707954268]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525003043050153, 0.0, 0.10897741810911275, 0.0, -0.43167106991511683, -0.10350970293975632, -1.4157765321287095, -1.5041196312536773, 4.153050639099335, -0.10345828232845566, -2.495268407235448, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11919795940845908, 0.09792561977080978, -0.0047612419515256875, -0.1705238767980194, 0.0034605502131995463, -0.12518075966064138, 0.0024027216811922745, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.434873130019234, -0.5412610155948835, 0.44626361290612115]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 8.318208855958413e-06, 0.0, 0.003580342984136435, 0.0, -0.00039341560216962844, 0.006676597895088218, 0.007969966136519546, -0.021350812367625347, 0.004173666004893266, -3.672571269730873e-08, -0.007441576430964209, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0015312228376845422, 0.006417030498751312, 0.00020738134220031138, 1.7013007276802883e-05, 0.00024238689998210168, -0.0004680808835174641, 2.7610347528415173e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010497106698361675, -0.0011774640393141323, 0.002047397694891744]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250056199777027, 0.0, 0.10915685015769623, 0.0, -0.43168725851356654, -0.10317464192197127, -1.4153812681838234, -1.5051382992175388, 4.153240193213947, -0.10345828462556604, -2.495630730789191, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11926880806461108, 0.09822784316821245, -0.004751303726670063, -0.17052392839602434, 0.0034721116582265535, -0.12520423361065364, 0.002402721681193265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4353740844553402, -0.5413170085581582, 0.4463612610236851]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 5.153855099642811e-06, 0.0, 0.003588640971669454, 0.0, -0.00032377196899458714, 0.006701220355701015, 0.007905278897723933, -0.020373359277231502, 0.0037910822922489857, -4.594220747090706e-08, -0.00724647107486297, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0014169731230401397, 0.00604446794805331, 0.0001987644971124929, -1.0319600992743894e-06, 0.0002312289005401437, -0.0004694790002449638, 1.9809791266289073e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010019088722122042, -0.0011198592654958323, 0.001952962351279709]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525006716811663, 0.0, 0.10933681581224193, 0.0, -0.4317001967343679, -0.10283867091869037, -1.4149890567719554, -1.5061103393116713, 4.153411638040677, -0.1034582873773915, -2.49598363339406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11933443571876777, 0.09851264759327906, -0.004741783894691773, -0.17052488196939983, 0.003483138278404697, -0.12522779039415452, 0.002402721681193976, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4358522275973402, -0.5413702594531301, 0.446454415053972]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.1936679209689417e-06, 0.0, 0.003599313090913898, 0.0, -0.00025876441602703073, 0.00671942006561824, 0.00784422823735728, -0.01944080188265033, 0.0034288965345937853, -5.503650913848695e-08, -0.007058052097376657, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0013125530831337255, 0.005696088501332263, 0.0001903966395657832, -1.907146750953426e-05, 0.00022053240356287258, -0.00047113567001759183, 1.4213070995845063e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009562862839999096, -0.001065017899437826, 0.0018630806057371003]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525006446467645, 0.0, 0.10951734351084795, 0.0, -0.4317100995416548, -0.10250215550925255, -1.4145997262435115, -1.507037881779375, 4.1535659793374275, -0.10345829057457463, -2.4963274080266666, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11939528715516118, 0.09878115489616926, -0.004732669679308067, -0.17052672350806422, 0.0034936524958262124, -0.12525142978831266, 0.002402721681194486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.436308603230223, -0.5414208993717876, 0.44654329168760876]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -5.406880356466864e-07, 0.0, 0.0036105539721204877, 0.0, -0.00019805614573874199, 0.006730308188756361, 0.007786610568879249, -0.018550849354073744, 0.0030868259350038023, -6.394366261586799e-08, -0.006875492652131085, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0012170287278680466, 0.005370146057804128, 0.00018228430767412249, -3.683077328768231e-05, 0.0002102843484303052, -0.0004727878831630051, 1.0197552520541675e-14, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.009127512657657266, -0.0010127983731496384, 0.001777532672735091]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250024683646244, 0.0, 0.10967991520443256, 0.0, -0.4317170846093674, -0.10216053568502476, -1.4142127050299458, -1.5079235121463859, 4.153701428164187, -0.10345829079875102, -2.496664459227406, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11945154707052118, 0.09903336044673502, -0.004723986163199914, -0.17052714226277949, 0.0035036329183928214, -0.1252724761111067, 0.002402721681194852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4367439888839186, -0.5414690608296366, 0.44662804378220056]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.956206041913836e-06, 0.0, 0.0032514338716922745, 0.0, -0.000139701354252904, 0.006832396484556028, 0.007740424271313811, -0.01771260734021741, 0.0027089765351797288, -4.48352785201282e-09, -0.006741024014788602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0011251983072000742, 0.005044111011315333, 0.0001736703221630695, -8.375094305022139e-06, 0.00019960845133218364, -0.00042092645588075964, 7.316510112001781e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008707713073914315, -0.0009632291569807933, 0.0016950418918363368]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249976094537047, 0.0, 0.10982153734125799, 0.0, -0.4317213397255061, -0.1018145229347189, -1.4138278636710668, -1.5087691101015954, 4.153819103841309, -0.10345829105358656, -2.496994885558162, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11950361384393553, 0.0992703840138673, -0.004715714819038201, -0.17052617261007352, 0.0035131068050698808, -0.1252905957803363, 0.0024027216811951142, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.437159340840383, -0.5415148609795127, 0.4467088694299034]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.717821839101677e-06, 0.0, 0.0028324427365087313, 0.0, -8.510232277329901e-05, 0.006920255006116923, 0.007696827177577579, -0.016911959104189262, 0.002353513542450804, -5.096710801979133e-09, -0.006608526615123668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0010413354682871094, 0.004740471342645429, 0.00016542688323424834, 1.9393054119149533e-05, 0.0001894777335411861, -0.0003623933845919471, 5.249428252535549e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.008307039129290967, -0.000916002997520956, 0.001616512954056842]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250137358761393, 0.0, 0.11013386519272177, 0.0, -0.43172381699032564, -0.10151690216714954, -1.413446790007604, -1.509571672313606, 4.153949458913465, -0.1034606672104238, -2.497296659055861, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11955705046445445, 0.09951887041172326, -0.0047068856210787345, -0.17055112558538887, 0.0035231734292377574, -0.12533706312028953, 0.0024027216811953024, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4375583357137551, -0.5415583897038049, 0.44678677310347054]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 3.225284486937632e-05, 0.0, 0.006246557029275519, 0.0, -4.954529639090937e-05, 0.0059524153513873124, 0.007621473269254952, -0.016051244240207534, 0.0026071014431222326, -4.752313674480964e-05, -0.0060354699539849135, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.001068732410378395, 0.00496972795711925, 0.00017658395918932618, -0.0004990595063071539, 0.00020133248335753643, -0.0009293467990643485, 3.766343035045179e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.007979897467438416, -0.0008705744858426893, 0.0015580734713430563]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250123319896933, 0.0, 0.11046367066295873, 0.0, -0.43172411246470266, -0.1012275962349581, -1.4130692874470165, -1.5103361374992912, 4.154070511372676, -0.10346066756890546, -2.4975869636407295, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11960598277190915, 0.09974912229180803, -0.004698624136039197, -0.17057913801075325, 0.0035325697273976974, -0.12538669966808283, 0.0024027216811954378, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4379396460698677, -0.5415997397477195, 0.4468611627746132]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.8077728922242697e-06, 0.0, 0.006596109404739374, 0.0, -5.909487540367595e-06, 0.005786118643828867, 0.007550051211747151, -0.015289303713704506, 0.002421049184198503, -7.16963324977728e-09, -0.005806091697372856, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0009786461490941753, 0.004605037601695376, 0.00016522970079075943, -0.0005602485072877552, 0.00018792596319879522, -0.0009927309558659463, 2.7022641121889272e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0076262071222490515, -0.0008270008782914171, 0.0014877934228533375]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525007292779986, 0.0, 0.1107730504389141, 0.0, -0.4317221549418397, -0.10093469709835044, -1.4126943808247012, -1.5110653811061423, 4.154176157822125, -0.10346067243821684, -2.497871222673151, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11964997869359197, 0.0999584462207124, -0.004691046235532908, -0.1706037962145071, 0.003541169409691249, -0.12543216789452802, 0.002402721681195535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4383034194738122, -0.5416390222467217, 0.4469320388955833]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.0078419414195723e-05, 0.0, 0.006187595519107414, 0.0, 3.91504572596842e-05, 0.0058579827321530685, 0.007498132446305204, -0.01458487213702452, 0.00211292898898495, -9.738622780715217e-08, -0.005685180648430174, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0008799184336562582, 0.004186478578087279, 0.0001515580101257763, -0.000493164075077061, 0.00017199364587103618, -0.0009093645289040094, 1.938812223432029e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0072754680788898905, -0.0007856499800441572, 0.0014175224194024325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250017251356, 0.0, 0.11105437173998403, 0.0, -0.43171803357329985, -0.10063668670859607, -1.412321410974244, -1.5117613531275305, 4.154266158791327, -0.10346067775202093, -2.498150486312361, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11968981161970005, 0.1001502113900759, -0.004684038876394425, -0.1706240592715194, 0.0035491032938626296, -0.12547217808998107, 0.0024027216811956043, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4386503743922627, -0.541676345568565, 0.44699957814219665]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1135288771855741e-05, 0.0, 0.0056264260213985855, 0.0, 8.242737079706473e-05, 0.005960207795087284, 0.007459397009145204, -0.013919440427765144, 0.0018000193840611973, -1.0627608180664975e-07, -0.005585272784201395, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007966585221615804, 0.00383530338727013, 0.00014014718276967927, -0.0004052611402459578, 0.00015867768342760926, -0.0008002039090609101, 1.3910531636821325e-15, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006939098369007831, -0.0007464664368673386, 0.001350784932266651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249960517041925, 0.0, 0.11130994429950984, 0.0, -0.4317119055304327, -0.10033583263386532, -1.4119501084311115, -1.5124255118211523, 4.154342387483122, -0.10346068276661556, -2.498424169608367, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11972633334296749, 0.10032824509932194, -0.004677469989685064, -0.1706406192012513, 0.0035565230894252543, -0.12550739685946583, 0.002402721681195654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4389814060540655, -0.5417118081757079, 0.4470639944459756]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.1346862815409195e-05, 0.0, 0.005111451190516094, 0.0, 0.00012256085734345352, 0.006017081494614951, 0.007426050862649289, -0.013283173872437229, 0.0015245738358913262, -1.0029189264180334e-07, -0.005473665920116116, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007304344653489404, 0.003560674184920708, 0.00013137773418721942, -0.0003311985946376716, 0.00014839591125249827, -0.0007043753896950072, 9.980486718486138e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006620633236054182, -0.0007092521428554155, 0.0012883260755792822]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2525001384373557, 0.0, 0.1117050192891867, 0.0, -0.43170436900186454, -0.10006576368687699, -1.4115803122696655, -1.5130566697447685, 4.154424442521445, -0.10346308571835948, -2.4986785013611303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1197646631853682, 0.10051870249933413, -0.004670340489154515, -0.17067602305255583, 0.003564547883005011, -0.12556336701526652, 0.00240272168119569, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4392991754655564, -0.541745510335605, 0.44712608062212517]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0665338728663511e-05, 0.0, 0.007901499793537149, 0.0, 0.0001507305713631738, 0.005401378939766552, 0.0073959232289202035, -0.01262315847232582, 0.0016411007664546785, -4.805903487831204e-05, -0.005086635055265355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007665968480142496, 0.003809148000243815, 0.00014259001061098394, -0.0007080770260910116, 0.00016049587159513884, -0.00111940311601398, 7.160756158517093e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0063553882298192236, -0.0006740431979440943, 0.0012417235229906737]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25250000610788326, 0.0, 0.11209411001814666, 0.0, -0.4316952662242287, -0.09980524104495966, -1.4112133297647802, -1.5136573042948216, 4.154500725766428, -0.10346308626118651, -2.4989224480148606, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1197995995660239, 0.10069395450060291, -0.004663734164297208, -0.17071145257965203, 0.0035719712807648018, -0.12561846584493908, 0.0024027216811957157, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.439603012924848, -0.5417774931899243, 0.4471854049468531]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -2.646589448364274e-06, 0.0, 0.007781814579199122, 0.0, 0.00018205555271695706, 0.005210452838346618, 0.007339650097706639, -0.012012691001060534, 0.001525664899654792, -1.0856540568420598e-08, -0.004878933074607122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006987276131141497, 0.003505040025375655, 0.00013212649714613355, -0.0007085905419242748, 0.0001484679551958168, -0.001101976593451383, 5.137671509296194e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006076749185834609, -0.0006396570863848082, 0.0011864864945589867]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249962144075555, 0.0, 0.11244605294697997, 0.0, -0.43168457320367054, -0.09954748596863551, -1.4108486459487477, -1.5142293507289228, 4.154567889258225, -0.10346309509115553, -2.4991591516070817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11983089597366163, 0.10085236216300913, -0.004657723870433551, -0.17074203477995611, 0.0035787144210383095, -0.12566726131852235, 0.002402721681195734, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4398931515837508, -0.5418078370077145, 0.4472419948645333]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -7.693342554454928e-06, 0.0, 0.007038858576666083, 0.0, 0.00021386041116345578, 0.0051551015264829705, 0.007293676320648721, -0.011440928682023063, 0.0013432698359509628, -1.765993803859804e-07, -0.004734071844420179, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006259281527545936, 0.0031681532481245478, 0.00012020587727314016, -0.0006116440060817338, 0.00013486280547015766, -0.0009759094716655546, 3.686158203834384e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0058027731780533115, -0.0006068763558047287, 0.0011317983536046066]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249957286519636, 0.0, 0.11291105001908276, 0.0, -0.4316725796237195, -0.09930873162805244, -1.4104845594478104, -1.5147734315263812, 4.154635734494015, -0.10346566666853016, -2.4993823421973334, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11986346121231904, 0.10101988057910342, -0.004651294549655318, -0.17078692635800605, 0.00358590801036463, -0.12573171610384903, 0.002402721681195747, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.440171348248949, -0.5418366595919201, 0.44729646504611703]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.715111832212327e-07, 0.0, 0.009299941442055856, 0.0, 0.00023987159902028637, 0.0047750868116613505, 0.007281730018745863, -0.01088161594916629, 0.0013569047157915284, -5.143154749257046e-05, -0.0044638118050375625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0006513047731483317, 0.0033503683218857206, 0.00012858641556464748, -0.0008978315609988181, 0.00014387178652640578, -0.0012890957065336793, 2.644731444288415e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0055639333039663435, -0.0005764516841108768, 0.0010894036316740792]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25249939957111855, 0.0, 0.11336490963706723, 0.0, -0.43165924659737326, -0.09907658820700373, -1.4101227996290768, -1.5152909551032032, 4.154697547813176, -0.10346571652271423, -2.4995971660286918, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11989301202149834, 0.10117313740778036, -0.00464537917342248, -0.17083080453302915, 0.00359251770894912, -0.12579359409639249, 0.0024027216811957565, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4404372423415666, -0.5418639840760764, 0.44734849415962974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -3.4658815559833157e-06, 0.0, 0.009077192359689493, 0.0, 0.00026666052692491386, 0.004642868420974282, 0.007235196374672906, -0.01035047153644131, 0.001236266383221228, -9.970836815166966e-07, -0.0042964766271680185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0005910161835857875, 0.0030651365735388713, 0.00011830752465675056, -0.0008775635004621102, 0.00013219397168979892, -0.0012375598508688114, 1.8975331751156095e-16, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005317881852348869, -0.0005464896831253916, 0.0010405822702546361]\n accelerations: []\n effort: []\n time_from_start: \n secs: 12\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2524991175333611, 0.0, 0.11376903100444105, 0.0, -0.4316445581937212, -0.09884734552449141, -1.4097630225416558, -1.5157834009442641, 4.154751632465885, -0.10346572932866722, -2.4998054134093515, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.11991907507680505, 0.10130929215868707, -0.004640097656576569, -0.1708684626021264, 0.0035984122442281807, -0.12584738954286698, 0.0024027216811957634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.4406911617342395, -0.541889877827432, 0.44739811438904004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 13\n nsecs: 0" - }, - "execution_count": 20, - "metadata": {}, - "output_type": "execute_result" - } - ], + "execution_count": 14, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -551,33 +464,29 @@ "world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", "\n", "# define the constraints\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='DistanceFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cylinder_center_feature,\n", - " robot_feature=robot_point_feature,\n", - " lower_limit=0.03,\n", - " upper_limit=0.03)\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='HeightFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cylinder_center_feature,\n", - " robot_feature=robot_point_feature,\n", - " lower_limit=-0.05,\n", - " upper_limit=0.05)\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='PointingFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cylinder_center_feature,\n", - " robot_feature=robot_pointing_feature)\n", - "gs.motion_goals.add_motion_goal(motion_goal_class='AlignFeatureFunction',\n", - " root_link='map',\n", - " tip_link=gripper_link,\n", - " world_feature=world_cyl_z_axis_feature,\n", - " robot_feature=robot_gripper_z_axis_feature)\n", + "gs.motion_goals.add_distance(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=0.03,\n", + " upper_limit=0.03)\n", + "gs.motion_goals.add_height(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=-0.05,\n", + " upper_limit=0.05)\n", + "gs.motion_goals.add_pointing(root_link='map',\n", + " tip_link=gripper_link,\n", + " goal_point=world_cylinder_center_feature,\n", + " pointing_axis=robot_pointing_feature)\n", "gs.motion_goals.avoid_collision(min_distance=0.1, group1='obstacle')\n", + "gs.motion_goals.add_align_planes(root_link='map',\n", + " tip_link=gripper_link,\n", + " goal_normal=world_cyl_z_axis_feature,\n", + " tip_normal=robot_gripper_z_axis_feature)\n", "gs.add_default_end_motion_conditions()\n", - "gs.execute()\n", + "assert gs.execute().error.code == GiskardError.SUCCESS\n", "\n", "# EXERCISE:\n", "# 1. Change Pose and size of the obstacle and see of the robot behaves." @@ -589,6 +498,121 @@ } } }, + { + "cell_type": "markdown", + "source": [ + "Now, for each constraint a related monitor can be added to observe their progression and collect feedback in the case of failure where one or many constraints cannot be satisfied." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 27, + "outputs": [], + "source": [ + "reset_giskard()\n", + "\n", + "# variables\n", + "gripper_link = 'r_gripper_tool_frame'\n", + "\n", + "# adding the object\n", + "cyl_pose = PoseStamped()\n", + "cyl_pose.header.frame_id = 'map'\n", + "cyl_pose.pose.orientation.w = 1\n", + "cyl_pose.pose.position = Point(2, -0.2, 1.2)\n", + "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", + "\n", + "obstacle_pose = PoseStamped()\n", + "obstacle_pose.header.frame_id = 'mycyl'\n", + "obstacle_pose.pose.orientation.w = 1\n", + "obstacle_pose.pose.position = Point(-0.1, 0.1, 0)\n", + "gs.world.add_box('obstacle', size=(0.02, 0.06, 0.05), pose=obstacle_pose, parent_link='mycyl')\n", + "\n", + "# define the robot features\n", + "robot_pointing_feature = Vector3Stamped()\n", + "robot_pointing_feature.header.frame_id = gripper_link\n", + "robot_pointing_feature.vector = Vector3(1, 0, 0)\n", + "\n", + "robot_point_feature = PointStamped()\n", + "robot_point_feature.header.frame_id = gripper_link\n", + "robot_point_feature.point = Point(0, 0, 0)\n", + "\n", + "robot_gripper_z_axis_feature = Vector3Stamped()\n", + "robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", + "robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "\n", + "# define the world features\n", + "world_cylinder_center_feature = PointStamped()\n", + "world_cylinder_center_feature.header.frame_id = 'mycyl'\n", + "world_cylinder_center_feature.point = Point(0, 0, 0)\n", + "\n", + "world_cyl_z_axis_feature = Vector3Stamped()\n", + "world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", + "world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", + "\n", + "# define the constraints\n", + "gs.motion_goals.add_distance(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=0.0,\n", + " upper_limit=0.0)\n", + "mon_dist = gs.monitors.add_distance(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=-0.001,\n", + " upper_limit=0.001)\n", + "\n", + "gs.motion_goals.add_height(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=-0.05,\n", + " upper_limit=0.05)\n", + "mon_height = gs.monitors.add_height(root_link='map',\n", + " tip_link=gripper_link,\n", + " reference_point=world_cylinder_center_feature,\n", + " tip_point=robot_point_feature,\n", + " lower_limit=-0.05,\n", + " upper_limit=0.05)\n", + "\n", + "gs.motion_goals.add_pointing_at_line(root_link='map',\n", + " tip_link=gripper_link,\n", + " goal_line=world_cyl_z_axis_feature,\n", + " pointing_axis=robot_pointing_feature)\n", + "mon_pointing = gs.monitors.add_pointing_at(root_link='map',\n", + " tip_link=gripper_link,\n", + " goal_point=world_cylinder_center_feature,\n", + " pointing_axis=robot_pointing_feature)\n", + "\n", + "gs.motion_goals.add_align_planes(root_link='map',\n", + " tip_link=gripper_link,\n", + " goal_normal=world_cyl_z_axis_feature,\n", + " tip_normal=robot_gripper_z_axis_feature)\n", + "mon_align = gs.monitors.add_vectors_aligned(root_link='map',\n", + " tip_link=gripper_link,\n", + " goal_normal=world_cyl_z_axis_feature,\n", + " tip_normal=robot_gripper_z_axis_feature)\n", + "\n", + "gs.motion_goals.allow_all_collisions()\n", + "# gs.motion_goals.avoid_collision(min_distance=0.08, group1='obstacle')\n", + "gs.monitors.add_end_motion(f'{mon_dist} and {mon_height} and {mon_align}')\n", + "gs.monitors.add_cancel_motion(gs.monitors.add_local_minimum_reached(), error_message='local minimum reached while monitors are not satisfied')\n", + "assert gs.execute().error.code == GiskardError.SUCCESS" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, { "cell_type": "markdown", "source": [ @@ -607,15 +631,16 @@ }, { "cell_type": "code", - "execution_count": 22, + "execution_count": 16, "outputs": [ { - "data": { - "text/plain": "error: \n code: 0\n msg: ''\ntrajectory: \n header: \n seq: 0\n stamp: \n secs: 0\n nsecs: 0\n frame_id: ''\n joint_names: \n - fl_caster_rotation_joint\n - fl_caster_l_wheel_joint\n - fl_caster_r_wheel_joint\n - fr_caster_rotation_joint\n - fr_caster_l_wheel_joint\n - fr_caster_r_wheel_joint\n - bl_caster_rotation_joint\n - bl_caster_l_wheel_joint\n - bl_caster_r_wheel_joint\n - br_caster_rotation_joint\n - br_caster_l_wheel_joint\n - br_caster_r_wheel_joint\n - torso_lift_joint\n - head_pan_joint\n - head_tilt_joint\n - laser_tilt_mount_joint\n - r_shoulder_pan_joint\n - r_shoulder_lift_joint\n - r_upper_arm_roll_joint\n - r_elbow_flex_joint\n - r_forearm_roll_joint\n - r_wrist_flex_joint\n - r_wrist_roll_joint\n - r_gripper_motor_slider_joint\n - r_gripper_motor_screw_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_l_finger_joint\n - r_gripper_joint\n - l_shoulder_pan_joint\n - l_shoulder_lift_joint\n - l_upper_arm_roll_joint\n - l_elbow_flex_joint\n - l_forearm_roll_joint\n - l_wrist_flex_joint\n - l_wrist_roll_joint\n - l_gripper_motor_slider_joint\n - l_gripper_motor_screw_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_l_finger_joint\n - l_gripper_joint\n - torso_lift_motor_screw_joint\n - brumbrum_x\n - brumbrum_y\n - brumbrum_yaw\n points: \n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2, 0.04188078064629572, -0.36061589913634406, 0.0, -1.0047308067033573, 0.4873679058742573, -0.9487715184807924, -1.392377812172585, -2.331136341128514, -0.45486951448967994, 0.1142679898015531, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8800033424638982, 0.011627231221513427, 1.7382923753144306, -2.030548385746772, -1.486497760500128, -0.10085496898308562, 0.2211702593354379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0, 0.0, 0.0]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19935004775600904, 0.03579287115241836, -0.3486119528240798, 0.0, -1.0026363626456556, 0.487280835369237, -0.9525215184808308, -1.3886278121727262, -2.334886341128509, -0.4522777612376269, 0.11051798980154005, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8762533424668997, 0.015377231220805351, 1.7420423753142413, -2.030174589286868, -1.4902477605001245, -0.10303703296564161, 0.21776153355159686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0006246092742949935, -0.0006253904815580002, -0.0006249658519791201]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879819642, -0.12175818987754719, 0.2400789262452849, 0.0, 0.04188888115403446, -0.0017414101004064207, -0.07499999999999428, 0.07499999999999567, -0.07499999999998637, 0.051835065041060883, -0.07499999999999458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.07499999999999445, 0.0749999999999933, 0.07499999999999102, 0.007475929198080923, -0.0749999999999336, -0.04364127965111987, -0.06817451567682108, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01249218548589987, -0.012507809631160003, -0.012499317039582403]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1987000955118654, 0.024080358963143086, -0.32789257823924267, 0.0, -1.0000374803489949, 0.4871546802127561, -0.9637715184807714, -1.377377812171733, -2.346136341128505, -0.4433442547461819, 0.09926798980154829, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8650033424646424, 0.02662723122095179, 1.753292375314062, -2.027566476647114, -1.501497760500122, -0.11115116089492502, 0.21469408198177917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.002497264252385374, -0.002502732574253318, -0.0012498975577598962]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882872538, -0.23425024378550546, 0.4143874916967424, 0.0, 0.05197764593321432, -0.002523103129618494, -0.22499999999998566, 0.22499999999998815, -0.22499999999992076, 0.17867012982890113, -0.22499999999998604, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.22499999999998438, 0.22499999999998208, 0.2249999999999753, 0.05216225279507682, -0.2249999999998406, -0.1622825585856681, -0.061349031396353684, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0374530995618076, -0.03754684185390636, -0.012498634115615522]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19805014326784395, 0.009163766288081052, -0.30283686996554215, 0.0, -0.9978836509932686, 0.4851544679925391, -0.9843965184807717, -1.3567528121717378, -2.361136341128498, -0.4246496660033108, 0.07864298980154821, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8453176331660688, 0.04725223122095102, 1.773899118231944, -2.0212985733357707, -1.5191122127905634, -0.12891035713212942, 0.21571790462598486, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.00593046539789056, -0.005944526059152402, -0.001249795117342325]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880429049, -0.2983318535012406, 0.50111416547401, 0.0, 0.04307658711452586, -0.04000424440434057, -0.4125000000000071, 0.41249999999990455, -0.2999999999998565, 0.37389177485742187, -0.41250000000000153, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.393714185971473, 0.41249999999998466, 0.41213485835763863, 0.12535806622686507, -0.3522890458088269, -0.3551839247440879, 0.02047645288411372, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06866402291010373, -0.06883586969798167, 2.048808351421544e-06]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019102358305, -0.00709741536618394, -0.27618797068082396, 0.0, -0.9968266099456617, 0.4807097474673838, -1.012834018480867, -1.329453416384282, -2.3761363412057532, -0.39782084205093726, 0.05020548980146977, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.8208447598151705, 0.07568973122064448, 1.800112604085682, -2.011791355899208, -1.539341117554956, -0.15256462167730755, 0.22458300148417265, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.010670050348371164, -0.010684107773593876, 3.414691331167421e-07]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044885217824, -0.3252236330852998, 0.5329779856943639, 0.0, 0.021140820952136388, -0.08889441050310486, -0.5687500000019068, 0.5459879157491171, -0.3000000015451077, 0.5365764790474705, -0.5687500000015688, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.48945746701796455, 0.5687499999938693, 0.524269717074763, 0.1901443487312527, -0.4045780952878528, -0.4730852909035629, 0.17730193716375559, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09479169900961207, -0.09479163428882947, 0.025002731729508836]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023877955897, -0.023275380310688133, -0.24927729873138352, 0.0, -0.9969321633200399, 0.47492671830707056, -1.0475840184809435, -1.2992296247946589, -2.387386341360299, -0.3643577828890391, 0.015455489801406985, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7949376047310681, 0.11043973122040035, 1.8281828328752878, -1.999624880566592, -1.5584344747933812, -0.17836395453046028, 0.24322058219932916, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.016476978965513554, -0.016460472163217305, 0.0026386413666429596]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880482017, -0.32355929889008384, 0.5382134389888087, 0.0, -0.002111067487563234, -0.11566058320626539, -0.6950000000015298, 0.604475831792462, -0.22500000309091267, 0.6692611832379638, -0.6950000000012557, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5181431016820468, 0.6949999999951174, 0.561404575792115, 0.24332950665232017, -0.38186714476850203, -0.5159866570630381, 0.3727516143031302, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11613857234284779, -0.11552728779246856, 0.052765997950196854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028653528302, -0.038387512901389045, -0.22263388530520128, 0.0, -0.9975569893600359, 0.46866534813531446, -1.08738401848104, -1.2693116176575314, -2.392228118071455, -0.3255873386435427, -0.024344510198662142, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.769731099419793, 0.15023973122006226, 1.8543598053360464, -1.9851864466453972, -1.5730208830209418, -0.20255835612588932, 0.2700018994619217, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.023150257086495492, -0.023053618704875423, 0.0060401055027243565]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044885518812, -0.30224265181401816, 0.5328682685236444, 0.0, -0.012496520799919598, -0.12522740343512184, -0.7960000000019307, 0.5983601427425489, -0.09683553422311905, 0.775408884909927, -0.7960000000013824, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5041301062255001, 0.795999999993238, 0.5235394492151696, 0.2887686784238945, -0.29172816455121264, -0.48388803190858065, 0.535626345251851, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13346556241963872, -0.1318629308331624, 0.06802928272162793]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1954503342912846, -0.05189640655835118, -0.19640894217534255, 0.0, -0.997957994660567, 0.46229408036443376, -1.1312240184811078, -1.2410058591494508, -2.392044389348854, -0.28257098633122174, -0.06818451019868726, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.7450870087007764, 0.1913397312202789, 1.8808590598573596, -1.9689808643747688, -1.5858220897600042, -0.22779991562278304, 0.30342695327188174, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.030526583689117773, -0.030289954890102812, 0.009579782743985136]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879968351, -0.2701778731392426, 0.5244988625971749, 0.0, -0.008020106010623185, -0.127425355417614, -0.8768000000013583, 0.5661151701616131, 0.0036745744520212675, 0.8603270462464196, -0.8768000000005023, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4928818143803325, 0.8220000000043325, 0.5299850904262638, 0.32411164541257026, -0.25602413478124675, -0.5048311899378742, 0.6685010761992001, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.14752653205244562, -0.14472672370454778, 0.0707935448252156]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19480038204750924, -0.06378126722720769, -0.17059839925484244, 0.0, -0.9981487691106901, 0.4543105869613007, -1.1782960184812163, -1.2161436618652872, -2.3871803808699363, -0.23905872577160636, -0.11525651019870915, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.71995605760354, 0.22998973123564354, 1.9113745871558452, -1.9514277816677486, -1.6001507887703625, -0.2578386330210367, 0.3421669963198305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0384733004933539, -0.038032577329402864, 0.013007740500501954]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044875507352, -0.2376972133771302, 0.5162108584100022, 0.0, -0.0038154890024610175, -0.15966986806266026, -0.9414400000021712, 0.49724394568327146, 0.09728016957835495, 0.8702452075829168, -0.9414400000004377, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5026190219447283, 0.7730000003072925, 0.6103105459697143, 0.3510616541404071, -0.2865739802071669, -0.6007743479650738, 0.7748008609589757, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15893433608472254, -0.1548524487860011, 0.06855915513033636]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1941504298034978, -0.07407266533993596, -0.14514291568062926, 0.0, -0.9982222795025852, 0.44212143758627886, -1.2279536184812154, -1.1961315056313289, -2.3766181156129362, -0.19880055732544735, -0.16491411019870095, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.694184024184408, 0.2624397346733757, 1.945090331198005, -1.932668688128486, -1.6166888973316518, -0.2938696069391025, 0.38515903075810215, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.0468828938222008, -0.04617333404578674, 0.016242132029195996]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488022866, -0.20582796225456554, 0.5091096714842638, 0.0, -0.0014702078379038221, -0.2437829875004373, -0.9931519999999829, 0.400243124679165, 0.21124530514000023, 0.805163368919551, -0.9931519999998355, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5154406683826414, 0.6490000687546438, 0.674314880843196, 0.37518187078525195, -0.3307621712257831, -0.7206194783613166, 0.8598406887654334, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.168191866576938, -0.1628151343276775, 0.06468783057388082]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19350047756019342, -0.08283073801450576, -0.11996749640256044, 0.0, -0.9981119532275723, 0.4248057884027918, -1.2779536435317629, -1.181742331772493, -2.3609615205313768, -0.16554648081212237, -0.2149141101968043, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6676919455340091, 0.28916553827362484, 1.9806422573554816, -1.9128932292758807, -1.635924752856884, -0.3346943860390268, 0.43155265830326833, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.05566840869963582, -0.05462664523497049, 0.019268282626884434]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904486608754, -0.17516145349139595, 0.5035083855613763, 0.0, 0.002206525500258042, -0.3463129836697408, -1.00000050101095, 0.287783477176716, 0.3131319016311939, 0.6650815302664999, -0.9999999999620668, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5298415730079769, 0.5345160720049826, 0.7110385231495326, 0.39550917705210575, -0.3847171105046487, -0.8164955819984858, 0.9278725509033235, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17571029754870024, -0.16906622378367492, 0.06052301195376879]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052531632355, -0.09012282790928375, -0.0949945158128233, 0.0, -0.9976918005572822, 0.4026379572150482, -1.3279536685823663, -1.1730634727276574, -2.34133298490516, -0.14304649451542698, -0.2649141101962771, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6403587455404234, 0.3122121626510556, 2.016897499986658, -1.8923979070698704, -1.658532571824784, -0.37935420931224917, 0.4806675603382588, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.06475954680006092, -0.06332478802745585, 0.02208809866024527]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877397654, -0.14584179789555962, 0.49945961179474274, 0.0, 0.008403053405801395, -0.4433566237548721, -1.000000501012068, 0.17357718089671292, 0.39257071252433307, 0.4499996916138813, -0.9999999999894564, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.546663999871713, 0.46093248754861493, 0.7251048526235306, 0.40990644412020644, -0.4521563793579988, -0.8931964654644475, 0.982298040699809, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18182276200850217, -0.1739628558497072, 0.05639632066721667]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057307258226, -0.09594093552277741, -0.07014707637061485, 0.0, -0.9965656124294026, 0.3766803497512302, -1.3779536936204972, -1.169030167948862, -2.3188933312720117, -0.12755060186777403, -0.3149141101951814, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.6121516039012516, 0.33322900331581234, 2.053048335335069, -1.8715176368705742, -1.6848067143323457, -0.42708206792039877, 0.530667560337271, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.07409876019703565, -0.07221494148670667, 0.02462889338418732]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044874825585, -0.11636215226987334, 0.4969487888441691, 0.0, 0.0225237625575933, -0.5191521492763591, -1.0000005007626211, 0.08066609557590844, 0.448793072662968, 0.3099178529530587, -0.999999999978086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5641428327834341, 0.4203368132951341, 0.7230167069682218, 0.41760540398592727, -0.5254828501512318, -0.9545571721629916, 0.9999999999802442, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1867842679394946, -0.17780306918501634, 0.05081589447884099]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1915506208284794, -0.10036310844292455, -0.045350139427469405, 0.0, -0.994422224041471, 0.34834388416853784, -1.4279537185076305, -1.1689940768341889, -2.2951883693504262, -0.11630060943476574, -0.3649141101951757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5826959934577998, 0.3496611586433309, 2.087412527711624, -1.8528999680816072, -1.717800433522904, -0.4770820929756406, 0.5806675603372661, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.08363935941947381, -0.08125553370904845, 0.026902815369241072]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044882057293, -0.08844345840294277, 0.49593873886290873, 0.0, 0.042867767758631964, -0.5667293116538475, -1.0000004977426664, 0.00072182229346264, 0.47409923843170926, 0.22499984866016598, -0.9999999999998861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5891122088690359, 0.328643106550371, 0.6872838475311028, 0.37235337577933897, -0.6598743838111675, -1.0000005011048363, 0.9999999999999002, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19081198444876327, -0.1808118444468358, 0.04547843970107507]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19090066858407462, -0.10323491255116392, -0.020530267648986685, 0.0, -0.9906616460684254, 0.31732411906218994, -1.4779537435627763, -1.1711932832728438, -2.269339733306679, -0.10692561567629634, -0.41491411019515523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.55273032354188, 0.3613532970549822, 2.11811519605928, -1.838500055732416, -1.7561954088753378, -0.5270821180306766, 0.6306675603372348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.09334129327795843, -0.09041616874373477, 0.02868910949959598]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044888095715, -0.05743608216478737, 0.4963974355696544, 0.0, 0.07521155946091031, -0.6203953021269575, -1.0000005011029138, -0.04398412877309881, 0.5169727208749474, 0.18749987516938793, -0.9999999999995902, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5993133983183974, 0.2338427682330254, 0.6140533669531139, 0.28799824698382426, -0.7678995070486744, -1.0000005011007207, 0.9999999999993754, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19403867716969223, -0.18321270069372653, 0.03572588260709818]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071634004234, -0.10457855053763135, 0.004385786626315297, 0.0, -0.9849369381476, 0.2839002360148954, -1.5279537686180218, -1.17466610110415, -2.2414735593357737, -0.10317562021799674, -0.4649141101951504, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.5233229725962216, 0.36969446740304934, 2.143038650411786, -1.8291699046431946, -1.798911389157298, -0.5756053876972766, 0.6806675603372229, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.10317100955539824, -0.09967415935561454, 0.029943606245836273]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880645341, -0.026872759729348675, 0.49832108550603965, 0.0, 0.11449415841650931, -0.6684776609458908, -1.0000005011049091, -0.06945635662612402, 0.5573234794180997, 0.07499990167861059, -0.9999999999999034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5881470189131661, 0.16682340696134274, 0.49846908705011983, 0.1866030217844274, -0.8543196056392057, -0.9704653933320009, 0.999999999999761, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1965943255487961, -0.18515981223759514, 0.025089934924805872]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076409519933, -0.10453057389574948, 0.029471171578727164, 0.0, -0.9771085917043104, 0.2485330794209001, -1.5779537936732664, -1.1788548881732956, -2.2118268152936804, -0.10317562216549314, -0.5149141101951414, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.495306006269499, 0.3761419989059404, 2.160891662915417, -1.824899582317421, -1.8450841733827208, -0.619577208476581, 0.7306675603371922, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.11310118230716668, -0.10901189464256239, 0.030737684190383353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044896860483, 0.0009595328376374654, 0.5017076990482373, 0.0, 0.1565669288657919, -0.7073431318799055, -1.0000005011048938, -0.08377574138291399, 0.5929348808418623, -3.8949927727571776e-08, -0.9999999999998208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5603393265344536, 0.1289506300578212, 0.3570602500726246, 0.08540644651547091, -0.9234556845084538, -0.8794364155860872, 0.9999999999993857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19860345503536875, -0.18675470573895703, 0.015881558890941574]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081185053514, -0.10325887035266997, 0.054799724407209094, 0.0, -0.9671468194654598, 0.21170593900339751, -1.6279538187285196, -1.1834283585822387, -2.180593818016655, -0.10317562119898441, -0.5649141101951358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4688487342508203, 0.3814027872192266, 2.1719326853827745, -1.825171873241273, -1.8940224007630342, -0.6580094539680865, 0.78066756033716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.12310997120708991, -0.11841527876514904, 0.03117675768890945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044893283523, 0.025434070861590136, 0.5065710565696384, 0.0, 0.19923544477701283, -0.7365428083500519, -1.0000005011050657, -0.0914694081788625, 0.6246599455405074, 1.9330174691911513e-08, -0.9999999999998875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5291454403735715, 0.10521576626572367, 0.22082044934715017, -0.005445818477038247, -0.9787645476062656, -0.7686449098301102, 0.999999999999356, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20017577799846473, -0.18806768245173283, 0.008781469970521932]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18830085960652074, -0.10094106828000085, 0.08044648176792582, 0.0, -0.9551158192300108, 0.17385418948230297, -1.6779538437837669, -1.1882353885402366, -2.148025953887049, -0.10317562119899297, -0.6149141101951241, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4438513795930497, 0.38604038290500425, 2.1769110942114307, -1.8290985891323805, -1.9440224007630011, -0.690938830721111, 0.8306675603370197, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.13318029585907415, -0.12787262454713696, 0.03137996710546729]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488028826, 0.04635604145338236, 0.5129351472143346, 0.0, 0.24062000470898037, -0.7570349904218909, -1.0000005011049475, -0.09614059915995513, 0.6513572825921219, -1.7120950368152377e-13, -0.9999999999997655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.49994709315541364, 0.09275191371555261, 0.09956817657312017, -0.07853431782215309, -0.9999999999993392, -0.6585875350604878, 0.999999999997195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20140649303968486, -0.1891469156397585, 0.004064188331156809]\n accelerations: []\n effort: []\n time_from_start: \n secs: 0\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090736249754, -0.09774250691140846, 0.10648834968152779, 0.0, -0.9411240359592388, 0.13536514841905334, -1.727953868839028, -1.1932265820845844, -2.114403332476961, -0.10317562119899225, -0.6649141101951245, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.4201341163778836, 0.39063143714604665, 2.1765951804883517, -1.835633730864658, -1.9940224007630023, -0.7187861159392873, 0.8806675603370199, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.14329907333356773, -0.1373739653243564, 0.03145918833284471]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880463854, 0.0639712273718478, 0.5208373582720394, 0.0, 0.2798356654154395, -0.7697808212649924, -1.0000005011052202, -0.09982387088695573, 0.6724524282017643, 1.4414515984740634e-14, -1.0000000000000073, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4743452643033202, 0.09182108482084815, -0.006318274461583409, -0.13070283464554755, -1.000000000000025, -0.5569457043635264, 1.0000000000000029, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20237554948987138, -0.1900268155443884, 0.0015844245475484528]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1870009551184788, -0.09380434713976812, 0.13300294106775307, 0.0, -0.9252870640524239, 0.09656003030771734, -1.7779538938942843, -1.198397942504916, -2.0800026432934255, -0.1031756211989961, -0.7149141101951192, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3966575446828693, 0.3942814735180769, 2.173228309942234, -1.8437768276556492, -2.044022400288047, -0.7440906075280878, 0.9298125954400028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.15345645516096196, -0.1469106701899372, 0.03150547657498004]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880374714, 0.0787631954328065, 0.5302918277245053, 0.0, 0.31673943813629674, -0.7761023622267198, -1.0000005011051265, -0.10342720840663337, 0.6880137836707058, -7.729788349580957e-14, -0.9999999999998935, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4695314339002854, 0.0730007274406058, -0.06733741092235547, -0.1628619358198225, -0.9999999905008928, -0.5060898317760081, 0.9829007020596591, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20314763654788484, -0.19073409731161634, 0.0009257648427065969]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1863510028746126, -0.08940657691239148, 0.15993646549514093, 0.0, -0.9077002177846101, 0.0577144982202569, -1.8279539189495444, -1.2037550845996223, -2.045082455288725, -0.10317562119899588, -0.7649141101951193, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.373403233514618, 0.39761818177927666, 2.1677150721919367, -1.8517095702924167, -2.090272400267555, -0.7671217427461602, 0.9743554279517473, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.16364505891301762, -0.15647530578669536, 0.03157764315624053]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044877324032, 0.08795540454753278, 0.5386704885477571, 0.0, 0.35173692535627676, -0.7769106417492088, -1.0000005011052027, -0.10714284189412701, 0.6984037600940188, 4.450678825453664e-15, -1.000000000000003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.46508622336502503, 0.066734165223995, -0.11026475500594807, -0.1586548527353489, -0.9249999995901508, -0.46062270436144914, 0.8908566502348907, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2037720750411131, -0.19129271193516295, 0.0014433316252097353]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1857010506306874, -0.08477395707851161, 0.18720497820862866, 0.0, -0.8884352929982886, 0.01907208418723394, -1.8779539440051352, -1.2092989879574256, -2.0098810870774675, -0.10317562119899996, -0.814914110195116, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3504207039881608, 0.4011800323063187, 2.160664577479721, -1.8582488832910644, -2.130318218837731, -0.7879559727175606, 1.0125331389814698, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.17385931028884796, -0.16606157196264626, 0.03170496753381734]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878503634, 0.09265239667759756, 0.5453702542697546, 0.0, 0.3852984957264305, -0.7728482806604591, -1.0000005011118134, -0.11087806715606638, 0.7040273642251468, -8.146622980198351e-14, -0.999999999999932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45965059052914475, 0.07123701054084097, -0.14100989424431654, -0.13078625997295515, -0.8009163714035266, -0.41668459942800695, 0.7635542205944467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2042850275166068, -0.19172532351901794, 0.0025464875515362044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100287469678, -0.08004658303450171, 0.2147149727192593, 0.0, -0.8673544013805521, -0.017515331797160368, -1.927953969060416, -1.2143074411173982, -1.9760158105709866, -0.10317562119900985, -0.8649141101951096, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3277781927368582, 0.4069905617644826, 2.1533057822128603, -1.8608207883874708, -2.160952331603752, -0.8063723870543738, 1.042771122912438, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.18409494956248756, -0.1756642153116939, 0.03189697652684323]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880187457, 0.09454748088019785, 0.5501998902126127, 0.0, 0.42161783235473066, -0.7317483196878861, -1.0000005011056152, -0.10016906319945132, 0.6773055301296188, -1.97726774355756e-13, -0.9999999999998725, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45285022502605515, 0.11621058916327776, -0.14717590533721614, -0.051438101928126534, -0.6126822553204215, -0.36832828673626294, 0.6047596786193603, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20471278547279198, -0.1920528669809529, 0.003840179860517767]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095511869036, -0.07528632615850864, 0.24236838577647574, 0.0, -0.8445410002726693, -0.052170687543544945, -1.977953994115659, -1.218888525397854, -1.9433658307873134, -0.10317562119908598, -0.9149141101950806, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.3053702514150862, 0.41459337746870106, 2.145905680764107, -1.859865008164406, -2.1836136967779933, -0.8227303364548901, 1.0663238948101657, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.19434857549061726, -0.1852790253493729, 0.03214122600879182]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879871701, 0.09520513751986139, 0.5530682611443287, 0.0, 0.4562680221576549, -0.6931071149276915, -1.0000005011048618, -0.09162168560911774, 0.6529995956734658, -1.5226675328354768e-12, -0.9999999999994209, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4481588264354371, 0.1520563140843691, -0.1480020289750656, 0.01911560446129544, -0.4532273034848304, -0.32715898801032733, 0.4710554379545536, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20507251856259387, -0.19229620075358023, 0.004884989638971829]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18765090736269682, -0.07051097554535792, 0.27005489054469406, 0.0, -0.820117098008896, -0.08532825542939047, -2.027954019170819, -1.2232720269389479, -1.911539421911304, -0.10317562119960076, -0.9649141101950837, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.283051502232509, 0.4230911108903051, 2.1384846086640117, -1.856402509099699, -2.200673827285524, -0.8375000830245992, 1.084970164605868, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.20461740258981545, -0.19490270153196496, 0.03242049742283092]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904488012937, 0.09550701226301443, 0.5537300953643661, 0.0, 0.4884780452754674, -0.6631513577169105, -1.0000005011032, -0.08767003082187402, 0.6365281775201885, -1.0295615631910274e-11, -1.0000000000000606, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4463749836515448, 0.16995466843208046, -0.1484214420019017, 0.06924998129414076, -0.34120261015062003, -0.29539493139418266, 0.3729253959140467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2053765419839639, -0.19247352365184098, 0.0055854282807819644]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18830085960663476, -0.06573065593356968, 0.2976490144776919, 0.0, -0.7940209891948569, -0.11768237806996801, -2.0779540442260287, -1.2278303686797252, -1.8798731125643917, -0.10456172044276532, -1.014914110194661, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2606814857024655, 0.431755769507175, 2.1310046803613925, -1.851301878665199, -2.214207864379562, -0.8510876125202473, 1.1002458589104858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2148992583261869, -0.2045325429886216, 0.03273359178370046]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487875863, 0.09560639223576467, 0.5518824786599563, 0.0, 0.5219221762807835, -0.6470824528115505, -1.000000501104192, -0.09116683481554808, 0.6333261869382456, -0.027721984863291253, -0.9999999999915493, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.44740033060087214, 0.1732931723373979, -0.14959856605238572, 0.10201260869000148, -0.27068074188076024, -0.27175058991296264, 0.30551388609235586, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2056371147274286, -0.19259682913313322, 0.0062618872173907094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1889508118503472, -0.06094514455415829, 0.3250118638883023, 0.0, -0.7660168281955159, -0.1498820473410018, -2.127954069281119, -1.2328746095083405, -1.8476590040733998, -0.10938369658481906, -1.064914110194654, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.2381640305215638, 0.44013717084252785, 2.1234227978349507, -1.8451475887645252, -2.225705791667517, -0.86379626868411, 1.1132725972557043, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.22519247883156732, -0.21416630923912433, 0.033081452035587405]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874249214, 0.0957102275882278, 0.5472569882122083, 0.0, 0.5600832199868193, -0.6439933854206761, -1.0000005011018094, -0.10088481657230536, 0.6442821698198388, -0.09643952284107475, -0.9999999999998602, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45034910361803604, 0.16762802670705734, -0.15163765052883937, 0.12308579801347541, -0.22995854575909658, -0.2541731232772522, 0.2605347669043711, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20586441010760834, -0.19267532501005452, 0.006957205037738919]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1896007640943593, -0.056136295744171866, 0.3502790770731317, 0.0, -0.7358821923991324, -0.1849208229691795, -2.1779540943363824, -1.2384363426293217, -1.8144877802196402, -0.1188691806799059, -1.1149141101946507, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.215463430339153, 0.44801518927411993, 2.1157062026622317, -1.838286239897125, -2.2361153657650807, -0.875836486222236, 1.124794054681236, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.23549568758795433, -0.22380225512893975, 0.03345246792854085]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880242122, 0.09617697619972848, 0.5053442636965884, 0.0, 0.6026927159276687, -0.700775512563554, -1.0000005011052675, -0.11123466241962579, 0.6634244770751929, -0.1897096819017367, -0.9999999999999337, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45401200364821753, 0.15756036863184142, -0.1543319034543817, 0.1372269773480076, -0.20819148195127996, -0.2408043507625211, 0.23042914851063429, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20606417512774042, -0.19271891779630862, 0.007420317859068804]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071633837923, -0.05126875511728496, 0.37168476444784687, 0.0, -0.7033745635644513, -0.22086031987406063, -2.22795411939164, -1.2441730694071969, -1.780436008865792, -0.13350254909532316, -1.1649141101946494, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1925993695354173, 0.45532158092343755, 2.1078359396501023, -1.830903332945316, -2.2459767976272564, -0.8873471725143723, 1.1352674019011204, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.24580754562115176, -0.23343923792898846, 0.033817400381839495]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880398485, 0.09735081253773807, 0.42811374749430303, 0.0, 0.6501525766936237, -0.7187899380976224, -1.000000501105156, -0.11473453555750569, 0.6810354270769632, -0.2926673683083453, -0.9999999999999719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.457281216074713, 0.14612783298635243, -0.15740526024259138, 0.1476581390361814, -0.19722863724351458, -0.2302137258427263, 0.20946694439768762, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20623716066394854, -0.1927396560009739, 0.00729864906597294]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19090066859357227, -0.04598248330987681, 0.3886109037577365, 0.0, -0.6676027099643385, -0.2560699793372169, -2.2779541444467584, -1.2479054559897538, -1.7469772680484013, -0.15154625311070333, -1.214914110194611, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1700112437989867, 0.46207634811224185, 2.099915046359739, -1.8232418122144567, -2.255537595132261, -0.8985359801059064, 1.1450041779607505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.25612352010166706, -0.2430800482900869, 0.033818410484089206]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904510386092, 0.10572543614816296, 0.338522786197792, 0.0, 0.7154370720022551, -0.7041931892631261, -1.000000501102369, -0.07464773165113807, 0.6691748163478137, -0.3608740803076032, -0.9999999999992314, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45176251472861234, 0.1350953437760863, -0.15841786580726494, 0.1532304146171864, -0.19121595010009734, -0.2237761518306816, 0.19473552119260332, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20631948961030647, -0.1928162072219686, 2.0202044994209294e-05]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062083595045, -0.040317521235115276, 0.40133864935816627, 0.0, -0.6302328383958651, -0.2867998021054996, -2.324204173917024, -1.249233972993645, -1.7178482851513637, -0.1767502859932872, -1.2649141101936572, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1476690025447447, 0.4683333008680236, 2.09191291107895, -1.8152899458118121, -2.2649088062839944, -0.9094202366145975, 1.154124183192693, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2664396304336438, -0.2527272981107301, 0.033491878793655123]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044847563757, 0.1132992414952307, 0.2545549120085955, 0.0, 0.7473974313694678, -0.6145964404286427, -0.9250005894053064, -0.0265703400778258, 0.5825796579407504, -0.5040806576516775, -0.9999999999809237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4468448250848407, 0.12513905511563492, -0.160042705615783, 0.15903732805288917, -0.18742422303466139, -0.21768513017382185, 0.1824001046388473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20632220663953524, -0.19294499641286425, -0.006530633808681684]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057308329783, -0.03435811871924357, 0.4106071128396652, 0.0, -0.5924384257520655, -0.3092997887046269, -2.3641190113732753, -1.2479121376185047, -1.6944830038835206, -0.20891351230026609, -1.3149141101936337, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1254971862108376, 0.47415393170495546, 2.083789800678732, -1.8069865192847097, -2.274116289795303, -0.9199753081595786, 1.1626655265439794, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2767528016450851, -0.2623829541739807, 0.032915192927361656]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044946947718, 0.11918805031743422, 0.1853692696299788, 0.0, 0.7558882528759906, -0.44999969159426667, -0.7982967491250276, 0.02643670750280394, 0.46730562535686115, -0.6432645261395776, -0.999999999999531, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4434363266781419, 0.11641261673863741, -0.1624622080043586, 0.16606853054205084, -0.184149670226171, -0.2111014308996233, 0.17082686702572897, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626342422882576, -0.19311312126501273, -0.011533717325869332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052532763977, -0.028246681651432553, 0.417278269546565, 0.0, -0.5533046909445254, -0.3273199358428501, -2.400841854050614, -1.2441771801193224, -1.6731391108808145, -0.24664409334589987, -1.364914110193866, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.1033514722958775, 0.4795913155188154, 2.0754923512785957, -1.7982316041646491, -2.2831497971975154, -0.9301385149898467, 1.1706182117756505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2870613964926463, -0.27204770428101827, 0.03222404529439046]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044886838658, 0.12222874135622029, 0.13342313413799528, 0.0, 0.7826746961508023, -0.36040294275985324, -0.734456853546777, 0.07469914998364757, 0.42687786005412354, -0.7546116209126756, -1.0000000000046478, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4429142782992028, 0.10874767627719871, -0.1659489880027314, 0.17509830240121216, -0.18067014804424714, -0.2032641366053611, 0.15905370463342458, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20617189695122384, -0.1932950021407505, -0.013822952659423841]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19350047757947533, -0.021986933544807425, 0.4221434061622202, 0.0, -0.5130500192277759, -0.3385699282758616, -2.435183288353933, -1.2376153997438408, -1.6527359320507653, -0.28882855819044684, -1.4149141101924279, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.081250423963103, 0.4846894888950291, 2.067020158165791, -1.7889953202043773, -2.2919788654504165, -0.9398948761634546, 1.1779804718250553, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.2973638782122777, -0.28172233421270915, 0.03141822304156141]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904503671109, 0.12519496213250256, 0.09730273231310324, 0.0, 0.80509343433499, -0.22499984866023012, -0.6868286860663773, 0.13123560750963204, 0.40806357660098147, -0.8436892968909393, -0.9999999999712385, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.442020966655492, 0.10196346752427456, -0.16944386225609773, 0.1847256792054373, -0.17658136505801988, -0.195127223472158, 0.1472452009880953, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20604963439262888, -0.1934925986338176, -0.016116445056581115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415042983015146, -0.015940318210569057, 0.42584211058524724, 0.0, -0.4735784370132148, -0.34679976600678003, -2.4659684518139637, -1.229742253064001, -1.6331973476449209, -0.33457613007048115, -1.4649141101914138, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0587794267988824, 0.48946642596631346, 2.0582582915254526, -1.7790703593797987, -2.300597054380919, -0.9490808104615622, 1.184684280414949, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.30766228438160115, -0.29140399152743357, 0.030858428686362897]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999045013522767, 0.12093230668476738, 0.07397408846054156, 0.0, 0.7894316442912224, -0.16459675456060263, -0.6157032692006137, 0.15746293359679744, 0.39077168811689056, -0.9149514376006856, -0.9999999999797207, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4494199432844081, 0.09553874142568745, -0.1752373328067675, 0.19849921649157368, -0.17236377861005436, -0.18371868596215365, 0.13407617179787834, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20596812338646886, -0.19363314629448874, -0.011195887103970254]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1948003817785157, -0.010211961403289976, 0.4288198723493238, 0.0, -0.436740694585272, -0.3505497610886175, -2.4926809098603018, -1.221532104533864, -1.6152614476139333, -0.38013680985480225, -1.5149141100153303, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.035825385381281, 0.4939367019768837, 2.0491840336525255, -1.7683863190096152, -2.30899050710184, -0.9576372854441152, 1.1907105397573798, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3179597789418257, -0.3010887701017077, 0.030653317206623815]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999038967284646, 0.11456713614558164, 0.059555235281530755, 0.0, 0.7367548485588561, -0.07499990163674985, -0.5342491609267589, 0.16420297060273872, 0.3587180006197488, -0.9112135956864214, -0.999999996478329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45908082835202635, 0.08940552021140502, -0.18148515745853835, 0.21368080740367146, -0.16786905441842137, -0.17112949965105848, 0.12052518684861432, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20594989120449095, -0.19369557148548283, -0.004102229594781623]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033402254522, -0.0047232234992234, 0.4314326130405708, 0.0, -0.40350562387742783, -0.350549759449232, -2.5159835345977135, -1.213658820867027, -1.5989292596586129, -0.4217605975434101, -1.5649141100153348, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 1.0124891843538457, 0.4981138770935389, 2.0398401390253653, -1.7569738888744086, -2.317143791957696, -0.9655843025413007, 1.1960794427474029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3282588830342648, -0.31077355784008315, 0.03073085442638707]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880590695, 0.10977475808133152, 0.0522548138249406, 0.0, 0.6647014141568836, 3.278770992209967e-08, -0.4660524947482356, 0.157465673336742, 0.3266437591064106, -0.832475753772157, -1.0000000000000906, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.466724020548707, 0.08354350233310322, -0.18687789254320628, 0.2282486027041316, -0.1630656971171136, -0.15894034194370965, 0.10737805980046133, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20598208184878208, -0.19369575476750928, 0.0015507443952651216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028626450218, 0.0005977739911573578, 0.43388750662554476, 0.0, -0.3744777343318386, -0.35054975944922634, -2.5357410254809083, -1.206897316826226, -1.5842685730535615, -0.4556974931450726, -1.6149141100136624, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9888600690673232, 0.5020058769292861, 2.0302696198490073, -1.7448654934375056, -2.3250498037173886, -0.9729427837511755, 1.2008148431743053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.33856153777606945, -0.3204559452647128, 0.03102658809182508]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044839139417, 0.10641994980761516, 0.04909787169947905, 0.0, 0.5805577909117838, 1.1328336769881886e-13, -0.3951498176638948, 0.13523008081601928, 0.2932137321010285, -0.6787379120332497, -0.9999999999665521, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.47258230573045196, 0.07783999671494374, -0.19141038352715636, 0.2421679087380596, -0.15812023519385113, -0.14716962419749657, 0.0947080085380473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20605309483609288, -0.19364774849259359, 0.005914673308760186]\n accelerations: []\n effort: []\n time_from_start: \n secs: 1\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023851750204, 0.0058067827884346526, 0.43629963435424546, 0.0, -0.34977328671760405, -0.3505497594490434, -2.5515534861851052, -1.2017523323379853, -1.5714335711273217, -0.47882349802376295, -1.6649141100218512, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9650064217284198, 0.5056166847091188, 2.020511062691655, -1.7320884987762222, -2.3327083427939947, -0.9797300216896181, 1.2049403664546836, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.34886924415138293, -0.33013405924060685, 0.031491401395039406]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999045059997324, 0.10418017594554589, 0.048242554574013434, 0.0, 0.4940889522846916, 3.659774971476059e-12, -0.31624921408393897, 0.10289968976481464, 0.25670003852479484, -0.46252009757380774, -1.0000000001637788, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.47707294677806744, 0.07221615559665442, -0.1951711431470496, 0.2555398932256706, -0.153170781532121, -0.13574475876885275, 0.08251046560756373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2061541275062699, -0.19356227951788008, 0.009296266064286476]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019076205678, 0.01094710659779356, 0.43889654427940505, 0.0, -0.32902778679993383, -0.350549759373933, -2.5632872879338184, -1.198315358941139, -1.5604962061654737, -0.4934354490988726, -1.714914110022389, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9409809099977413, 0.5089478611007892, 2.010598536565035, -1.7186648939314983, -2.340124142176677, -0.9859601185588565, 1.2084781184221773, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3591827297248039, -0.3398064579031829, 0.032087084044182854]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044891095112, 0.1028064761871781, 0.05193819850319245, 0.0, 0.4149099983534049, 1.5022074274711807e-09, -0.23467603497425943, 0.06873946793692268, 0.21874729923696185, -0.2922390215021926, -1.0000000000107563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4805102346135684, 0.06662352783340725, -0.19825052253240177, 0.2684720968944773, -0.14831598765364637, -0.12460193738476788, 0.0707550393498762, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20626971146842019, -0.1934479732515218, 0.011913652982868894]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19805014300595303, 0.01616763718753221, 0.4416266043295242, 0.0, -0.31434046046960834, -0.3479964396838741, -2.5671924307342984, -1.1950174970328917, -1.554812365961576, -0.5032833461061631, -1.7649141100222665, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.9169604577879927, 0.5120072136652394, 2.00059743522944, -1.704673767036179, -2.3472996936890005, -0.9916948375641602, 1.211471161209099, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.3695018483503711, -0.3494732006465865, 0.03266842201820772]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904487792508, 0.10441061179477303, 0.05460120100238339, 0.0, 0.2937465266065099, 0.05106639380117792, -0.07810285600959682, 0.06595723816494561, 0.11367680407795161, -0.19695794014580975, -0.999999999997548, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4804090441949723, 0.06118705128900468, -0.2000220267118964, 0.27982253790639017, -0.1435110302464684, -0.11469438010607613, 0.05986085573843309, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20638237251134314, -0.19333485486807092, 0.01162675948049735]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009524997645, 0.021640331934095997, 0.4444094503665469, 0.0, -0.304737426692917, -0.3427112339558802, -2.5595189145865422, -1.1902472533215211, -1.550632050515629, -0.5121171890456344, -1.8149141100222674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8931497268190505, 0.5148052017724185, 1.9905777506774254, -1.6902082840764425, -2.3542384659824007, -0.9970080801219692, 1.2139672984600969, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.37982523717026523, -0.35913610610156427, 0.033065302053414555]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880468606, 0.10945389493127572, 0.055656920740453225, 0.0, 0.19206067553382752, 0.10570411455987822, 0.15347032295506577, 0.09540487422740983, 0.08360630891894133, -0.1766768587894268, -1.0000000000000187, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4762146193788446, 0.05595976214358289, -0.20039369104029425, 0.28930965919472607, -0.13877544586800694, -0.10626485115617988, 0.049922745019961134, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20646777639788294, -0.1932581090995557, 0.007937600704136717]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 149999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1993500474956596, 0.027447032750500533, 0.44719311617393104, 0.0, -0.29823048299466254, -0.3352181634233884, -2.542572561456278, -1.1827877741334119, -1.5442052929674068, -0.5236869779123055, -1.8649141100241524, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8696467036921314, 0.5173466653397626, 1.9805781575461696, -1.675311040154937, -2.360949814515019, -1.0019336360562776, 1.2159940812038226, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.39014989056841987, -0.36879770316238975, 0.0331956858122768]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044913662933, 0.11613401632809074, 0.05567331614768283, 0.0, 0.13013887396508894, 0.14986141064983624, 0.3389270626052834, 0.14918958376218805, 0.12853515096444196, -0.2313957773334218, -1.000000000037699, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4700604625383813, 0.05082927134688156, -0.1999918626251158, 0.29794487843011247, -0.1342269706523728, -0.09851111868616734, 0.040535654874511946, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064930679630922, -0.19323194121651005, 0.0026076751772447955]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1999999997003511, 0.033592312459156615, 0.4499549798999402, 0.0, -0.29315264841581834, -0.32590245878973567, -2.518708697586323, -1.1718661023438643, -1.531782159828312, -0.5417427127055413, -1.9149141099798261, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8464598471325393, 0.5196314842200286, 1.9706121252746787, -1.6599820410640642, -2.367446701831865, -1.0064703094283112, 1.2175614943098638, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.40047317043285663, -0.37846080958946, 0.03305339426913867]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044093829817, 0.12290559417312169, 0.055237274520183975, 0.0, 0.1015566915768841, 0.18631409267305396, 0.47727727739910464, 0.21843343579094981, 0.24846266278189927, -0.36111469586471806, -0.9999999991134741, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4637371311918405, 0.04569637760531954, -0.19932064542981973, 0.3065799818174531, -0.12993774633690805, -0.09073346744067307, 0.031348262120822826, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064655972887355, -0.1932621285414052, -0.0028458308627625087]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2006499519420922, 0.04003511810004251, 0.45269094781589203, 0.0, -0.28861039686939943, -0.3147651443760416, -2.4892823022395594, -1.1570507908866805, -1.5134748485088176, -0.5680391583132592, -1.9649141099779086, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8235447304128778, 0.521656394972345, 1.9606785911354212, -1.6441949516323666, -2.3737434259767833, -1.0105951578991965, 1.2186683700516299, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.410792821544449, -0.3881279303848756, 0.032677488274773736]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044834821975, 0.12885611281771786, 0.05471935831903599, 0.0, 0.09084503092837815, 0.2227462882738813, 0.5885279069352773, 0.29630622914367577, 0.3661462263898845, -0.5259289121543582, -0.9999999999616506, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45830233439323115, 0.040498215046326475, -0.19867068278514982, 0.31574178863394986, -0.1259344828983689, -0.08249696941770744, 0.022137514835319477, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20639302223184805, -0.19334241590831164, -0.007518119887298623]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990418579913, 0.04671538543980319, 0.4554057181909018, 0.0, -0.2838827642228798, -0.3019029479424872, -2.455884788221434, -1.1381720395643866, -1.4903458368715168, -0.6010763147994233, -2.0149141099775054, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.8008343802272794, 0.5234171721993149, 1.950771004995255, -1.6279119791823433, -2.379853847090309, -1.0142760082439803, 1.2193088408478379, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.42110715147266914, -0.39780091040365606, 0.03212661541481748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044874138607, 0.13360534679521358, 0.05429540750019529, 0.0, 0.09455265293039257, 0.2572439286710881, 0.667950280362509, 0.37757502644587654, 0.4625802327460171, -0.6607431297232793, -0.9999999999919376, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45420700371196837, 0.03521554453940012, -0.19815172280332605, 0.3256594490004656, -0.12220842227051065, -0.07361700689567822, 0.012809415924162066, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20628659856440296, -0.19345960037560989, -0.011017457199125055]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985640854057, 0.05357324937276742, 0.45810659155045075, 0.0, -0.27828038023136986, -0.28757407765082377, -2.420452115364689, -1.1151671965650922, -1.4633713831116553, -0.639506039985464, -2.0649141099481136, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7794608664244675, 0.5244703198472045, 1.9411650492665435, -1.6108132890177125, -2.3853688117460723, -1.0162423503856675, 1.2186008742168057, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.4314150480332894, -0.40748076114322623, 0.031460277024761264]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904445482911, 0.13715727865928448, 0.054017467190979204, 0.0, 0.1120476798301987, 0.2865774058332679, 0.7086534571348982, 0.46009685998588584, 0.5394890751972281, -0.7685945037208132, -0.9999999994121649, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.42747027605623766, 0.021062952957791307, -0.19211911457422637, 0.34197380329261556, -0.11029929311527009, -0.039326842833743554, -0.014159332620644524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20615793121240503, -0.19359701479140357, -0.013326767801124356]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980863865823, 0.060558253728217847, 0.4608003339180001, 0.0, -0.27124769585929104, -0.2720714565471836, -2.384536171805477, -1.087982578750324, -1.4334078958920156, -0.682249820130641, -2.114914109927149, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7619383690801973, 0.5239413460919039, 1.9324989319144232, -1.5923745781900724, -2.3894218614842417, -1.0139187264028344, 1.2147879232101293, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.44171587498106996, -0.41716813981334966, 0.030729705617939817]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044602353002, 0.13970008710900855, 0.053874847350987604, 0.0, 0.14065368744157608, 0.310052422072803, 0.7183188711842404, 0.5436923562953645, 0.5992697443927931, -0.8548756029035406, -0.9999999995807045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3504499468854042, -0.010579475106011309, -0.17332234704240554, 0.36877421655280007, -0.08106099476339179, 0.04647247965666023, -0.07625902013352719, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20601653895561098, -0.19374757340246815, -0.014611428136428942]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976084665441, 0.06763116936743845, 0.46349199665047647, 0.0, -0.26235884845665897, -0.25569754699541775, -2.349315057040639, -1.056465929720404, -1.4011217029463618, -0.7284448442338358, -2.1649141098676727, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7495449441077074, 0.5214804819607382, 1.9251501248039335, -1.5724409526841792, -2.3915615157597157, -1.0060987553730838, 1.2070922837320053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.45200940989261845, -0.4268632815303917, 0.02997584084206367]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044159923643, 0.141458312784412, 0.05383325464952704, 0.0, 0.17777694805264133, 0.327478191035317, 0.7044222952967618, 0.6303329805983988, 0.6457238589130739, -0.9239004820638986, -0.9999999988104814, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24786849944979672, -0.04921728262331534, -0.1469761422097941, 0.39867251011786753, -0.04279308550947567, 0.1563994205950119, -0.15391278956248045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20587069823097007, -0.19390283434084124, -0.01507729551752297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2038997130844338, 0.07476229667116564, 0.46618478772117466, 0.0, -0.25128950011283474, -0.23875032963856022, -2.3157137524361513, -1.0204814385968584, -1.3669705066420434, -0.7774008635131713, -2.214914109856457, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7422497665069451, 0.5172244562577061, 1.9191726927644646, -1.5510974706307565, -2.3917003534409726, -0.992886619002887, 1.1955969381640508, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.46229573129892776, -0.43656609127169094, 0.029230685132609274]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044755587892, 0.14262254607454386, 0.05385582141396442, 0.0, 0.22138696687648404, 0.3389443471371508, 0.6720260920897557, 0.7196898224709112, 0.6830239260863685, -0.9791203855867099, -0.9999999997756912, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1459035520152469, -0.0851205140606409, -0.1195486407893788, 0.42686964106845204, -0.0027767536251423128, 0.2642427274039362, -0.229906911359091, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20572642812618652, -0.19405619482598455, -0.01490311418908793]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966532733232, 0.08192522858262052, 0.46888039415683935, 0.0, -0.23767593175400703, -0.22168354143863822, -2.2849982840336165, -0.9801644044549478, -1.3307513073431536, -0.8274008885665106, -2.264914109822181, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7392115747201519, 0.5115679153440071, 1.9143876819995183, -1.5284752268909134, -2.389913935093663, -0.9751042820728416, 1.1807938630140489, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.47257518851057284, -0.4462762846687216, 0.02852318716484185]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044857970357, 0.14325863822909762, 0.053912128713293275, 0.0, 0.2722713671765543, 0.3413357639984401, 0.6143093680506944, 0.8063406828382109, 0.724383985977795, -1.0000005010667865, -0.9999999993144846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06076383573586386, -0.11313081827397765, -0.0957002152989265, 0.45244487479686285, 0.035728366946192296, 0.3556467386009085, -0.29606150300003864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20558914423290142, -0.19420386794061276, -0.014149959355348452]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961757465188, 0.08903301748486578, 0.4715794237084032, 0.0, -0.22147480879436784, -0.20506404918597032, -2.258337088505657, -0.9359107771503143, -1.2920463048020234, -0.87740091362361, -2.314914109825028, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7391918173828845, 0.5049722875996087, 1.9104832483634167, -1.5046223900848206, -2.3862997616093375, -0.953775414653893, 1.1632392212627674, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.48284934187660894, -0.45599255170371705, 0.02794281530422694]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904494639122, 0.14215577804490517, 0.053980591031276844, 0.0, 0.3240224591927836, 0.3323898450533577, 0.53322391055919, 0.885072546092669, 0.7741000508226037, -1.0000005011419866, -1.0000000000569382, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003951467453463253, -0.13191255488796916, -0.07808867272203174, 0.4770567361218574, 0.07228346968650735, 0.4265773483789722, -0.35109283502562866, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20548306732072152, -0.19432534069990923, -0.011607437212298176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20584956975527796, 0.09591929435173313, 0.4742818254449502, 0.0, -0.20323394897009178, -0.18936634225229104, -2.236126259020258, -0.8885078750851945, -1.251228327329373, -0.9274009386381123, -2.364914109760475, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7408578123591797, 0.49785868085957863, 1.9071025292885182, -1.4794787630397328, -2.380912016845177, -0.9298348750177827, 1.1433840472268757, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.49312074315231635, -0.46571174018750716, 0.02765851237722452]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999043612521492, 0.13772553733734705, 0.05404803473093897, 0.0, 0.3648171964855214, 0.3139541386735858, 0.44421658970798006, 0.9480580413023973, 0.8163595494530113, -1.0000005002900476, -0.9999999987089433, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.033319899525904216, -0.1422721348006006, -0.06761438149797121, 0.5028725409017544, 0.1077548952832099, 0.47881079272220706, -0.3971034807178315, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2054280255141487, -0.19438376967580193, -0.005686058540048478]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2064995219992295, 0.10247586891485333, 0.4769872192600208, 0.0, -0.18347680707648317, -0.17485124399808333, -2.218584463460786, -0.8385855534330408, -1.208676291225198, -0.9774009636933224, -2.4149141097604034, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7431160957031382, 0.4905766522403294, 1.9039338485504134, -1.4529810274913606, -2.3737479731150892, -0.9040711371926337, 1.1215577613589578, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5033933423961802, -0.47542976000208337, 0.027781497716039466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879030494, 0.13113149126240384, 0.05410787630141277, 0.0, 0.39514283787217197, 0.2903019650841543, 0.3508359111894426, 0.9984464330430733, 0.8510407220834976, -1.000000501104201, -0.9999999999985625, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04516566687917056, -0.14564057238498354, -0.0633736147620975, 0.5299547109674442, 0.14328087460175465, 0.5152747565029818, -0.43652571735835655, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2054519848772768, -0.1943603962915242, 0.0024597067762989174]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20714947424208874, 0.1087497798270423, 0.47969516230900283, 0.0, -0.16319645140065323, -0.16103359446106466, -2.2036510925670614, -0.7885855284092813, -1.1678977513842976, -1.0274009887478648, -2.4649141097444422, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7452872959271061, 0.48340264483539896, 1.9007569166417722, -1.4251468722520122, -2.3647620003914542, -0.8771425608227693, 1.0979982825218204, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5136706717703803, -0.4851428570373369, 0.028268135747124133]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044857184991, 0.1254782182437795, 0.05415886097964067, 0.0, 0.40560711351659895, 0.2763529907403734, 0.29866741787449347, 1.0000005004751893, 0.8155707968180089, -1.0000005010908486, -0.9999999996807786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04342400447935876, -0.1434801480986095, -0.06353863817282335, 0.5566831047869689, 0.1797194544727016, 0.538571527397288, -0.47118957674274703, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2055465874840014, -0.19426194070507039, 0.00973276062169336]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20779942648610297, 0.11505399951598874, 0.482405313379302, 0.0, -0.14399512818284158, -0.14671201535440748, -2.1875761606731885, -0.7385855032967514, -1.1326427072862721, -1.0774010138031231, -2.514914109777272, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7463112319953491, 0.47680023294367757, 1.8972925156002587, -1.3964523903027506, -2.354485392825743, -0.8506324446720157, 1.0737267971404694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5239352503067686, -0.4942257372364583, 0.02880836449977823]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880284928, 0.12608439377892897, 0.054203021405982994, 0.0, 0.38402646435623317, 0.2864315821331439, 0.3214986378774594, 1.0000005022505989, 0.7051008819605089, -1.000000501105166, -1.000000000656594, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020478721364859717, -0.13204823783442785, -0.06928802083026986, 0.5738896389852342, 0.20553215131422328, 0.5302023230150723, -0.4854297076270206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20529157072776677, -0.18165760398242817, 0.010804575053081881]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2071494742420842, 0.12174093329032455, 0.48512022863353205, 0.0, -0.12703699815286704, -0.1330316338389753, -2.1692811221070403, -0.6885854782277657, -1.1062531906929634, -1.1274010388583806, -2.564914109772917, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7447721797131188, 0.4698644227828504, 1.8928468390931963, -1.370000315662169, -2.346668129674009, -0.8275798134794191, 1.0524933000882424, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5341653816753601, -0.5020571886286284, 0.029006302249322744]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880375872, 0.13373867548671614, 0.054298305084600804, 0.0, 0.3391626005994906, 0.2736076303086439, 0.3659007713229604, 1.000000501379713, 0.5277903318661774, -1.0000005011051478, -0.999999999912899, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.030781045644606056, -0.13871620321654374, -0.08891353014124645, 0.5290414928116319, 0.15634526303467822, 0.46105262385193224, -0.4246699410445408, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20460262737183083, -0.15662902784340033, 0.003958754990890307]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20649952200160285, 0.1288531968728209, 0.4877537292982551, 0.0, -0.11127879631859366, -0.12123266659801699, -2.152515976867951, -0.638585453201901, -1.0849792016045696, -1.1750080095204751, -2.614914109768534, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7403127525402534, 0.4630400930972924, 1.887522054384438, -1.3458304132489392, -2.341802604476354, -0.8086387528830363, 1.0351149030017601, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5443393163617989, -0.5080176136196273, 0.028700901168124553]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044809626607, 0.14224527164992679, 0.052670013294461304, 0.0, 0.31516403668546744, 0.23597934481916613, 0.3353029047817842, 1.000000500517296, 0.4254797817678723, -0.9521394132418927, -0.9999999999123431, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08918854345730803, -0.13648659371116054, -0.10649569417516626, 0.4833980482645942, 0.09731050395310598, 0.3788212119276556, -0.3475679417296472, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20347869372877544, -0.119208499819979, -0.006108021623963841]\n accelerations: []\n effort: []\n time_from_start: \n secs: 2\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20584956974297777, 0.13622915267109276, 0.49026997596542493, 0.0, -0.09563245738549116, -0.11201254330131988, -2.1410307249611287, -0.5885854280285516, -1.0650707400211386, -1.2170697945073672, -2.664914109768335, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.733083621328042, 0.4568044054527166, 1.8816078509680838, -1.3233471258646443, -2.339360013525105, -0.7935780776758881, 1.0211795057893378, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5544385794568797, -0.5114877119316235, 0.027852796972441026]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904517250131, 0.14751911596543701, 0.05032493334339612, 0.0, 0.3129267786620501, 0.1844024659339423, 0.2297050382406099, 1.0000005034669874, 0.39816923166862045, -0.841235699737842, -0.9999999999960145, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.14458262424423035, -0.12471375289151534, -0.11828406832708285, 0.4496657476858964, 0.04885181902497327, 0.30121350414296555, -0.27870794424844453, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20198526190161653, -0.06940196623992366, -0.016962083913670545]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20519961749850008, 0.14347767687799604, 0.4926883436390763, 0.0, -0.0799490845530307, -0.10473597296061643, -2.1385753663749787, -0.5385854029659267, -1.042777806598555, -1.2530083189787227, -2.7141678650258716, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.723212907717397, 0.4514133974815875, 1.8753360586111512, -1.301981413310433, -2.338886394443288, -0.7819601456803171, 1.0101823202031883, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5644669740578634, -0.5124715600072361, 0.026578481527876154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044889553888, 0.14497048413806565, 0.04836735347302726, 0.0, 0.3136674566492093, 0.14553140681406895, 0.04910717172737772, 1.000000501252499, 0.4458586684516722, -0.7187704894271084, -0.9850751051507305, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.19741427221289898, -0.107820159422582, -0.12543584713865363, 0.42731425108422566, 0.009472381636343591, 0.232358639911418, -0.21994371172299126, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20056789201967395, -0.019676961512254725, -0.02548630889129742]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20454966525107235, 0.1501180568282623, 0.4950581279024008, 0.0, -0.0643583983722623, -0.0986053141444437, -2.1477792342193154, -0.48858537787584494, -1.0152356226636083, -1.2833013137851883, -2.760990841056552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.7109834366159921, 0.4468695283308784, 1.8688737216200249, -1.281207065531371, -2.3399299756846346, -0.7730676992512461, 1.001480798261087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5744416597538146, -0.5113878401654328, 0.025071403548264388]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044948554406, 0.1328075990053251, 0.04739568526648936, 0.0, 0.3118137236153678, 0.12261317632345448, -0.18407735688673582, 1.0000005018016358, 0.5508436786989327, -0.6058598961293146, -0.9364595206136054, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24458942202809822, -0.09087738301418201, -0.12924673982252782, 0.4154869555812392, -0.0208716248269358, 0.17784892858142218, -0.17403043884202934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19949371391902437, 0.021674396836067467, -0.030141559592235332]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20389971302483856, 0.1557347602845968, 0.4974355814920868, 0.0, -0.049171950719876324, -0.09290833001914381, -2.166699123922198, -0.43858535282219446, -0.983039311514298, -1.3088912161864783, -2.805051479993562, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.696631918576592, 0.44306047961185746, 1.8623103243262331, -1.2606412765175208, -2.3421891515752655, -0.766255196787645, 0.9945600283663869, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.584377181551185, -0.5085839361568828, 0.02352282088400695]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044524675847, 0.11233406912669008, 0.04754907179371985, 0.0, 0.3037289530477196, 0.11393968250599804, -0.37839779405765367, 1.0000005010730098, 0.6439262229862059, -0.5117980480258004, -0.8812127787402005, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2870303607880001, -0.07618097438041899, -0.13126794587583548, 0.41131578027700544, -0.04518351781261587, 0.1362500492720216, -0.13841539789400073, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1987104359474099, 0.056078080171000425, -0.03097165328514873]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20324976078082183, 0.16004026855228848, 0.4998663148578667, 0.0, -0.03475744050340202, -0.08704928408971153, -2.1937156986745796, -0.3885853277524376, -0.9469153092290022, -1.330848638717644, -2.846731398229221, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.680328560204502, 0.43983553820878407, 1.8556791868320301, -1.2400132328159672, -2.3454682780451055, -0.761004411987782, 0.989031466263781, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.5942847510091662, -0.5043478281575161, 0.022093544939932187]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880334902, 0.0861101653538336, 0.04861466731559875, 0.0, 0.288290204329486, 0.1171809185886454, -0.5403314950476272, 1.0000005013951379, 0.7224800457059154, -0.4391484506233125, -0.8335983647131766, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3260671674417992, -0.0644988280614681, -0.1326227498840574, 0.4125608740310738, -0.06558252939680123, 0.10501569599726031, -0.11057124205211823, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19815138915962352, 0.08472215998733477, -0.02858551888149523]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20259980853628662, 0.1628810660419216, 0.5023836857779382, 0.0, -0.02146507066358042, -0.08050544006023874, -2.227328958476591, -0.3385853065366045, -0.9075100422134267, -1.350229081014295, -2.886554478075514, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6622171825178012, 0.4370416681576247, 1.8489840447886192, -1.2191099997866723, -2.349599213706185, -0.7568828944553346, 0.9845644102047254, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6041723284826315, -0.49892698401412294, 0.020906601296891956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044890704152, 0.056815949792662565, 0.05034741840143012, 0.0, 0.26584739679643205, 0.13087688058945599, -0.6722651960402309, 1.0000004243166616, 0.7881053403115118, -0.3876088459330212, -0.7964615969258632, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.36222755373401777, -0.05587740102318819, -0.13390284086821666, 0.41806466058589586, -0.08261871322159553, 0.08243035064894742, -0.08934112118111256, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19775154946930532, 0.108416882867863, -0.023738872860804647]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20194985629231166, 0.16403503715368722, 0.5050072272508807, 0.0, -0.011243884127353705, -0.07421039306373724, -2.2662195663178375, -0.2898353030935007, -0.8658600300289816, -1.3654800266138287, -2.922378543192585, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6422493597370729, 0.43452377840769396, 1.8421865306661536, -1.1975862116477367, -2.3543180247878333, -0.7533806159453872, 0.9807201183559711, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6140442139193496, -0.49255562128481134, 0.02022972303051304]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879498977, 0.02307942223531246, 0.05247082945884825, 0.0, 0.20442373072453424, 0.1259009399300301, -0.7778121568249285, 0.9750000688620889, 0.8330002436889006, -0.30501891199067344, -0.7164813023414127, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3993564556145661, -0.05035779499861437, -0.1359502824493128, 0.43047576277871336, -0.09437622163296054, 0.07004557019894854, -0.07688583697508587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19743770873436203, 0.12742725458623247, -0.013537565327578261]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20129990404829132, 0.1634528238542528, 0.5077442557294407, 0.0, -0.0052736904708706395, -0.0688637565733239, -2.3093320525908254, -0.24608531727078933, -0.8223896271717159, -1.3756473939547909, -2.953043017750895, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6204459301088425, 0.43216271543255413, 1.8352615284808589, -1.1751861103482526, -2.359402241429792, -0.7501162514018523, 0.9771526473899087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6239007551967034, -0.4854186738108172, 0.02021091229376357]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880406778, -0.01164426598868843, 0.054740569571201006, 0.0, 0.1194038731296613, 0.10693272980826685, -0.862249725459756, 0.8749997164542269, 0.8694080571453129, -0.2033473468192408, -0.6132894911662041, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.4360685925646062, -0.04722125950279615, -0.13850004370589578, 0.4480020259896821, -0.10168433283917212, 0.0652872908706964, -0.07134941932124653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19713082554707667, 0.14273894947988258, -0.0003762147349894666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20064995207125083, 0.16125515316071548, 0.5105965959626493, 0.0, -0.0037487047189047433, -0.06473860939691131, -2.3558220390061826, -0.2110853491157563, -0.7770705824432016, -1.3807552560112464, -2.9786328165653635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5969319840743816, 0.42987640088613466, 1.8282067634454782, -1.1517576808179886, -2.364683061285807, -0.7468397566077684, 0.9736201630002069, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6337399387311056, -0.47766274797102026, 0.02085730157444466]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999039540809772, -0.043953413870746395, 0.057046804664170475, 0.0, 0.030499715039317907, 0.08250294352825183, -0.9297997283071426, 0.6999993631006605, 0.9063808945702878, -0.1021572411291091, -0.5117959762893696, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.47027892068921706, -0.04572629092838926, -0.14109530070761406, 0.46856859060527967, -0.10561639712030374, 0.06552989588167944, -0.07064968779403517, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1967836706880425, 0.1551185167959386, 0.012927785613621815]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19999999984326117, 0.15768765165884438, 0.5135512489358962, 0.0, -0.00616463600715151, -0.061846554116171536, -2.405014028064136, -0.18858539873101185, -0.7298031601922028, -1.3815453045766257, -3.000000195125954, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5719289977899731, 0.42761247062920993, 1.8210415729253842, -1.127232545602249, -2.3700346013699742, -0.7433995533741241, 0.9699621806321289, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6435589804185872, -0.4694049232923046, 0.022059696800314513]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044559793125, -0.07135003003742205, 0.05909305946493837, 0.0, -0.04831862576493534, 0.05784110561479554, -0.9838397811590689, 0.449999007694889, 0.9453484450199748, -0.015800971307585995, -0.4273475712118086, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.50005972568817, -0.04527860513849512, -0.14330381040188064, 0.49050270431479176, -0.10703080168334739, 0.06880406467288452, -0.07315964736156136, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19638083374963167, 0.1651564935743131, 0.02404790451739708]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1993500475993132, 0.1531059836622251, 0.5165972804966571, 0.0, -0.011321500045881627, -0.059722561727841024, -2.455014053119358, -0.1748354661144148, -0.6808404506671848, -1.3797754066509618, -3.018756930641455, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.545776366805559, 0.42534237538555697, 1.8138078595489, -1.101631862133982, -2.3753719026962243, -0.7397278004894978, 0.9660930013351087, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6533561077416291, -0.46074001291962563, 0.02359243322392935]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044878959289, -0.09163335993238557, 0.060920631215217964, 0.0, -0.10313728077460235, 0.042479847766610235, -1.0000005011044395, 0.274998652289112, 0.9792541905003596, 0.03539795851328094, -0.3751347103100101, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5230526196882822, -0.04540190487305961, -0.1446742675296841, 0.5120136693653407, -0.1067460265249996, 0.07343505769252516, -0.07738358594040508, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1959425464608382, 0.17329820745357993, 0.03065472847229672]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19870009535586797, 0.1478265715582224, 0.5197240940829704, 0.0, -0.018404427062329774, -0.05835052075953421, -2.5050140781741654, -0.1660855512702357, -0.630840450758246, -1.376485342803627, -3.035810258442042, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5187666738714398, 0.42304827153940777, 1.8065449697932832, -1.074960536705539, -2.380613433408026, -0.7357640502338193, 0.9619317187747937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6631309078675722, -0.451745218465321, 0.025253383383543715]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044868904913, -0.1055882420800543, 0.06253627172626618, 0.0, -0.14165854032896297, 0.0274408193661363, -1.0000005010961466, 0.17499829688358215, 0.9999999981787757, 0.06580127694669732, -0.3410665560117501, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5401938586823838, -0.04588207692298429, -0.14525779511233775, 0.5334265085688592, -0.10483061423602534, 0.07927500511357005, -0.08322565120630003, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19549600251886146, 0.17989588908609205, 0.03321900319228731]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1980501431118577, 0.1421007874172408, 0.5229216746904746, 0.0, -0.02658431568031288, -0.05747198159103363, -2.5550141032293996, -0.15858565418962448, -0.5808404507647364, -1.3727673576968753, -3.0520895642158288, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4911254567069497, 0.42071833519784235, 1.79928617618249, -1.0471938394617235, -2.385674963330175, -0.7314405198040996, 0.9573896266296948, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6728842725984181, -0.44248358922131076, 0.02688599015013237]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880205283, -0.1145156828196317, 0.06395161215008299, 0.0, -0.16359777235966208, 0.017570783370011552, -1.0000005011046809, 0.1499979414776177, 0.9999999998701911, 0.07435970213503222, -0.32558611547573035, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5528243432898023, -0.046598726831308786, -0.14517587221586284, 0.5553339448763092, -0.10123059844298155, 0.08647060859439241, -0.0908418429019767, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19506729461691788, 0.18523258488020505, 0.032652135331773094]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19740019086785293, 0.13606399813496428, 0.5261810657016347, 0.0, -0.035472835377396775, -0.057101985885221355, -2.605014128284609, -0.15483565910571975, -0.5308404507710939, -1.368904944270376, -3.067949081016235, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46294756611546506, 0.4183410790120704, 1.792050829594656, -1.0182330824384032, -2.3904526312345604, -0.7266530272982114, 0.9523399269391635, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6826176217761467, -0.4330062059173643, 0.028430379332107875]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880095423, -0.12073578564553024, 0.06518782022320214, 0.0, -0.17777039394167793, 0.007399914116245536, -1.00000050110419, 0.0749999016780947, 0.9999999998728506, 0.0772482685299836, -0.3171903360081307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.563557811829693, -0.04754512371543864, -0.14470693175668006, 0.5792151404664072, -0.09555335808771143, 0.0957498501177645, -0.10099399381062744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19466698355457251, 0.1895476660789295, 0.030887783639510044]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19675023862382987, 0.12982277795756555, 0.5294946501058542, 0.0, -0.043531957664554234, -0.057110529894674356, -2.655014153339869, -0.15108566257591344, -0.4808404507710939, -1.3652633803964829, -3.082522285964115, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.4356805662753338, 0.4157580239385849, 1.7851077565307472, -0.9877918440271041, -2.393629089153797, -0.7201146745182879, 0.9453928203124106, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.6923502699602505, -0.42393915197121984, 0.029838748765362626]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880461195, -0.12482440354797446, 0.06627168808438987, 0.0, -0.16118244574314916, -0.00017088018905999074, -1.0000005011051973, 0.07499993059612628, 1.0, 0.07283127747786261, -0.2914640989576027, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.5453399968026248, -0.051661101469710376, -0.13886146127817714, 0.6088247682259811, -0.06352915838472939, 0.13076705559846796, -0.13894213253505744, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1946529636820768, 0.18134107892288842, 0.02816738866509501]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19610028637983842, 0.12348623709877309, 0.5328527398750367, 0.0, -0.04969676221172055, -0.057485647706447485, -2.7050141783949404, -0.1510856639697593, -0.4308404507919986, -1.361897389465149, -3.094971635756059, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.41044558298583034, 0.4128748517544358, 1.7786892467856021, -0.9557549202216273, -2.3941818789341616, -0.7109142627610385, 0.9355052143242124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7021041457419289, -0.41590859078600234, 0.031094731410392658]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044879828718, -0.1267308171758495, 0.06716179538365002, 0.0, -0.1232960909433263, -0.00750235623546257, -1.0000005011014281, -2.7876917302327442e-08, 0.9999999995819053, 0.0673198186266802, -0.24898699583888168, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.504699665790069, -0.05766344368298311, -0.12837019490289894, 0.6407384761095339, -0.011055795607288886, 0.18400823514498735, -0.19775211976396387, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.195077515633568, 0.16061122370434996, 0.025119652900600663]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19545033413581114, 0.11725984300068812, 0.5362419192213744, 0.0, -0.05346509209642338, -0.05821348256404178, -2.7550142034502008, -0.15108566396972173, -0.3808404507919988, -1.3589670324368708, -3.1050165137103725, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3877605510969789, 0.4096955213135772, 1.7729241862523164, -0.922217272698735, -2.391649727333554, -0.6988078337317745, 0.9222569378761857, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.711903327841214, -0.40954104556327225, 0.032154828425129574]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880545577, -0.1245278819616992, 0.0677835869267552, 0.0, -0.07536659769405668, -0.014556697151885964, -1.0000005011052027, 7.515571488957265e-13, 0.9999999999999958, 0.05860714056556331, -0.2008975590862666, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.45370063777702946, -0.06358660881717078, -0.11530121066571655, 0.6707529504578463, 0.05064303201215177, 0.24212858058528186, -0.26496552896053505, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1959836419857026, 0.1273509044546015, 0.021201940294738347]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.194800381891786, 0.11140651526474173, 0.5396456406321406, 0.0, -0.05472175647520017, -0.059232195843190456, -2.805014228505461, -0.15108566396970827, -0.330840450791999, -1.3565871969353567, -3.1126913630238477, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3677081904528124, 0.4062750476728567, 1.7678641069457335, -0.8873084625152019, -2.385832343668878, -0.6839122652153853, 0.9054977056595419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.721772988008984, -0.40546319243640266, 0.03299932331538283]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880502625, -0.11706655471892778, 0.06807442821532397, 0.0, -0.02513328757553563, -0.02037426558297347, -1.0000005011052049, 2.6930039876871783e-13, 0.999999999999997, 0.0475967100302808, -0.15349698626950314, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40104721288332945, -0.06840947281441045, -0.10120158613166023, 0.6981762036706615, 0.11634767329352289, 0.29791137032778403, -0.33518464433287654, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1973932033554007, 0.08155706253739231, 0.016889897805065085]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19415042964776344, 0.10624086999716453, 0.543045632780374, 0.0, -0.05348699854456831, -0.06045094654852357, -2.855014253560714, -0.15108566397066872, -0.2808404508041338, -1.354804428019382, -3.1180936245074147, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.35020072663132, 0.40267658592562, 1.763532413131884, -0.851091450772986, -2.3765030775719227, -0.666426491427131, 0.8850237238372762, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.73172413878826, -0.4038776609292309, 0.03363408450187708]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880451413, -0.103312905351544, 0.0679998429646669, 0.0, 0.024695158612637234, -0.024375014106662304, -1.0000005011050572, -1.92089421119441e-11, 0.9999999997573039, 0.035655378319491046, -0.10804522967133524, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35014927642984706, -0.07196923494473477, -0.08663387627699216, 0.724340234844318, 0.18658532193910699, 0.34971547576508616, -0.40947963644531254, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19902301558552038, 0.031710630143435226, 0.012695223729885036]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19350047740374038, 0.10208601244693091, 0.5464253702836711, 0.0, -0.0500554056491182, -0.06177358669528461, -2.905014278615974, -0.1510856639706687, -0.2308404508041338, -1.353593745533974, -3.121540769967444, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.334795790861629, 0.39897602354908296, 1.7598920071795534, -0.8134632686738965, -2.363555862553039, -0.6467319013928798, 0.8607037819043989, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7417455709631614, -0.4043697536173637, 0.03408620694107694]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880461285, -0.08309715100467241, 0.06759475006594273, 0.0, 0.06863185790900211, -0.026452802935220857, -1.0000005011051973, 6.699698549881089e-16, 1.0, 0.02421364970816069, -0.06894290920059078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.30809871539382094, -0.07401124753074047, -0.07280811904660889, 0.7525636419817895, 0.2589443003776699, 0.3938918006850227, -0.4863988386575473, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2004286434980274, -0.00984185376265648, 0.009042448783997115]\n accelerations: []\n effort: []\n time_from_start: \n secs: 3\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19285052515971743, 0.09919621459447991, 0.5497746088744935, 0.0, -0.044743809407597465, -0.06311462718084727, -2.9550143036712315, -0.15108566397393738, -0.18084045080628525, -1.3528928706486967, -3.123336846852577, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3209903415746785, 0.3952334020779346, 1.7569151089505652, -0.7741415471294454, -2.346768275172348, -0.625184498628295, 0.8322293043745047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7518268543330414, -0.4065938730473247, 0.034391306373769054]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01299904488045882, -0.05779595704902002, 0.06698477181644778, 0.0, 0.10623192483041466, -0.02682080971125322, -1.0000005011051578, -6.537362009349135e-11, 0.9999999999569708, 0.014017497705543246, -0.03592153770265838, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.27610898573900977, -0.074852429422967, -0.05953796457976281, 0.7864344308890218, 0.3357517476138206, 0.4309480552916968, -0.5694895505978831, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2016256673975996, -0.044482388599219956, 0.006101988653842297]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19220057291569473, 0.09771681594988851, 0.5530897308860852, 0.0, -0.0378326129635943, -0.06440600603043037, -3.0050143287264848, -0.15108566396806272, -0.13084045080689594, -1.3526246336896657, -3.123729111930007, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3082969862682504, 0.391562832084579, 1.7544032059645278, -0.7327468420860533, -2.3256337929756556, -0.6020119965039805, 0.7989388921336881, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7619586078069222, -0.4102619236645109, 0.03458597316747342]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880453997, -0.029587972891827918, 0.06630244023183293, 0.0, 0.13822392888006327, -0.025827576991661962, -1.0000005011050692, 1.1749331784800576e-10, 0.9999999999877863, 0.005364739180617806, -0.007845301548598749, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2538671061285619, -0.0734113998671122, -0.05023805972075046, 0.8278941008678415, 0.42268964393384745, 0.46345004248628874, -0.6658082448163329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20263506947761573, -0.07336101234372465, 0.0038933358740873454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 49999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19155062067167086, 0.09768311833415702, 0.5563715143433214, 0.0, -0.029578400160805388, -0.06559781370835066, -3.0550143537817447, -0.15108566396804227, -0.08084045080689617, -1.352709797800101, -3.1229315466599212, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.29624812924312005, 0.38828587567980505, 1.7515133532901046, -0.6888641628709329, -2.2990742171570946, -0.5771980123146865, 0.7608559862502859, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7721323180897082, -0.41512481737513857, 0.034703972904727945]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880477215, -0.0006739523146299699, 0.06563566914472549, 0.0, 0.1650842560557783, -0.023836153558405765, -1.0000005011051971, 4.093820046833613e-13, 0.9999999999999953, -0.0017032822087073227, 0.01595130540171204, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.24097714050260752, -0.06553912809547843, -0.05779705348846587, 0.8776535843024084, 0.5311915163712216, 0.4962796837858806, -0.7616581176680423, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20347420565572077, -0.09725787421255347, 0.0023599947450904167]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19090066842068107, 0.09905019821720568, 0.559622516332651, 0.0, -0.020251583133576265, -0.0666557903129154, -3.105014378837004, -0.1510856639671973, -0.030840450806902286, -1.3530693915611052, -3.1211788744540523, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2844025123609683, 0.38605225882708716, 1.7461341166806055, -0.6422997301764205, -2.2658265565003815, -0.5504230827574887, 0.7183896615413528, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7823396072090592, -0.42094391136383696, 0.0347657581216569]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045019795926, 0.027341597660972963, 0.06502003978659196, 0.0, 0.1865363405445825, -0.02115953209129461, -1.0000005011051905, 1.6899523227346692e-11, 0.9999999999998775, -0.007191875220084972, 0.03505344411737497, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.23691233764303435, -0.04467233705435793, -0.10758473218998413, 0.9312886538902485, 0.6649532131342638, 0.5354985911439556, -0.8493264941786643, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20414578238701966, -0.11638187977396824, 0.001235704338579088]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19025071618273126, 0.10177670978088993, 0.5628453353346253, 0.0, -0.010008191778812053, -0.06755713850463801, -3.1550144038921792, -0.15108566396789896, 0.019159549192805186, -1.3536065082394133, -3.118653567873419, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2725368957113056, 0.38453371293233773, 1.7384471621046758, -0.5936379938258535, -2.2272284279763612, -0.522335624205453, 0.6724166017760013, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.7925732316328732, -0.4275289296599921, 0.03472065903468458]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044758996303, 0.054530231273685024, 0.06445638003948663, 0.0, 0.20486782709528423, -0.01802696383445232, -1.0000005011034976, -1.4033141114487748e-11, 0.9999999999941495, -0.010742333566161255, 0.0505061316126605, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2373123329932541, -0.030370917894988088, -0.15373909151859416, 0.9732347270113408, 0.771962570480407, 0.5617491710407155, -0.9194611953070297, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20467248847628142, -0.13170036592310264, -0.0009019817394463239]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18960076388482106, 0.10574357227851135, 0.5660417576546126, 0.0, -0.00042576089466839565, -0.06829442303081046, -3.2012644289473546, -0.1510856639621717, 0.06540954919226402, -1.3542323562786198, -3.11591463792251, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2592387461756797, 0.3834738615738649, 1.7287842128246071, -0.5436379687750676, -2.1843499251465626, -0.4942662776437652, 0.6236381539450436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8028106481204823, -0.43425648000666217, 0.03455544591445554]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045958203951, 0.07933724995242827, 0.06392844639974546, 0.0, 0.1916486176828731, -0.014745690523448884, -0.9250005011035052, 1.1454484291921683e-10, 0.9249999999891767, -0.012516960784131496, 0.05477859901818476, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.26596299071251867, -0.02119702716945642, -0.193258985601374, 1.0000005010157158, 0.8575700565959689, 0.5613869312337558, -0.9755689566191522, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20474832975218196, -0.13455100693340136, -0.003304262404580721]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18895081164078212, 0.11084488526123108, 0.5692152641411549, 0.0, 0.007327081444803023, -0.06891422758095465, -3.24001445400253, -0.15108566396217094, 0.10415954919147422, -1.3548236443389758, -3.113469220037347, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24389564605362593, 0.3826857249632519, 1.7174401801441044, -0.4936379437197939, -2.1380471228827242, -0.4674307293897115, 0.5736381539450451, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8130290285570152, -0.4405040284177781, 0.034185257773753745]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880778517, 0.10202625965439471, 0.06347012973084504, 0.0, 0.15505684678942835, -0.012396091002884031, -0.7750005011035128, 1.5416625098004766e-14, 0.774999999984204, -0.011825761207120965, 0.04890835770325934, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3068620024410758, -0.015762732212259954, -0.22688065361005555, 1.000000501105475, 0.9260560452767674, 0.5367109650810742, -0.9999999999999701, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2043676087306583, -0.12495096822231867, -0.0074037628140359805]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 299999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18830085939674862, 0.1168682998621621, 0.5723735984918562, 0.0, 0.01279488605585831, -0.06949015565604581, -3.267514479057706, -0.1510856639621704, 0.13165954919043577, -1.355295556055603, -3.1116941390594457, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.22639404800798923, 0.38206343620151845, 1.7044270009377873, -0.4436379186645256, -2.0890048810716535, -0.44252512835682656, 0.5236381539450461, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8232062897281709, -0.4456495101855262, 0.03356048893964285]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880669865, 0.12046829201862037, 0.06316668701402718, 0.0, 0.10935609222110573, -0.011518561501823146, -0.5500005011035205, 1.0285593347541038e-14, 0.5499999999792312, -0.009438234332541996, 0.03550161955802123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.35003196091273364, -0.012445775234669245, -0.26026358412634165, 1.0000005011053654, 0.9808448362214114, 0.49811202065769816, -0.9999999999999819, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20354522342311293, -0.1029096353549623, -0.012495376682217854]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.187650907146763, 0.12349070696850292, 0.575530926732498, 0.0, 0.015875769056676658, -0.07009857410633885, -3.2800145041138236, -0.1510856639619281, 0.14415954918915228, -1.3556044392466584, -3.110780610866699, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.20678927323091031, 0.38145448726057296, 1.6900504329166228, -0.393637893605721, -2.039004881071841, -0.41995974399263125, 0.4736381539454505, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8333223339433692, -0.449070888338172, 0.03267152049044358]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044999712342, 0.13244814212681633, 0.06314656481283405, 0.0, 0.06161766001636698, -0.012168369005860841, -0.2500005011223463, 4.846041807285645e-12, 0.24999999997433026, -0.006177663821108001, 0.018270563854934467, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3920954955415783, -0.012178978818909237, -0.2875313604232904, 1.0000005011760922, 0.9999999999962499, 0.45130768728390613, -0.9999999999919122, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2023208843039665, -0.06842756305291622, -0.01777936898398549]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18700095490224208, 0.1303059818083584, 0.578709596447737, 0.0, 0.01663740539542849, -0.07079335890312408, -3.279348617111691, -0.15108566396190268, 0.1433262158547493, -1.3557531566458456, -3.1108328465955637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.18518989723312684, 0.38070151043865647, 1.674827226995007, -0.34363787239074856, -1.989004881071854, -0.3999369843270981, 0.4236381539454852, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8433600970483742, -0.4501459080461137, 0.031530233574934854]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044890418355, 0.13630549679710965, 0.06357339430478097, 0.0, 0.015232726775036641, -0.01389569593570463, 0.013317740042652182, 5.084029732821355e-13, -0.016666666688059273, -0.0029743479837431807, -0.0010447145772944123, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.43198751995566914, -0.015059536438330285, -0.30446411843231347, 1.0000004242994487, 0.9999999999997422, 0.4004551933106626, -0.9999999999993061, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2007552621001006, -0.021500394158834236, -0.0228257383101745]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18635100265822452, 0.13716782503642297, 0.5819414810463058, 0.0, 0.015622662698062803, -0.07158909666787702, -3.2676865852172723, -0.1510856639619363, 0.13138177142430832, -1.3556264374294271, -3.1118264350361655, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.16482978366483125, 0.37956727677911706, 1.6605101123009882, -0.2948878689479938, -1.9390048810727891, -0.38320267563393423, 0.3736381539456568, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8533331710492935, -0.4491320139890995, 0.029839529773247796]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880351208, 0.13723686456129133, 0.06463769197137753, 0.0, -0.020294853947313757, -0.015914755295059032, 0.23324063788837107, -6.723347370973023e-13, -0.23888888860881952, 0.0025343843283717675, -0.019871768812037185, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.40720227136591186, -0.022684673190788124, -0.2863422938803785, 0.9750000688550795, 0.9999999999812937, 0.33468617386327815, -0.9999999999965685, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19946148001838562, 0.020277881140283848, -0.033814076033741196]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18570105059554876, 0.14372000985997885, 0.5852616088199726, 0.0, 0.013150080016791667, -0.07247482681912906, -3.246826533544618, -0.15108566396397757, 0.11017806894184964, -1.3552536464253246, -3.113673881772124, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14731632679496365, 0.37730029947682714, 1.6508490803594336, -0.2511378748513695, -1.8927548810250436, -0.3706853076590909, 0.3271660452713667, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8632601662738979, -0.4463858952467008, 0.02755433778903355]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999041253515484, 0.13104369647111783, 0.06640255547333526, 0.0, -0.04945165362542271, -0.01771460302504093, 0.4172010334530901, -4.0825890786404623e-11, -0.4240740496491734, 0.0074558200820498185, -0.0369489347191731, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.3502691373973523, -0.0453395460457983, -0.1932206388310925, 0.8749997134115084, 0.9250000009549093, 0.2503473594968669, -0.9294421734858019, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19853990449208828, 0.054922374847974006, -0.04570383968428495]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 549999999\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18505109835132671, 0.1495111131536685, 0.5887013217648692, 0.0, 0.00931219129786175, -0.0734210099581803, -3.2182616806552238, -0.15108566396396783, 0.0812583168731341, -1.3547750322338903, -3.1162672465180634, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1328210203207374, 0.37434308384091103, 1.6455594497755093, -0.21613790695268945, -1.8540048809286176, -0.3616218961841422, 0.2879718279226149, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.873158245191225, -0.442204125368704, 0.024838751974921722]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044884440905, 0.11582206587379303, 0.06879425889793392, 0.0, -0.07675777437859833, -0.01892366278102456, 0.5712970577878788, 1.9500473059854678e-13, -0.5783950413743107, 0.009572283828689267, -0.05186729491878928, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.28990612948452515, -0.05914431271832189, -0.10579261167848765, 0.6999993579736011, 0.7750000019285248, 0.1812682294989748, -0.7838843469750373, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19796157834654132, 0.08363539755993613, -0.05431171628223651]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18440114610098793, 0.15414407269932823, 0.5922847927776022, 0.0, 0.004127325710146613, -0.07438421725731753, -3.183465468653156, -0.1510856639636442, 0.046122515218160964, -1.354367038965555, -3.1195149135950384, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12078338944013996, 0.37121588888835955, 1.6419956491561358, -0.19363795682445784, -1.8265048807835136, -0.3550175377881328, 0.25980550189940127, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.883041798944669, -0.43683829991992523, 0.02193868311631353]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045006775784, 0.09265919091319452, 0.0716694202546576, 0.0, -0.10369731175430275, -0.0192641459827447, 0.6959242400413602, 6.4723970762956335e-12, -0.7027160330994626, 0.008159865366703163, -0.06495334153949786, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2407526176119486, -0.0625438990510294, -0.07127601238746689, 0.44999900254446545, 0.5500000029021404, 0.13208716792018851, -0.5633265204642727, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19767107506888132, 0.10731650897557556, -0.05800137717216389]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18375119384291677, 0.15732942807231187, 0.5960270238503697, 0.0, -0.0023616147181740096, -0.07531734882974532, -3.1436778726233734, -0.1510856639629031, 0.006013873894185555, -1.3541933031256093, -3.123265085874298, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10995913409493915, 0.3680666995102423, 1.6407153122466238, -0.17988802446905186, -1.8140048805897255, -0.3502158021940072, 0.24498336322442604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.8929219161656519, -0.43053012581329686, 0.019114919880067693]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045161422964, 0.06370710745967303, 0.07484462145534933, 0.0, -0.12977880856641244, -0.01866263144855585, 0.7957519205956515, 1.4822292710075692e-11, -0.8021728264795082, 0.0034747167989180117, -0.07500344558519137, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.21648510690401612, -0.06298378756234504, -0.025606738190238537, 0.2749986471083416, 0.2500000038757602, 0.0960347118825112, -0.29644277349950443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1976023444196566, 0.12616348213256767, -0.05647526472491666]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18310124150925075, 0.1589889611753551, 0.5999337936781227, 0.0, -0.00984731799743496, -0.07617358642091679, -3.1026488864346318, -0.15108566396100356, -0.03531761227217421, -1.3543383854722173, -3.1277285057152535, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.09983094535420313, 0.36506538386402926, 1.6407601284466957, -0.1711381098793262, -1.8148382118118953, -0.34667186046993215, 0.24235030700496213, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9028056123666762, -0.4234714369026071, 0.01651140412187688]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046673320499, 0.033190662060864594, 0.07813539655506205, 0.0, -0.14971406558521902, -0.01712475182342931, 0.8205797237748332, 3.799090597542977e-11, -0.8266297233271953, -0.0029016469321622267, -0.0892683968191105, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20256377481472054, -0.060026312924260486, 0.0008963240014389778, 0.17499829161692027, -0.01666662444339634, 0.07087883448150187, -0.05266112438927842, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19767392402048758, 0.14117377821379615, -0.05207031516381623]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1824512892652273, 0.15915939644494007, 0.6040022486202019, 0.0, -0.01790119568347799, -0.07694366735720332, -3.064128510086931, -0.15108566396100354, -0.07412194328091834, -1.3548016861352943, -3.1333542967049053, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08974399180899639, 0.3622112885232253, 1.6428104144171176, -0.16363821307305126, -1.826782654497037, -0.3441091903026668, 0.2488243667568404, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9126966482492623, -0.4158144144853017, 0.014217011760813062]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880469067, 0.003408705391698987, 0.08136909884158368, 0.0, -0.16107755372086058, -0.015401618725730402, 0.7704075269540149, 4.046905280882585e-16, -0.7760866201748824, -0.009266013261538563, -0.11251581979303481, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.20173907090413462, -0.05708190681607927, 0.041005719408437384, 0.14999793612549894, -0.23888885370283033, 0.05125340334530691, 0.1294811950375653, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.197820717651723, 0.1531404483461079, -0.04588784722127638]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18180133702120382, 0.1579836902397271, 0.6082239844852447, 0.0, -0.026245477880351354, -0.07765637687954342, -3.031866743580271, -0.1510856639610035, -0.1066491191320468, -1.3554931543420097, -3.140331227004298, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07958225519360303, 0.3595102128394174, 1.6466750999640751, -0.1598882172868466, -1.8479863567346548, -0.3423665152106241, 0.2626293353429637, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9225967014108053, -0.4076801011764562, 0.012242447282070938]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880469665, -0.023514124104259182, 0.08443471730085615, 0.0, -0.16688564393746724, -0.014254190446802208, 0.6452353301331967, 4.3893720018571743e-16, -0.6505435170225695, -0.01382936413430796, -0.13953860598785225, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.2032347323078672, -0.054021513676158386, 0.07729371093914962, 0.07499991572409334, -0.42407404475235866, 0.03485350184085309, 0.27609937172246535, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19800106323085867, 0.1626862661769106, -0.03949128957484249]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18115138465868108, 0.15564678986916028, 0.6125871981160778, 0.0, -0.03361419240013659, -0.07836283251325987, -3.0096135869123235, -0.15108566395456785, -0.12914913982615003, -1.3563246227167198, -3.1475371302524815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07033204439736407, 0.35662631523658256, 1.656104185056394, -0.1561382222029459, -1.8769061085970973, -0.34143627720905445, 0.2800152127652186, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9325117905050209, -0.39969057515731043, 0.01055997406833761]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999047250454683, -0.04673800741133668, 0.08726427261666053, 0.0, -0.1473742903957047, -0.014129112674329083, 0.44506313335895087, 1.287132596842939e-10, -0.45000041388206435, -0.016629367494202383, -0.14411806496367263, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.18500421592477906, -0.05767795205669744, 0.18858170184637846, 0.0749999016780138, -0.5783950372488509, 0.01860476003139278, 0.34771754844509944, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19830178188431102, 0.15979052038291505, -0.03364946427466657]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18050143249818038, 0.15238286092135125, 0.6170735685025275, 0.0, -0.039042785036414715, -0.0791166074452899, -3.001119040082996, -0.15108566395905232, -0.1378720053635739, -1.3572409674664012, -3.1540043553793686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06278847247649953, 0.3533160146345854, 1.6748476696820527, -0.15238822711904093, -1.9120419100866872, -0.34127662330276953, 0.29723199902385944, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9424451545427063, -0.39246829759872076, 0.009133325242966839]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999043210014247, -0.06527857895618058, 0.08972740772899394, 0.0, -0.10857185272556252, -0.015075498640600326, 0.1698909365865478, -8.968913603425124e-11, -0.1744573107484777, -0.01832689499362691, -0.12934450253773833, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.15087143841729078, -0.06620601203994364, 0.37486969251317437, 0.07499990167810085, -0.7027160297917996, 0.003193078125698903, 0.3443357251728169, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1986672807537077, 0.14444555117179345, -0.028532976507415438]\n accelerations: []\n effort: []\n time_from_start: \n secs: 4\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17985148023812256, 0.1485040403757502, 0.6216570530857805, 0.0, -0.04212970094835467, -0.07995169277133968, -3.005290251050999, -0.1510856639581898, -0.13394898939747776, -1.3582234656051229, -3.159235973536804, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.057432194132922526, 0.34962387823871066, 1.7017172401933713, -0.1523882287556444, -1.9510224762068111, -0.34166623669419177, 0.31052969413526527, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9523982029141851, -0.38663617873502326, 0.007918215737823633]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045201156086, -0.07757641091202078, 0.09166969166505873, 0.0, -0.0617383182387991, -0.016701706520995615, -0.08342421936006261, 1.725052272299186e-11, 0.07846031932192304, -0.019649962774433247, -0.10463236314870206, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.1071255668715402, -0.07384272791749483, 0.5373914102263719, -3.2732069110696926e-08, -0.7796113224024789, -0.007792267828444251, 0.26595390222807846, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19906096742957533, 0.11664237727394976, -0.0243021901028641]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920152799410063, 0.14438950370246345, 0.6263050232459871, 0.0, -0.04280571278238718, -0.08087688725592981, -3.0200162601910017, -0.15108566395818984, -0.11954146316905666, -1.3592873687775122, -3.1630579394084886, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.05439232928331262, 0.34567531255408446, 1.7352128966024263, -0.1523882287556445, -1.9908180868349037, -0.34239832711491036, 0.31615829809943224, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9623710680396644, -0.38281743798443224, 0.006883760537404866]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880438454, -0.08229073346573497, 0.0929594032041331, 0.0, -0.013520236680650208, -0.01850388969180274, -0.2945201828000522, -1.2056196451885986e-15, 0.288150524568422, -0.02127806344778866, -0.07643931743369124, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.06079729699219813, -0.0789713136925239, 0.6699131281810976, -1.984127331124936e-15, -0.7959122125618534, -0.014641808414372117, 0.11257207928333998, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19945730250958782, 0.07637481501182036, -0.020689104008375345]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1785515757431032, 0.14049180633214745, 0.6309805330169114, 0.0, -0.04108261173395056, -0.0818770162320404, -3.043537934474317, -0.1510856639578668, -0.09641780671766334, -1.3604621121243403, -3.165397535989083, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.053658225782037536, 0.3415828861955776, 1.7740094217296576, -0.1523882287551262, -2.0288188547174086, -0.34327649876449906, 0.31161045425027684, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9723623061551029, -0.3815074393136128, 0.006002802492612629]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045019948276, -0.0779539474063201, 0.09351019541848467, 0.0, 0.03446202096873247, -0.020002579522211583, -0.4704334856663087, 6.46073483916983e-12, 0.4624731290278664, -0.023494866936561935, -0.046791931611883227, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.014682070025501676, -0.08184852717013741, 0.775930502544628, 1.036613310613156e-11, -0.7600153576501024, -0.01756343299177417, -0.09095687698310861, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19982476230876808, 0.026199973416388304, -0.017619160895844733]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1779016233977662, 0.1373136043554086, 0.6356456482204245, 0.0, -0.03721676254498572, -0.08291730352673327, -3.074355273900223, -0.15108566395214434, -0.06605081515808248, -1.3617583954219048, -3.166435467390029, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0549240149231531, 0.3374144189867764, 1.817046641831272, -0.15238822874598326, -2.064083672791269, -0.3442069198242152, 0.2988910361871185, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9823654777091959, -0.382288255145447, 0.005251187109685319]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046906740402, -0.06356403953477706, 0.09330230407026224, 0.0, 0.07731698377929677, -0.020805745893857277, -0.6163467885181212, 1.1444887293409058e-10, 0.6073398311916174, -0.025925665951291362, -0.02075862801891857, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025315782822311367, -0.08336934417602423, 0.8607444020322879, 1.8285895541423434e-10, -0.705296361477212, -0.018608421194322655, -0.25438836126316683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20006343108186034, -0.015616316636683765, -0.015032307658546209]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1772516710495929, 0.13529048128252258, 0.6402713836342976, 0.0, -0.03149499701051951, -0.08395031620918555, -3.11100914544, -0.1510856639462402, -0.02987127014059504, -1.3631774725600079, -3.16633910806168, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.057858352002869484, 0.33320247265458536, 1.8634764179124828, -0.15238822873660748, -2.096487574646692, -0.3451427537055695, 0.28023137361792533, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 0.9923761497353961, -0.3848116208574997, 0.004605653662711748]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999046963465384, -0.04046246145772013, 0.09251470827746201, 0.0, 0.11443531068932403, -0.02066025364904566, -0.7330774307955384, 1.1808274346496299e-10, 0.7235909003497487, -0.028381542762063686, 0.001927186566978354, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.058686741594327574, -0.0842389266438206, 0.9285955216242128, 1.8751557595464868e-10, -0.6480780371084631, -0.018716677627086887, -0.3731932513838633, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20021344052400455, -0.05046731424105442, -0.012910668939471426]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1766017188055696, 0.13471901453230187, 0.645231549819708, 0.0, -0.02416965084878169, -0.08492661174638531, -3.152270363464285, -0.1510856639462402, 0.010908203198714495, -1.3647106046236785, -3.165242001480579, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06217135434159315, 0.32895968187741137, 1.9126202387774514, -0.15238822873660746, -2.12626565705343, -0.3460676703930643, 0.2573788185876828, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0023912548109384, -0.38878735328224806, 0.004044283910718682]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880466324, -0.011429335004414138, 0.09920332370820686, 0.0, 0.14650692323475642, -0.019525910743995213, -0.8252243604856998, -5.1800227045744044e-17, 0.8155894667861907, -0.03066264127341375, 0.02194213162201805, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08626004677447328, -0.08485581554348026, 0.9828764172993703, 4.288595310145001e-16, -0.5955616481347529, -0.018498333749895728, -0.4570511006048501, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.200302101510847, -0.07951464849496764, -0.011227395039861325]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517665611328, 0.13574270242782435, 0.6502725913472744, 0.0, -0.01571113510471196, -0.08580388757662322, -3.194388927973078, -0.15108566394621728, 0.05253760485984613, -1.3663368532289746, -3.1628907517415876, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06761102310516666, 0.3247122015295923, 1.9626202638327115, -0.15238822873657057, -2.153531210980476, -0.3469689344484492, 0.2315539474836294, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0124086287532215, -0.39396481303968484, 0.003547424423011781]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044888736022, 0.020473757910449652, 0.10082083055132941, 0.0, 0.16917031488139464, -0.017545516604757973, -0.8423712901758613, 4.585464562307299e-13, 0.8325880332226328, -0.0325249721059218, 0.04702499477982379, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10879337527147032, -0.08494960695638139, 1.0000005011052027, 7.377710022999099e-13, -0.5453110785409144, -0.018025281107697775, -0.5164974220810683, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20034747884565973, -0.1035491951487355, -0.00993718975413802]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181430335368, 0.1383746540950873, 0.6551860938037658, 0.0, -0.006670975387808682, -0.0865813985623583, -3.2336148389663792, -0.15108566394543793, 0.09126693484279993, -1.3679888723883138, -3.158985354312172, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07391614828210855, 0.3204913820097959, 2.0126202888879714, -0.1523882287353417, -2.1784636034234555, -0.34785074761133405, 0.20368800209272797, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0224266368471195, -0.40010418388757907, 0.0030973259999944884]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045155582176, 0.05263903334525896, 0.0982700491298277, 0.0, 0.18080319433806555, -0.015550219714701807, -0.7845182198660242, 1.55868540518478e-11, 0.774586599659076, -0.03304038318678298, 0.07810794858831407, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1261025035388378, -0.08441639039592783, 1.000000501105197, 2.457773304398776e-11, -0.4986478488595889, -0.01763626325769817, -0.5573189078180284, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20036016187796218, -0.12278741695788474, -0.009001968460345853]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17465186205932903, 0.14251602070874636, 0.6598925422847217, 0.0, 0.0016030793331443458, -0.08729477854882496, -3.266198096444189, -0.15108566394543785, 0.12334619314757589, -1.3695512368190794, -3.154453088644374, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07982756443999056, 0.3163277536121052, 2.0626203139432313, -0.15238822873534155, -2.2042448429181474, -0.34895761940997483, 0.17709901113784765, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.032443057977591, -0.40658000956213863, 0.002693140832566091]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880492921, 0.08282733227318091, 0.09412896961911733, 0.0, 0.16548109441906056, -0.014267599729333242, -0.651665149556187, 1.7500498659875483e-15, 0.6415851660955192, -0.03124728861531467, 0.09064531335596208, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11822832315764034, -0.08327256795381392, 1.0000005011051973, 2.8383014400603007e-15, -0.5156247898938344, -0.02213743597281518, -0.5317798190976062, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20032842260942893, -0.1295165134911911, -0.008083703348567946]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019098149044, 0.14795532408776924, 0.6644006998709707, 0.0, 0.008095903915653874, -0.08799923597904404, -3.288388700406509, -0.15108566394541567, 0.14502537977418914, -1.3709455261515713, -3.1501995021533333, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08431833677887605, 0.31225207180356557, 2.1126203389984903, -0.1523882287353194, -2.233520273561294, -0.3504622645705228, 0.15433358252726875, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.042456506313181, -0.4127667813847632, 0.0023398861434476845]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044888492819, 0.10878606758045761, 0.09016315172498066, 0.0, 0.1298564916501906, -0.014089148604381528, -0.4438120792464024, 4.432760145763378e-13, 0.4335837325322651, -0.0278857866498374, 0.08507172982080496, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08981544677770986, -0.08151363617079282, 1.0000005011051796, 4.4313343872401245e-13, -0.5855086128629368, -0.03009290321095999, -0.4553085722115776, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2002689667118008, -0.12373543645249158, -0.007065093782368125]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335195754928173, 0.15381470375484052, 0.6687619356737848, 0.0, 0.011801112131179157, -0.08876287277435958, -3.2964366508533414, -0.1510856639441679, 0.1525544947226688, -1.372414743598762, -3.1466749970209817, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08641114859130924, 0.30877731245587253, 2.1626203640537502, -0.15238822873338168, -2.266608007001135, -0.35360112425363094, 0.1355596659586425, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0524691736195775, -0.41803336723260776, 0.0025991644053059266]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045312453526, 0.1171875933414259, 0.08722471605628192, 0.0, 0.07410416431050565, -0.015272735906310873, -0.16095900893664555, 2.4955491240236406e-11, 0.15058229896959346, -0.02938434894381268, 0.07049010264702758, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.04185623624866385, -0.0694951869538606, 1.0000005011051951, 3.87543158782191e-11, -0.6617546687968169, -0.0627771936621623, -0.3754783313725254, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20025334612792828, -0.10533171695689127, 0.0051855652371648395]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1727020052837514, 0.15910990520794183, 0.6730436904063931, 0.0, 0.01209259324338477, -0.0896312812213857, -3.2918932762257014, -0.15108566394292017, 0.14778315393122798, -1.3742420597597076, -3.144056162404082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0854943869559228, 0.3064072814326638, 2.21262038910901, -0.15238822873145386, -2.3027641636516325, -0.35951741926289627, 0.12002811706564168, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0624831991850114, -0.4217429079490254, 0.004043300761445533]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999045310606465, 0.10590402906202619, 0.08563509465216454, 0.0, 0.005829622244112265, -0.017368168940522337, 0.09086749255279558, 2.4954726898402533e-11, -0.0954268158288161, -0.036546323218912664, 0.052376692337988966, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.01833523270772871, -0.04740062046417382, 1.0000005011051945, 3.855647347949171e-11, -0.7231231330099523, -0.11832590018530695, -0.31063097786001637, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.20028051130867994, -0.07419081432835296, 0.028882727122792128]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205303926846, 0.16312336010316328, 0.6773196311605819, 0.0, 0.008783371322250575, -0.09061576647714656, -3.2768571307026684, -0.15108566394289397, 0.13280317030149538, -1.376541255578462, -3.1424264675070432, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0813678154984397, 0.30533278267816627, 2.2626204141642705, -0.1523882287314128, -2.3417751578713353, -0.3685733362431661, 0.10734078415195589, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0724928138095362, -0.4232563577129999, 0.006892786772233863]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044889659032, 0.08026909790442899, 0.08551881508377562, 0.0, -0.0661844384226839, -0.019689705115217185, 0.30072291046066424, 5.240079563609482e-13, -0.2995996725946518, -0.04598391637508785, 0.032593897940776495, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08253142914966197, -0.021489975089950826, 1.0000005011052069, 8.207976542219979e-13, -0.7802198843940573, -0.18111833960539717, -0.2537466582737159, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2001922924904937, -0.030268995279489373, 0.05698972021576661]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17140210079523688, 0.16536182465487986, 0.6816685111025065, 0.0, 0.0020567013753800927, -0.09169630736544777, -3.253077009433474, -0.1510856639428935, 0.1093171303644079, -1.3792675060886193, -3.1417628975388854, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07417716494466262, 0.3055003045196396, 2.3126204392195304, -0.15238822873141206, -2.383588298044554, -0.3805404671278764, 0.09732319781768035, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.0824850270606277, -0.42258996612219607, 0.011011199443797946]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.012999044880631723, 0.04476929103433167, 0.08697759883849168, 0.0, -0.13453339893740962, -0.02161081776602424, 0.4756024253838869, 9.612942048149176e-15, -0.46972079874174955, -0.05452501020314621, 0.013271399363154142, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.14381301107554165, 0.003350436829466962, 1.0000005011051976, 1.5096879011949583e-14, -0.8362628034643698, -0.23934261769420637, -0.20035172668551063, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19984426502182973, 0.013327831816076247, 0.08236825343128162]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17205205301877607, 0.16597805396681378, 0.6861642962710915, 0.0, -0.006561983311071809, -0.09155121450957437, -3.2220529124181203, -0.1510856639417128, 0.07870047172017502, -1.380856228691764, -3.1413022629186855, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06767243529439816, 0.3056433195789616, 2.3588704642752227, -0.15613822873145153, -2.4290388101832234, -0.3982879836460423, 0.09372535806350568, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.092449911859682, -0.4203617084734724, 0.015847921693943487]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044470784137, 0.01232458623867859, 0.089915703371702, 0.0, -0.172373693729038, 0.0029018571174679944, 0.6204819403070778, 2.3614081654452418e-11, -0.6123331728846577, -0.031774452062897446, 0.009212692404001237, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.13009459300528914, 0.0028603011864401593, 0.9250005011138476, -0.07500000000078957, -0.9090102427733874, -0.354950330363317, -0.07195679509730563, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1992976959810858, 0.0445651529744743, 0.09673444500291083]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1727020052627469, 0.16483509539357782, 0.6910185546790882, 0.0, -0.015990952294651556, -0.09041189029842443, -3.185233634805837, -0.15108566394170986, 0.04227578579109506, -1.3814752736639797, -3.140326395507318, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06364309611568393, 0.305322022330296, 2.3976204893313477, -0.16738822873153122, -2.474376694287344, -0.42099077343716496, 0.10029726488805064, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1023838633031842, -0.41719153632183137, 0.021207949239884102]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879416596, -0.022859171464718893, 0.0970851681599346, 0.0, -0.18857937967159488, 0.02278648422299878, 0.7363855522456624, 5.865245912684931e-14, -0.7284937185815993, -0.012380899444311241, 0.019517348227347162, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.08058678357428453, -0.0064259449733132575, 0.7750005011224975, -0.22500000000159404, -0.906757682082405, -0.4540557958224535, 0.13143813649089936, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1986790288700425, 0.06340344303282006, 0.10720055091881234]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17335195775792278, 0.161950159038252, 0.6963155062539931, 0.0, -0.025491194441480652, -0.08873697501568004, -3.143803003667016, -0.15108566394242376, 0.001136042593015557, -1.3815751538398173, -3.1383886906313436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06242968942107733, 0.30412610489531816, 2.425120516279411, -0.18801322875407267, -2.5158519503678174, -0.4476022411171592, 0.11557367176515676, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1122924593252814, -0.413701070222391, 0.026916337110555653]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999049903517846, -0.05769872710651673, 0.10593903149809614, 0.0, -0.1900048429365819, 0.03349830565488787, 0.8286126227764188, -1.4278057764907079e-11, -0.8227948639615901, -0.0019976035167508926, 0.038754097519486864, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.024268133892132088, -0.02391834869955691, 0.5500005389612634, -0.41250000045082885, -0.8295051216094694, -0.5322293535998845, 0.3055281375421222, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.19817192044194573, 0.06980932198880781, 0.11416775741343098]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1740019100036723, 0.15757954132765753, 0.7020264352714224, 0.0, -0.03436451796271941, -0.08686124373677767, -3.1015110167607336, -0.1510856639440033, -0.04096876069478934, -1.3815074613106897, -3.1356306586780898, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06399777559145882, 0.3017863503198967, 2.438598205715731, -0.2164507287715678, -2.549714578447051, -0.47733155212195744, 0.13646331089789604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1221922513892382, -0.41051360896180855, 0.03278264048542176]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044914990392, -0.08741235421188942, 0.11421858034858519, 0.0, -0.1774664704247751, 0.037514625578047286, 0.8458397381256497, -3.1590924565482646e-11, -0.8420960657560979, 0.00135385058255385, 0.055160639065074665, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03136172340762981, -0.04679509150842894, 0.26955378872640356, -0.5687500003499022, -0.6772525615846705, -0.5945862200959646, 0.4177927826547855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1979958412791336, 0.06374922521164865, 0.11732606749732216]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17465186223889276, 0.15217779009200227, 0.7080645301015452, 0.0, -0.04190972713234761, -0.08499100456380453, -3.0621076432519163, -0.15108566405548138, -0.0802886573801937, -1.381444211849322, -3.132475788215136, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.06832190880551685, 0.2983788269683103, 2.4401762912569205, -0.2512007287240646, -2.572214580367877, -0.5094102594425518, 0.15975870935092604, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1321115499245507, -0.40825390906272213, 0.03862268339322451]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044704409362, -0.10803502471310493, 0.1207618966024565, 0.0, -0.15090418339256406, 0.03740478345946296, 0.7880674701763424, -2.22956136916465e-09, -0.7863979337080872, 0.0012649892273525654, 0.06309740925906894, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08648266428116053, -0.06815046703172797, 0.03156171082379433, -0.6949999990499367, -0.4500000384165206, -0.6415741464118883, 0.46590796906059984, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1983859707062493, 0.04519399798172852, 0.11680085815605497]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17530181448304938, 0.14634295930537133, 0.7143282920502034, 0.0, -0.04767542417300177, -0.08324706248963396, -3.029342883140532, -0.15108566405548787, -0.11307364746329827, -1.3814082355969337, -3.129141117566607, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.07560509253619208, 0.29427251145015076, 2.4313545435803565, -0.2910007286860957, -2.5797145822880476, -0.543008486057172, 0.18387218976289643, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1420894047205166, -0.4075478983837941, 0.04427090055689298]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044883132263, -0.11669661573261857, 0.1252752389731627, 0.0, -0.11531394081308308, 0.03487884148341147, 0.6552952022276859, -1.297887904950337e-13, -0.6556998016620915, 0.0007195250477670915, 0.06669341297059006, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1456636746135045, -0.0821263103631912, -0.17643495353127728, -0.7959999992406224, -0.1500000384034142, -0.6719645322924045, 0.4822696082394078, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1995570959193191, 0.014120213578560345, 0.11296434327336935]\n accelerations: []\n effort: []\n time_from_start: \n secs: 5\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1759517667270293, 0.14087616500899, 0.7207192700049359, 0.0, -0.05130059984749168, -0.08168098803432443, -3.006966736280589, -0.15108566405617405, -0.13557373182378663, -1.3809871155732667, -3.1256297962518595, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.08629524612955392, 0.28974991959045465, 2.4134506214256293, -0.33484072865550796, -2.5747145839025842, -0.57676709254455, 0.20874871215779198, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1518833814699454, -0.4087201747639428, 0.049477045622971234]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879598493, -0.10933588592762669, 0.12781955909464854, 0.0, -0.07250351348979833, 0.031321489106190405, 0.4475229371988535, -1.3723230004060078e-11, -0.4500016872097671, 0.008422400473339534, 0.07022642629494587, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.21380307186723668, -0.09045183719392172, -0.35807844309454434, -0.8767999993882443, 0.09999996770926722, -0.6751721297475612, 0.4975304478979107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1958795349885746, -0.02344552760297345, 0.10412290132156508]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17660171897112145, 0.1371032577843417, 0.7271252862803065, 0.0, -0.05202247430501683, -0.0803487408300558, -2.998729202612335, -0.1510856640564177, -0.14403891068743035, -1.3809205315903337, -3.121898840886219, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.10145746395477852, 0.284965226253537, 2.3872806863021534, -0.38191272863063047, -2.5592979186230647, -0.6086425360107686, 0.23512557828638722, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1608688115279318, -0.4114969829055082, 0.053616119994558245]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881843128, -0.07545814449296599, 0.12812032550741165, 0.0, -0.014437489150502879, 0.02664494408537261, 0.16475067336508165, -4.873332958880133e-12, -0.16930357727287448, 0.0013316796586589621, 0.07461910731280615, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.303244356504492, -0.09569386673835342, -0.5233987024695144, -0.9414399995024506, 0.3083333055903922, -0.6375088693243703, 0.5275373225719047, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17970860115972706, -0.05553616283130822, 0.08278148743174023]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17725167121510715, 0.13592737364801435, 0.7333770629482129, 0.0, -0.049468003962240686, -0.07926698365761067, -3.0031145909034858, -0.1510856640570343, -0.1399238074040001, -1.3818584670012264, -3.117869833464093, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.12164618385704976, 0.28017313325093046, 2.354344738214693, -0.4315703286105022, -2.5361992750932227, -0.6372767155407535, 0.26385179988899937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1686842500957415, -0.4156522710266188, 0.056098934597024135]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879713921, -0.023517682726546987, 0.1250355333581288, 0.0, 0.05108940685552287, 0.021635143448902737, -0.08770776582301631, -1.2331939099049948e-11, 0.08230206566860537, -0.018758708217856336, 0.0805801484425198, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4037743980454249, -0.09584186005213002, -0.6587189617492026, -0.993151999597435, 0.4619728705968341, -0.5726835905996981, 0.5745244320522428, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15630877135619414, -0.08310576242221249, 0.04965629204931778]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17790162345912786, 0.13769689362482335, 0.7392633232944548, 0.0, -0.04371842423540572, -0.07841277358030474, -3.0180190811444625, -0.15108566405703752, -0.12532870746021035, -1.3841065954728933, -3.113547267588901, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.14675051944424197, 0.27593732192142706, 2.3159959797447707, -0.4815703536657623, -2.5080429251008076, -0.6617620986593467, 0.2954239602154801, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1754018473332655, -0.4209487288336699, 0.05684630806134782]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880414092, 0.03539039953617991, 0.1177252069248379, 0.0, 0.1149915945366993, 0.017084201546118623, -0.2980898048195306, -6.445816007531437e-14, 0.2919019988757949, -0.0449625694333392, 0.0864513175038396, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5020867117438443, -0.0847162265900678, -0.7669751693984501, -1.0000005011052018, 0.5631269998483031, -0.48970766237186375, 0.6314432065296146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.13435194475047968, -0.10592915614102259, 0.014947469286473773]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17855157570323288, 0.1423494925849366, 0.7445973520771563, 0.0, -0.035109914849150214, -0.0777350048902328, -3.0416894896324176, -0.15108566405708915, -0.10196011125436293, -1.387718041016077, -3.108985778246317, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.1763296994073591, 0.2729225936182874, 2.2733169729693983, -0.5315703787211625, -2.4772889303575556, -0.681607983107226, 0.3302611997514402, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1812739922654643, -0.42716524600644146, 0.05603868894754244]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904488210067, 0.09305197920226482, 0.10668057565402905, 0.0, 0.17217018772511017, 0.013555373801438909, -0.4734081697591004, -1.0324159940635262e-12, 0.46737192411694856, -0.07222891086367339, 0.09122978685168114, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5915835992623424, -0.06029456606279274, -0.8535801355074448, -1.0000005011080058, 0.6150798948650421, -0.396917688957587, 0.6967447907192018, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11744289864397377, -0.12433034345543047, -0.016152382276107678]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.17920152794721542, 0.14958969662156446, 0.7492739091409042, 0.0, -0.024055180118689012, -0.07716654240149338, -3.072625799413134, -0.151085664057092, -0.07128199803723775, -1.3926214387484985, -3.1042318552042554, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2099806070937234, 0.2717567146424505, 2.2271737675490533, -0.5815704037765583, -2.4457527007007562, -0.6966307442407192, 0.3686513401802233, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1865984702089254, -0.4341167818967145, 0.05394697708368154]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044879650567, 0.14480408073255746, 0.09353114127495879, 0.0, 0.22109469460922404, 0.011369249774788256, -0.6187261956143226, -5.725003471137484e-14, 0.6135622643425034, -0.09806795464843032, 0.09507846084122676, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.6730181537272859, -0.02331757951673811, -0.922864108406897, -1.0000005011079167, 0.6307245931359834, -0.3004552226698653, 0.7678028085756611, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10648955886922284, -0.13903071780546067, -0.04183423727721784]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1798514801912255, 0.15902906566373926, 0.7532830800827253, 0.0, -0.010982790770819588, -0.07663287104534652, -3.1092312362341192, -0.15108566405710275, -0.034869412993651, -1.3987108332966032, -3.099270164945047, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.24722205061270702, 0.27298174906857214, 2.17825920321281, -0.6315704288321814, -2.414560436063433, -0.7068340582870763, 0.4103981923796951, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1916516473830405, -0.4416525452904486, 0.05083977875677709]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880201654, 0.18878738084349583, 0.0801834188364215, 0.0, 0.26144778695738846, 0.010673427122937238, -0.7321087364197056, -2.147618283924008e-13, 0.7282517008717351, -0.12178789096209228, 0.09923380518416146, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.7448288703796723, 0.024500688522433103, -0.978291286724871, -1.0000005011124615, 0.6238452927464607, -0.20406628092714274, 0.8349370439894361, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10106354348230442, -0.15071526787468248, -0.062143966538089096]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18050143243529132, 0.17027750381196718, 0.7566953026312148, 0.0, 0.003673181971210783, -0.07606326841160532, -3.149212726614908, -0.1510856640572582, 0.0050019223459289094, -1.4058864712950043, -3.0939796643121436, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.2874618301685328, 0.2769764097851253, 2.128259178157986, -0.6815704538877064, -2.3845785124451475, -0.7123880454785564, 0.45536910542929737, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.1966608891125206, -0.4496525542768724, 0.046942196070602446]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044881316648, 0.2249687629645586, 0.06824445096978903, 0.0, 0.2931194548406074, 0.011392052674824082, -0.7996298076157756, -3.109222367056565e-12, 0.7974267067915982, -0.14351275996802088, 0.10581001265806782, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8047955911165143, 0.0798932143310627, -1.0000005010964745, -1.0000005011105, 0.59963847236571, -0.11107974382960066, 0.899418260992045, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10018483458959851, -0.16000017972847572, -0.07795165372349284]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 350000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1811513846793199, 0.1829947553831078, 0.7596321401344559, 0.0, 0.0193960581976295, -0.07540808841377789, -3.188820270556529, -0.15108566405725962, 0.04458200798271322, -1.4140597521860399, -3.0879947017322937, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.3301418237284822, 0.28395807786954924, 2.07825915310273, -0.731570478943008, -2.3564988728709744, -0.7135729757885216, 0.5033458358685953, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.201800231774993, -0.45802312668937334, 0.04242334301339836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904488057193, 0.2543450314228124, 0.05873675006482335, 0.0, 0.31445752452837433, 0.013103599956548818, -0.7921508788324167, -2.8410509147961003e-14, 0.7916017127356862, -0.16346561782071173, 0.11969925159699979, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8535998711989885, 0.13963336168847892, -1.0000005011051212, -1.0000005011060302, 0.5615927914834594, -0.02369860619930428, 0.9595346087859589, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10278685324944778, -0.16741144825001897, -0.09037706114408176]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 400000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1818013369233457, 0.1969167425552046, 0.7622344074955548, 0.0, 0.035766371029200675, -0.07466006815323989, -3.22430386805902, -0.15108566405725996, 0.08012084391673846, -1.423146828808112, -3.0809864019469644, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.37479227488307315, 0.2939673995850642, 2.028259128047653, -0.7815705039982425, -2.330630970808783, -0.71078288328739, 0.55334583586862, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2072025858081896, -0.46669201841220415, 0.03739458730645981]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880516392, 0.2784397434419362, 0.052045347221978885, 0.0, 0.32740625663142353, 0.014960405210759897, -0.7096719500498208, -6.521892815837001e-15, 0.7107767186805047, -0.18174153244144117, 0.1401659957065854, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8930090230918182, 0.2001864343102987, -1.0000005011015374, -1.0000005011046906, 0.51735804124383, 0.05580185002263219, 1.0000000000004932, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10804708066393481, -0.17337783445661573, -0.10057511413877109]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 450000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18245128916722209, 0.21183086953647284, 0.7646396646831926, 0.0, 0.0524763495314135, -0.07384824097046697, -3.2519135191262616, -0.15108566405727045, 0.10786843015187739, -1.4329999739671921, -3.0727403927227694, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.42036563384484343, 0.3060577211974452, 1.981091308902783, -0.8315705290533837, -2.309521591134529, -0.7053035051402812, 0.6033458358686082, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2129372417230304, -0.47560523918677233, 0.03194623932790946]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044877527574, 0.2982825396253648, 0.04810514375275424, 0.0, 0.33419957004425654, 0.01623654365545846, -0.5521930213448287, -2.0986415905868122e-13, 0.5549517247027784, -0.19706290318160427, 0.1649201844838996, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.9114671792354057, 0.24180643224761939, -0.9433563828974036, -1.0000005011028246, 0.42218759348507884, 0.10958756294217628, 0.9999999999997661, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.11469311829681787, -0.17826441549136418, -0.10896695957100706]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 500000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18310124141125184, 0.22758443401029846, 0.7669658449566188, 0.0, 0.0694526525569448, -0.07300626366440441, -3.267899224622042, -0.15108566405728063, 0.12407476676796537, -1.4434851796994796, -3.063342494099787, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.46608008696175574, 0.31924305320879015, 1.9393510807323524, -0.8815705541086492, -2.2950692021910535, -0.6984067766938797, 0.653345835868597, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2190548450883782, -0.48472192459455565, 0.026141215310764566]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.012999044880595235, 0.3150712894765124, 0.04652360546852429, 0.0, 0.33952606051062584, 0.016839546121251135, -0.3197141099156157, -2.035544000805935e-13, 0.3241267323217597, -0.2097041146457514, 0.18795797245965243, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.9142890623382459, 0.2637066402268998, -0.8348045634086119, -1.0000005011053104, 0.2890477788695127, 0.13793456892802824, 0.999999999999774, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12235206730695616, -0.18233370815566632, -0.11610048034289783]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 550000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18375119364440953, 0.24401333951134288, 0.7693052654245798, 0.0, 0.08617309644124832, -0.07229498616478056, -3.276010984457859, -0.15108566418202574, 0.13248985369620608, -1.454569156417389, -3.0538739121415275, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.510055367209955, 0.33140436099869, 1.9067884434470768, -0.9315705791529495, -2.290629034657913, -0.6926463774923567, 0.7033458358217826, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2254721728141764, -0.4934249128701134, 0.020083289649944956]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01299904466315395, 0.32857811002088855, 0.046788409359219414, 0.0, 0.3344088776860703, 0.014225549992476934, -0.16223519671633924, -2.4949023335305603e-09, 0.1683017385648144, -0.22167953435818924, 0.1893716391651844, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.8795056049639868, 0.24322615579799664, -0.651252745705514, -1.0000005008860064, 0.08880335066280498, 0.11520798403046185, 0.9999999990637111, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1283465545159625, -0.17405976551115585, -0.1211585132163922]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 600000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18402162815265266, 0.2602693828641821, 0.7717298633609453, 0.0, 0.10115450876979075, -0.07203522220195482, -3.279998798606076, -0.15108566459251002, 0.13686364605532478, -1.4651628916581865, -3.0453359109430003, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5485496770021581, 0.3422195339595048, 1.882933189685166, -0.977820604186797, -2.2929087696225645, -0.6871353850333461, 0.7495958357293222, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2315636007595263, -0.5010997474676454, 0.014397462345241169]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.005408690164862766, 0.3251208670567842, 0.04849195872731077, 0.0, 0.29962824657084863, 0.0051952792565145775, -0.07975628296433276, -8.209685482198641e-09, 0.08747584718237404, -0.21187470481595078, 0.17076002397054307, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.7698861958440597, 0.21630345921629596, -0.47710507523821716, -0.9250005006769478, -0.045594699293030144, 0.11021984918021112, 0.9249999981507918, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.12182855890699898, -0.15349669195064058, -0.11371654609407572]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 650000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1839660606307883, 0.2756258749361232, 0.7741909908396435, 0.0, 0.1135571857514478, -0.07233743302177859, -3.2819936739435875, -0.1514275973541771, 0.1391869211947469, -1.4741217506511974, -3.0382482848786023, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.5795517802231369, 0.3516989381885014, 1.8659885815775683, -1.0165706292127579, -2.2982230069284384, -0.6813759421199589, 0.7883458360126491, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2367183624031646, -0.5073037980153204, 0.009699486358135126]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011113504372871359, 0.307129841438822, 0.049222549573963506, 0.0, 0.2480535396331409, -0.0060442163964752015, -0.03989750675023332, -0.0068386552333414485, 0.046465502788442255, -0.17917717986021847, 0.14175252128795865, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.6200420644195777, 0.1895880845799324, -0.33889216215195384, -0.7750005005192183, -0.10628474611748055, 0.11518885826774523, 0.7750000056665367, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.10309523287276692, -0.12408101095350153, -0.09395951974212087]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 700000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18383843214265974, 0.2895451019372624, 0.7765353888760588, 0.0, 0.1232384155537244, -0.07304605805138052, -3.2830066241068687, -0.15214830224717277, 0.1404721237640992, -1.4809836883612761, -3.0326736951669555, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6029328184120373, 0.3598480719742292, 1.8541160753355093, -1.044329174557169, -2.3040199154760015, -0.6754264003294851, 0.8182018784289025, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2407288886913488, -0.5120676292499943, 0.006144015859052955]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0025525697625713587, 0.278384540022784, 0.046887960728305145, 0.0, 0.19362459604553203, -0.014172500592038707, -0.0202590032656203, -0.014414097859913556, 0.025704051387046133, -0.13723875420157283, 0.11149179423293398, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.4676207637780063, 0.16298267571455632, -0.23745012484118194, -0.5551709068882206, -0.11593817095126543, 0.11899083580947649, 0.5971208483250672, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.08021052576368295, -0.09527662469347689, -0.07110940998164345]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 750000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18371275250461674, 0.30166417253169414, 0.778707428450579, 0.0, 0.13046412692613102, -0.07396215042611672, -3.2835290108569946, -0.15314328313358036, 0.141224485733525, -1.485810649274088, -3.028448463225928, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6196728042889283, 0.3666645189753038, 1.845777536782371, -1.0621855742121162, -2.3089676238541714, -0.6696029359195457, 0.8398843838531204, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2436664025974984, -0.5156064125956614, 0.003634735583843041]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002513592760859904, 0.24238141188863518, 0.04344079149040617, 0.0, 0.14451422744813247, -0.018321847494723917, -0.010447735002521106, -0.019899617728151787, 0.01504723938851575, -0.09653921825623427, 0.08450463882055195, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.33479971753782145, 0.13632894002149207, -0.16677077106276694, -0.3571279930989445, -0.09895416756339574, 0.11646928819878878, 0.4336501084843575, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.058750278122992355, -0.07077566691334293, -0.050185605504198275]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 800000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18360795704237837, 0.3117955034757106, 0.7805590516178845, 0.0, 0.13566924655406928, -0.07492436931637118, -3.283804705930197, -0.1542731884251925, 0.1416933224669047, -1.4889356157184528, -3.0253303662877746, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6311536643163875, 0.37219186194219256, 1.8398293678117, -1.072576236145607, -2.312586388148183, -0.6642308706198838, 0.8549224942300372, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2457141404754046, -0.5181772718134344, 0.0019715227747025676]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.002095909244767307, 0.2026266188803291, 0.037032463346109816, 0.0, 0.10410239255876516, -0.019244377805089453, -0.005513901464048984, -0.02259810583224268, 0.009376734667593868, -0.06249932888729732, 0.062361938763060544, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.22961720054918275, 0.11054685933777585, -0.11896337941342239, -0.2078132386698147, -0.07237528588023441, 0.10744130599323604, 0.30076220753833555, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.040954757558126095, -0.05141718435546044, -0.033264256182809454]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 850000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1835275900637907, 0.3199216904239934, 0.7820595888521741, 0.0, 0.1393116010646722, -0.07582729400770906, -3.283956305748153, -0.15541643137687242, 0.14200205638908517, -1.4907741427124896, -3.023075379756437, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6387375861914906, 0.37653751652333434, 1.8354854291778415, -1.0779206722204324, -2.3148821938996207, -0.6595308292893728, 0.8649520402851358, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.247079227374476, -0.5200165860545145, 0.0009367785374041974]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.001607339571752801, 0.16252373896565536, 0.030010744685790295, 0.0, 0.07284709021205835, -0.018058493826757456, -0.003031996359117991, -0.022864859033598316, 0.006174678443609671, -0.0367705398807391, 0.04509973062675102, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.15167843750206145, 0.08691309162283524, -0.08687877267716698, -0.1068887214965054, -0.04591611502875118, 0.09400082661022059, 0.200590921101974, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.027301737981424795, -0.036786284821601324, -0.020694884745967403]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 900000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1834695269057793, 0.3261709192390962, 0.7830887140845092, 0.0, 0.1417993681514609, -0.07661460819669193, -3.2840455076083397, -0.15648683692091078, 0.14221345575610359, -1.4917173782945368, -3.0214702922319665, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.643577612829679, 0.3798577488667566, 1.8322327949121966, -1.0801491810445512, -2.316085858530731, -0.6555991282023448, 0.8714044367514686, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2479503631261804, -0.5213187383230194, 0.0003379965770590836]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0011612631602278675, 0.12498457630205637, 0.02058250464670325, 0.0, 0.049755341735774394, -0.015746283779657304, -0.0017840372037389955, -0.021408110880767228, 0.004227987340368557, -0.01886471164094053, 0.03210175048940624, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.09680053276376781, 0.06640464686844516, -0.06505268531289751, -0.044570176482374144, -0.024073292622204465, 0.0786340217405597, 0.12904792932665443, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.017422715034088317, -0.026043045370098716, -0.011975639206902278]\n accelerations: []\n effort: []\n time_from_start: \n secs: 6\n nsecs: 950000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18342967008403432, 0.3307749417841999, 0.7836680385440494, 0.0, 0.143464478565032, -0.07726559258404059, -3.284103002854, -0.1574338414462765, 0.1423613541076298, -1.4920849997217835, -3.0203421693754815, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6465667230857132, 0.38233086629476615, 1.8297461990354478, -1.0806299380368327, -2.3164944115261896, -0.6524318442295359, 0.875410568911046, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2484814446036618, -0.5222341640065341, 2.3226286910602966e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0007971364348996466, 0.09208045090207409, 0.011586489190803706, 0.0, 0.03330220827142194, -0.013019687746973162, -0.001149904913208196, -0.01894009050731424, 0.002957967030523964, -0.007352428544935554, 0.02256245712970329, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.059782205120684224, 0.04946234856019059, -0.0497319175349762, -0.009615139845631678, -0.008171059909167767, 0.06334567945617779, 0.08012264319154756, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.010621629549628074, -0.01830851367029275, -0.006295405802969612]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 0\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1834036529740797, 0.334020963038557, 0.7839287782569468, 0.0, 0.1445608347215669, -0.07778203451555002, -3.2841437210751527, -0.15823561922046073, 0.1424656081204051, -1.4921146107533023, -3.0195570764009627, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6483549329266043, 0.38413301891198803, 1.827819714252681, -1.080251114683641, -2.31638709896749, -0.649960431899801, 0.8778072461642858, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.248789033240762, -0.5228750177384924, -0.00011821021719431629]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0005203421990924129, 0.06492042508714126, 0.005214794257947626, 0.0, 0.021927123130697723, -0.010328838630188686, -0.0008143644230532267, -0.016035555483684356, 0.002085080255506097, -0.0005922206303753058, 0.015701859490374875, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.035764196817821836, 0.036043052344438005, -0.03852969565533501, 0.007576467063832144, 0.002146251173997509, 0.049428246594698334, 0.047933545064798855, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0061517727420049816, -0.012817074639166965, -0.002828730082098385]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 50000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18338757973737052, 0.3362077350864409, 0.783996589935374, 0.0, 0.14527398297417238, -0.07817806417005463, -3.2841747320480144, -0.1588906287355294, 0.142538979033575, -1.4919695597240903, -3.0190146192566187, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6493926834672351, 0.3854222235984978, 1.8263191269562384, -1.0795433901192968, -2.315989273982879, -0.6480837745618142, 0.879183980517305, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.248956447401717, -0.5233228524512259, -0.00016173726153491207]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.0003214647341836887, 0.04373544095767847, 0.001356233568543082, 0.0, 0.014262965052109562, -0.007920593090092156, -0.0006202194572320772, -0.013100190301373122, 0.0014674182633978925, 0.002901020584240151, 0.010849142886876821, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.020755010812615503, 0.025784093730195752, -0.030011745928851086, 0.01415449128688585, 0.007956499692219251, 0.03753314675973629, 0.027534687060381233, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.003348283219099396, -0.008956694254668555, -0.0008705408868119155]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 100000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833782895592516, 0.3376123823199131, 0.7839534119960576, 0.0, 0.1457346006108684, -0.07847310357867418, -3.2841993335108457, -0.15940994113696103, 0.14259027395186555, -1.4917539593648532, -3.0186414388226552, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6499788946862083, 0.3863307194669248, 1.8251518663611956, -1.0787943652683476, -2.3154640632570134, -0.6466916488423651, 0.8799390677265504, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490403005675041, -0.5236359232832056, -0.0001556170402208232]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -0.00018580356237870348, 0.02809294466944282, -0.0008635587863289867, 0.0, 0.009212352733920792, -0.0059007881723911115, -0.0004920292566229249, -0.010386248028632828, 0.0010258983658110467, 0.004312007184741031, 0.00746360867926863, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01172422437946425, 0.018169917368539894, -0.02334521190085568, 0.014980497018981716, 0.010504214517312966, 0.027842514388983455, 0.015101744184909584, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0016770633157432893, -0.006261416639594555, 0.00012240442628177702]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 150000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833733874113519, 0.3384703147674239, 0.7838553234792257, 0.0, 0.1460318681804236, -0.0786874455201064, -3.284219117704473, -0.15981122054937766, 0.14262582340148963, -1.4915286111041632, -3.018385057003743, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6503039246654709, 0.3869635108615828, 1.8242495341121394, -1.0781386816338103, -2.314918252792128, -0.6456794614066003, 0.8803312371019563, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490772394179737, -0.5238552959244377, -0.00012870995865658087]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -9.804295799399034e-05, 0.017158648950216713, -0.001961770336637787, 0.0, 0.005945351391104147, -0.004286838828644372, -0.00039568387255076924, -0.008025588248332624, 0.0007109889924814144, 0.004506965213799725, 0.005127636378245034, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.006500599585253516, 0.012655827893160198, -0.018046644981122892, 0.013113672690743974, 0.010916209297704867, 0.020243748715297247, 0.00784338750811712, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0007387770093907497, -0.004387452824642356, 0.0005381416312848467]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 200000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833711610957024, 0.3389671531937855, 0.7837391159720067, 0.0, 0.1462249820954502, -0.07883976670638937, -3.2842349681914467, -0.1601144451605627, 0.1426502429520146, -1.491324900325474, -3.0182086093760616, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6504840334498744, 0.3874006196860896, 1.823558482743354, -1.07762221190819, -2.314413932083169, -0.644955979551123, 0.8805219546054766, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490898201849965, -0.5240096320436542, -9.688935398549742e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -4.452631299021533e-05, 0.009936768527232149, -0.0023241501443800735, 0.0, 0.003862278300532218, -0.0030464237256594365, -0.0003170097394683431, -0.006064492223700689, 0.0004883910104990615, 0.004074215573785519, 0.0035289525536256364, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0036021756880694317, 0.008742176490135431, -0.013821027375709909, 0.010329394512407762, 0.010086414179181746, 0.014469637109544724, 0.003814350070406129, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0002516153404558213, -0.0030867223843307557, 0.0006364120934216687]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 250000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1833704558340642, 0.33923964962580055, 0.7836271609957393, 0.0, 0.14635231577309238, -0.07894622022229704, -3.284247503543484, -0.16033933991921395, 0.14266688879345205, -1.4911553234162143, -3.0180866432926536, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6505871561088624, 0.3877010626879867, 1.8230350548685343, -1.0772444475641927, -2.313981080676113, -0.644446200846774, 0.8806077169351076, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.2490911748440372, -0.5241187943418757, -6.787095843431326e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -1.4105232763898814e-05, 0.005449928640301458, -0.0022390995253505517, 0.0, 0.0025466735528434873, -0.002129070318153288, -0.0002507070407423788, -0.004497895173025094, 0.00033291682874891086, 0.0033915381851977546, 0.002439321668162359, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0020624531797600702, 0.00600886003794276, -0.010468557496391633, 0.007555286879945618, 0.008657028141118767, 0.010195574086981393, 0.0017152465926219317, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 2.7093180815913254e-05, -0.002183245964429059, 0.000580367911023683]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 300000000\n - \n positions: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.18337053162700073, 0.33938210006866304, 0.7835302587172076, 0.0, 0.14643821416366967, -0.07901991799308448, -3.284257250147277, -0.1605037981030579, 0.1426781727592407, -1.4910215445663788, -3.018001800509428, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.6506510491866041, 0.387907221814751, 1.8226432168733302, -1.0769843791899039, -2.313628617116843, -0.644091141792743, 0.8806433328626165, 0.0, 0.0, 0.55, 0.55, 0.55, 0.55, 0.0, 0.0, 1.249088427523313, -0.5241964858753997, -4.4597254673075766e-05]\n velocities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]\n accelerations: []\n effort: []\n time_from_start: \n secs: 7\n nsecs: 350000000" - }, - "execution_count": 22, - "metadata": {}, - "output_type": "execute_result" + "name": "stderr", + "output_type": "stream", + "text": [ + "\n", + "KeyboardInterrupt\n", + "\n" + ] } ], "source": [ @@ -721,7 +746,7 @@ " name='MaxMal2')\n", "gs.add_default_end_motion_conditions()\n", "gs.motion_goals.allow_all_collisions()\n", - "gs.execute()\n", + "assert gs.execute().error.code == GiskardError.SUCCESS\n", "\n", "# EXERCISE:\n", "# 1.Comment the BaseArmWeightScaling and MaxManipulabilityLinWeight Goals to observe the resulting motions when the cost function is not augmented." diff --git a/src/giskardpy/goals/pointing.py b/src/giskardpy/goals/pointing.py index 71fbd27d2e..ede0357b9f 100644 --- a/src/giskardpy/goals/pointing.py +++ b/src/giskardpy/goals/pointing.py @@ -60,10 +60,6 @@ def __init__(self, self.tip_V_pointing_axis.vector.z = 1 root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) - # root_P_goal_point = symbol_manager.get_expr(f'god_map.motion_goal_manager.motion_goals[\'{str(self)}\']' - # f'.root_P_goal_point', - # input_type_hint=PointStamped, - # output_type_hint=cas.Point3) root_P_goal_point = cas.Point3(self.root_P_goal_point) root_P_goal_point.reference_frame = self.root tip_V_pointing_axis = cas.Vector3(self.tip_V_pointing_axis) From 294210d42ab70b7cd442ceaff4f4f203bfd8f9ac Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 12 Aug 2024 13:58:48 +0200 Subject: [PATCH 22/43] proposed monitor state feedback --- src/giskardpy/tree/behaviors/set_move_result.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/giskardpy/tree/behaviors/set_move_result.py b/src/giskardpy/tree/behaviors/set_move_result.py index 844b645767..b95fdc3d60 100644 --- a/src/giskardpy/tree/behaviors/set_move_result.py +++ b/src/giskardpy/tree/behaviors/set_move_result.py @@ -6,6 +6,7 @@ from giskardpy.tree.behaviors.plugin import GiskardBehavior from giskardpy.utils import logging from giskardpy.utils.decorators import record_time +from giskardpy.tree.behaviors.publish_feedback import giskard_state_to_execution_state class SetMoveResult(GiskardBehavior): @@ -39,5 +40,8 @@ def update(self): logging.loginfo(f'{self.context} succeeded.') else: logging.logwarn(f'{self.context} failed: {move_result.error.msg}.') + + move_result.execution_state = giskard_state_to_execution_state() + god_map.move_action_server.result_msg = move_result return Status.SUCCESS From 626e8ad2ab48c1df4760d896ed5552ff950cbef9 Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 12 Aug 2024 14:03:54 +0200 Subject: [PATCH 23/43] changed github workflow to test with new msgs --- .github/workflows/reusable_robot_ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/reusable_robot_ci.yml b/.github/workflows/reusable_robot_ci.yml index 4c5f82ecee..7b33757fba 100644 --- a/.github/workflows/reusable_robot_ci.yml +++ b/.github/workflows/reusable_robot_ci.yml @@ -93,7 +93,7 @@ jobs: with: path: 'ros_ws/src/giskard_msgs' repository: SemRoCo/giskard_msgs - ref: devel + ref: monitor_result_feedback - name: Checkout iai_maps uses: actions/checkout@v3 with: From fd30b4ca25dd0542dd570ce74a50937ea569aa27 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 13 Aug 2024 08:46:59 +0200 Subject: [PATCH 24/43] added get_end_motion_reason to the python interface --- .github/workflows/ci_standalone.yml | 1 + scripts/giskard_examples.ipynb | 36 +++++++---- .../python_interface/python_interface.py | 61 ++++++++++++++++++- test/test_integration_pr2.py | 49 +++++++++++++++ 4 files changed, 133 insertions(+), 14 deletions(-) diff --git a/.github/workflows/ci_standalone.yml b/.github/workflows/ci_standalone.yml index 567c2c98ee..81f18b05fa 100644 --- a/.github/workflows/ci_standalone.yml +++ b/.github/workflows/ci_standalone.yml @@ -56,6 +56,7 @@ jobs: test4: test/test_integration_pr2.py::TestManipulability::test_manip1 test5: test/test_integration_pr2.py::TestWeightScaling test6: test/test_integration_pr2.py::TestFeatureFunctions + test7: test/test_integration_pr2.py::TestEndMotionReason pr2_part2: needs: [ build_dependencies ] uses: ./.github/workflows/reusable_robot_ci.yml diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 021a67d225..45bab96833 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 7, + "execution_count": 2, "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", @@ -22,7 +22,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 3, "outputs": [], "source": [ "rospy.init_node('giskard_examples')" @@ -36,7 +36,7 @@ }, { "cell_type": "code", - "execution_count": 22, + "execution_count": 7, "outputs": [], "source": [ "# Launch the giskardpy PR2 standalone launch file before this\n", @@ -51,7 +51,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 5, "outputs": [], "source": [ "def reset_giskard():\n", @@ -512,8 +512,17 @@ }, { "cell_type": "code", - "execution_count": 27, - "outputs": [], + "execution_count": 10, + "outputs": [ + { + "data": { + "text/plain": "{'PointingAt': False, 'Sleep': False}" + }, + "execution_count": 10, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "reset_giskard()\n", "\n", @@ -582,9 +591,9 @@ " lower_limit=-0.05,\n", " upper_limit=0.05)\n", "\n", - "gs.motion_goals.add_pointing_at_line(root_link='map',\n", + "gs.motion_goals.add_pointing(root_link='map',\n", " tip_link=gripper_link,\n", - " goal_line=world_cyl_z_axis_feature,\n", + " goal_point=world_cylinder_center_feature,\n", " pointing_axis=robot_pointing_feature)\n", "mon_pointing = gs.monitors.add_pointing_at(root_link='map',\n", " tip_link=gripper_link,\n", @@ -601,10 +610,13 @@ " tip_normal=robot_gripper_z_axis_feature)\n", "\n", "gs.motion_goals.allow_all_collisions()\n", - "# gs.motion_goals.avoid_collision(min_distance=0.08, group1='obstacle')\n", - "gs.monitors.add_end_motion(f'{mon_dist} and {mon_height} and {mon_align}')\n", - "gs.monitors.add_cancel_motion(gs.monitors.add_local_minimum_reached(), error_message='local minimum reached while monitors are not satisfied')\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" + "gs.motion_goals.avoid_collision(min_distance=0.08, group1='obstacle')\n", + "gs.monitors.add_end_motion(f'{mon_dist} and {mon_height} and {mon_align} and {mon_pointing}')\n", + "gs.monitors.add_cancel_motion(gs.monitors.add_local_minimum_reached(),\n", + " error_message='local minimum reached while monitors are not satisfied')\n", + "result = gs.execute()\n", + "if result.error.code != GiskardError.SUCCESS:\n", + " gs.get_end_motion_reason(show_all=False)" ], "metadata": { "collapsed": false, diff --git a/src/giskardpy/python_interface/python_interface.py b/src/giskardpy/python_interface/python_interface.py index 06427aefa2..2a5862496e 100644 --- a/src/giskardpy/python_interface/python_interface.py +++ b/src/giskardpy/python_interface/python_interface.py @@ -39,6 +39,7 @@ from giskardpy.utils.utils import kwargs_to_json, get_all_classes_in_package from giskardpy.goals.feature_functions import AlignPerpendicular, HeightGoal, AngleGoal, DistanceGoal from giskardpy.monitors.feature_monitors import PerpendicularMonitor, AngleMonitor, HeightMonitor, DistanceMonitor +from giskard_msgs.msg import ExecutionState class WorldWrapper: @@ -1927,6 +1928,7 @@ def add_distance(self, class GiskardWrapper: last_feedback: MoveFeedback = None + last_execution_state: ExecutionState = None def __init__(self, node_name: str = 'giskard', avoid_name_conflict: bool = False): """ @@ -1987,7 +1989,9 @@ def execute(self, wait: bool = True) -> MoveResult: :param wait: this function blocks if wait=True :return: result from giskard """ - return self._send_action_goal(MoveGoal.EXECUTE, wait) + result = self._send_action_goal(MoveGoal.EXECUTE, wait) + self.last_execution_state = result.execution_state + return result def projection(self, wait: bool = True) -> MoveResult: """ @@ -1995,7 +1999,9 @@ def projection(self, wait: bool = True) -> MoveResult: :param wait: this function blocks if wait=True :return: result from Giskard """ - return self._send_action_goal(MoveGoal.PROJECTION, wait) + result = self._send_action_goal(MoveGoal.PROJECTION, wait) + self.last_execution_state = result.execution_state + return result def _send_action_goal(self, goal_type: int, wait: bool = True) -> Optional[MoveResult]: """ @@ -2043,3 +2049,54 @@ def get_result(self, timeout: rospy.Duration = rospy.Duration()) -> MoveResult: def _feedback_cb(self, msg: MoveFeedback): self.last_feedback = msg + + def get_end_motion_reason(self, move_result: MoveResult = None, show_all=False): + if not move_result and not self.last_execution_state: + raise Exception('No MoveResult available to analyze') + elif not move_result: + execution_state = self.last_execution_state + else: + execution_state = move_result.execution_state + + result = {} + + endMotion_idx = 0 + cancelMotion_idx = 0 + idx = 0 + for monitor in execution_state.monitors: + if monitor.monitor_class == 'CancelMotion': + cancelMotion_idx = idx + if monitor.monitor_class == 'EndMotion': + endMotion_idx = idx + idx += 1 + + if execution_state.monitor_state[endMotion_idx] == 1: + # the end motion was successful + return result + + if show_all: + for monitor, state in zip(execution_state.monitors, execution_state.monitor_state): + result[monitor.name] = state + return result + + def search_for_monitor_values_in_start_condition(start_condition: str): + res = [] + for monitor, state in zip(execution_state.monitors, execution_state.monitor_state): + if monitor.name in start_condition and state == 0: + res.append(monitor) + return res + + start_condition = execution_state.monitors[endMotion_idx].start_condition + false_monitors = search_for_monitor_values_in_start_condition(start_condition=start_condition) + idx = 0 + # repeatedly search for all inactive monitors in all start_conditions directly + # connected to the endMotion start_condition + while idx < len(false_monitors): + if false_monitors[idx].start_condition != '1.0': + false_monitors.extend(search_for_monitor_values_in_start_condition(false_monitors[idx].start_condition)) + idx += 1 + + for mon in false_monitors: + result[mon.name] = False + + return result diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 0978b14ecd..ab154c5be0 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -4739,6 +4739,55 @@ def test_feature_distance(self, zero_pose: PR2TestWrapper): zero_pose.monitors.add_end_motion(mon) zero_pose.execute() + +class TestEndMotionReason: + def test_get_end_motion_reason_simple(self, zero_pose: PR2TestWrapper): + goal_point = PointStamped() + goal_point.header.frame_id = 'map' + goal_point.point = Point(2, 2, 2) + controlled_point = PointStamped() + controlled_point.header.frame_id = zero_pose.r_tip + + mon_distance = zero_pose.monitors.add_distance(root_link='map', tip_link=zero_pose.r_tip, + reference_point=goal_point, + tip_point=controlled_point, lower_limit=0, upper_limit=0) + zero_pose.motion_goals.add_distance(root_link='base_link', tip_link=zero_pose.r_tip, reference_point=goal_point, + tip_point=controlled_point, lower_limit=0, upper_limit=0) + + mon_trajectory = zero_pose.monitors.add_max_trajectory_length(max_trajectory_length=1) + zero_pose.monitors.add_cancel_motion(mon_trajectory, error_message='stop motion') + zero_pose.monitors.add_end_motion(mon_distance) + result = zero_pose.execute(expected_error_code=GiskardError.MAX_TRAJECTORY_LENGTH, + add_local_minimum_reached=False) + reason = zero_pose.get_end_motion_reason(move_result=result) + assert len(reason) == 1 and list(reason.keys())[0] == 'M0 DistanceMonitor' + + def test_get_end_motion_reason_convoluted(self, zero_pose: PR2TestWrapper): + goal_point = PointStamped() + goal_point.header.frame_id = 'map' + goal_point.point = Point(2, 2, 2) + controlled_point = PointStamped() + controlled_point.header.frame_id = zero_pose.r_tip + + mon_sleep1 = zero_pose.monitors.add_sleep(10, name='sleep1') + mon_sleep2 = zero_pose.monitors.add_sleep(10, start_condition=mon_sleep1, name='sleep2') + mon_distance = zero_pose.monitors.add_distance(root_link='map', tip_link=zero_pose.r_tip, + reference_point=goal_point, + tip_point=controlled_point, lower_limit=0, upper_limit=0, + start_condition=mon_sleep2) + zero_pose.motion_goals.add_distance(root_link='base_link', tip_link=zero_pose.r_tip, reference_point=goal_point, + tip_point=controlled_point, lower_limit=0, upper_limit=0) + + mon_trajectory = zero_pose.monitors.add_max_trajectory_length(max_trajectory_length=1) + zero_pose.monitors.add_cancel_motion(mon_trajectory, error_message='stop motion') + zero_pose.monitors.add_end_motion(mon_distance) + result = zero_pose.execute(expected_error_code=GiskardError.MAX_TRAJECTORY_LENGTH, + add_local_minimum_reached=False) + reason = zero_pose.get_end_motion_reason(move_result=result) + print(reason) + assert len(reason) == 3 and list(reason.keys())[0] == 'M2 DistanceMonitor' \ + and list(reason.keys())[2] == 'M0 sleep1' and list(reason.keys())[1] == 'M1 sleep2' + # kernprof -lv py.test -s test/test_integration_pr2.py # time: [1-9][1-9]*.[1-9]* s # import pytest From 836941a74f5e54ae9f5ee626a7c598d19867a581 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 13 Aug 2024 13:43:53 +0200 Subject: [PATCH 25/43] environment manipulation and monitor sequences in notebook --- scripts/giskard_examples.ipynb | 327 ++++++++++++++++++++++++++++++++- 1 file changed, 322 insertions(+), 5 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 45bab96833..b982f0372f 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 2, + "execution_count": 8, "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", @@ -11,7 +11,8 @@ "from tf.transformations import quaternion_from_matrix, quaternion_about_axis\n", "from giskardpy.goals.weight_scaling_goals import MaxManipulabilityLinWeight, BaseArmWeightScaling\n", "from copy import deepcopy\n", - "from giskard_msgs.msg import WorldBody, CollisionEntry, WorldGoal, GiskardError" + "from giskard_msgs.msg import WorldBody, CollisionEntry, WorldGoal, GiskardError\n", + "import numpy as np" ], "metadata": { "collapsed": false, @@ -22,7 +23,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 15, "outputs": [], "source": [ "rospy.init_node('giskard_examples')" @@ -36,7 +37,7 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 18, "outputs": [], "source": [ "# Launch the giskardpy PR2 standalone launch file before this\n", @@ -616,7 +617,9 @@ " error_message='local minimum reached while monitors are not satisfied')\n", "result = gs.execute()\n", "if result.error.code != GiskardError.SUCCESS:\n", - " gs.get_end_motion_reason(show_all=False)" + " gs.get_end_motion_reason(show_all=False)\n", + "# EXERCISE:\n", + "# The output tells you which monitor of the end motion was not successful. Try changing/removing/adding constraint and monitors to realize a successful execution." ], "metadata": { "collapsed": false, @@ -769,6 +772,320 @@ "name": "#%%\n" } } + }, + { + "cell_type": "markdown", + "source": [ + "### Environment Manipulation\n", + "If an environment is modelled as articulated links in an URDF Giskard can load it and control the joint states of the environment when it is connected to links of the robot." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 27, + "outputs": [], + "source": [ + "reset_giskard()\n", + "\n", + "# load the kitchen environment\n", + "kitchen_pose = PoseStamped()\n", + "kitchen_pose.header.frame_id = 'map'\n", + "kitchen_pose.pose.orientation.w = 1\n", + "gs.world.add_urdf(name='iai_kitchen',\n", + " urdf=rospy.get_param('kitchen_description'),\n", + " pose=kitchen_pose)\n", + "\n", + "# Define poses and groups\n", + "p = PoseStamped()\n", + "p.header.frame_id = 'map'\n", + "p.pose.orientation.w = 1\n", + "p.pose.position.x = 0.5\n", + "p.pose.position.y = 0.2\n", + "\n", + "hand = 'r_gripper_tool_frame'\n", + "\n", + "goal_angle = np.pi / 4\n", + "handle_frame_id = 'sink_area_dish_washer_door_handle'\n", + "handle_name = 'sink_area_dish_washer_door_handle'\n", + "gs.world.register_group('dishwasher', root_link_name='sink_area_dish_washer_main',\n", + " root_link_group_name='iai_kitchen')\n", + "gs.world.register_group('handle', root_link_name=handle_name,\n", + " root_link_group_name='iai_kitchen')\n", + "\n", + "# grasp the dishwasher handle\n", + "bar_axis = Vector3Stamped()\n", + "bar_axis.header.frame_id = handle_frame_id\n", + "bar_axis.vector.y = 1\n", + "\n", + "bar_center = PointStamped()\n", + "bar_center.header.frame_id = handle_frame_id\n", + "\n", + "tip_grasp_axis = Vector3Stamped()\n", + "tip_grasp_axis.header.frame_id = hand\n", + "tip_grasp_axis.vector.z = 1\n", + "\n", + "gs.motion_goals.add_grasp_bar(root_link='map',\n", + " tip_link=hand,\n", + " tip_grasp_axis=tip_grasp_axis,\n", + " bar_center=bar_center,\n", + " bar_axis=bar_axis,\n", + " bar_length=.3)\n", + "\n", + "x_gripper = Vector3Stamped()\n", + "x_gripper.header.frame_id = hand\n", + "x_gripper.vector.x = 1\n", + "\n", + "x_goal = Vector3Stamped()\n", + "x_goal.header.frame_id = handle_frame_id\n", + "x_goal.vector.x = -1\n", + "gs.motion_goals.add_align_planes(tip_link=hand,\n", + " root_link='map',\n", + " tip_normal=x_gripper,\n", + " goal_normal=x_goal)\n", + "gs.add_default_end_motion_conditions()\n", + "gs.execute()\n", + "\n", + "# open the dishwasher\n", + "gs.motion_goals.add_open_container(tip_link=hand,\n", + " environment_link=handle_name,\n", + " goal_joint_state=goal_angle)\n", + "gs.motion_goals.allow_all_collisions()\n", + "gs.add_default_end_motion_conditions()\n", + "gs.execute()\n", + "\n", + "# close the dishwasher\n", + "gs.motion_goals.add_open_container(tip_link=hand,\n", + " environment_link=handle_name,\n", + " goal_joint_state=0)\n", + "gs.motion_goals.allow_all_collisions()\n", + "gs.add_default_end_motion_conditions()\n", + "assert gs.execute().error.code == GiskardError.SUCCESS" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "### Monitors and Giskard Task Graphs\n", + "Until now, we have seen different motion goals and monitors to observe the success of the specified Motion Goals, i.e. constraints.\n", + "Another way to specify a motion with giskard is to utilize monitors and the start-, to_hold- and end_condition's each motion goal and monitor offer.\n", + "Doing this a chain, or more specifically a graph (task graph in Giskard terms), of motion goals is build up.\n", + "The task graph will be executed as one continuous controller (no need to recompile a new one for each goal).\n", + "After execution a picture of the task graph and a Gant diagram visualizing the execution order of goals and monitors can be inspected.\n", + "Next we will see simple example to execute two cartesian poses after each other." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 30, + "outputs": [], + "source": [ + "reset_giskard()\n", + "\n", + "pose1 = PoseStamped()\n", + "pose1.header.frame_id = 'map'\n", + "pose1.pose.position.x = 1\n", + "pose1.pose.orientation.w = 1\n", + "\n", + "pose2 = PoseStamped()\n", + "pose2.header.frame_id = 'base_footprint'\n", + "pose2.pose.position.y = 1\n", + "pose2.pose.orientation.w = 1\n", + "\n", + "root_link = 'map'\n", + "tip_link = 'base_footprint'\n", + "\n", + "monitor1 = gs.monitors.add_cartesian_pose(name='pose1',\n", + " root_link=root_link,\n", + " tip_link=tip_link,\n", + " goal_pose=pose1)\n", + "\n", + "monitor2 = gs.monitors.add_cartesian_pose(name='pose2',\n", + " root_link=root_link,\n", + " tip_link=tip_link,\n", + " goal_pose=pose2,\n", + " absolute=True,\n", + " start_condition=monitor1)\n", + "end_monitor = gs.monitors.add_local_minimum_reached()\n", + "\n", + "gs.motion_goals.add_cartesian_pose(goal_pose=pose1,\n", + " name='g1',\n", + " root_link=root_link,\n", + " tip_link=tip_link,\n", + " end_condition=monitor1)\n", + "gs.motion_goals.add_cartesian_pose(goal_pose=pose2,\n", + " name='g2',\n", + " root_link=root_link,\n", + " tip_link=tip_link,\n", + " absolute=True,\n", + " start_condition=monitor1,\n", + " end_condition=f'{monitor2} and {end_monitor}')\n", + "gs.motion_goals.allow_all_collisions()\n", + "gs.monitors.add_end_motion(start_condition=' and '.join([end_monitor, monitor2]))\n", + "assert gs.execute().error.code == GiskardError.SUCCESS" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "**Visualize the Task Graph**" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 42, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "../tmp/task_graphs/goal_33.png\n" + ] + }, + { + "data": { + "image/png": "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\n", + "text/plain": "" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "from IPython.display import Image, display\n", + "import os\n", + "import glob\n", + "\n", + "folder_path = '../tmp/task_graphs'\n", + "files = glob.glob((os.path.join(folder_path, '*')))\n", + "latest_file = max(files, key=os.path.getmtime)\n", + "print(latest_file)\n", + "display(Image(filename=latest_file))" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "**Visualize the Gant diagramm**" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 41, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "../tmp/gantt_charts/goal_33.pdf\n" + ] + }, + { + "data": { + "text/plain": "", + "image/png": "iVBORw0KGgoAAAANSUhEUgAABgcAAAG8CAIAAAB1/+LFAACgFklEQVR4Ae3da6gVV77v/b36SU7gRIkkGNxkiVFsd1wh0fRxI602JkQTou7WgNh4QZBuId4JvpAY8PYcbXwh4j1gmoBEJZIQzVE3iYpbjhokgfayY5oc0UgUJWGvk0bzYmPIen7x3/3f46mqWbNq3tacs77zxXLUqFGjxvjUnNNV/zXGqI6enp5/4IUAAggggAACCCCAAAIIIIAAAgggUDCBXxSsv3QXAQQQQAABBBBAAAEEEEAAAQQQQOBnAaJCvA8QQAABBBBAAAEEEEAAAQQQQACBIgoQFSriVafPCCCAAAIIIIAAAggggAACCCCAAFEh3gMIIIAAAggggAACCCCAAAIIIIBAEQWIChXxqtNnBBBAAAEEEEAAAQQQQAABBBBAgKgQ7wEEEEAAAQQQQAABBBBAAAEEEECgiAJEhYp41ekzAggggAACCCCAAAIIIIAAAgggQFSI9wACCCCAAAIIIIAAAggggAACCCBQRAGiQkW86vQZAQQQQAABBBBAAAEEEEAAAQQQICrEewABBBBAAAEEEEAAAQQQQAABBBAoogBRoSJedfqMAAIIIIAAAggggAACCCCAAAIIEBXiPYAAAggggAACCCCAAAIIIIAAAggUUYCoUBGvOn1GAAEEEEAAAQQQQAABBBBAAAEEiArxHkAAAQQQQAABBBBAAAEEEEAAAQSKKEBUqIhXnT4jgAACCCCAAAIIIIAAAggggAACRIV4DyCAAAIIIIAAAggggAACCCCAAAJFFCAqVMSrTp8RQAABBBBAAAEEEEAAAQQQQAABokK8BxBAAAEEEEAAAQQQQAABBBBAAIEiChAVKuJVp88IIIAAAggggAACCCCAAAIIIIAAUSHeAwgggAACCCCAAAIIIIAAAggggEARBYgKFfGq02cEEEAAAQQQQAABBBBAAAEEEECAqBDvAQQQQAABBBBAAAEEEEAAAQQQQKCIAkSFinjV6TMCCCCAAAIIIIAAAggggAACCCBAVIj3AAIIIIAAAggggAACCCCAAAIIIFBEAaJCRbzq9BkBBBBAAAEEEEAAAQQQQAABBBAgKsR7AAEEEEAAAQQQQAABBBBAAAEEECiiAFGhIl51+owAAggggAACCCCAAAIIIIAAAggQFeI9gAACCCCAAAIIIIAAAggggAACCBRR4IE263RHR0eb9YjuIIAAAggggAACCCCAAAIu0NPT42kSCCCAQJUCjBWqEpDDEUAAAQQQQAABBBBAAAEEEEAAgZYUaLexQnYRCJ9nfDMeOnRIJadOnZqxfMGLGRdiGd8GcGWE8mJ8Hp0iSwKuLEpeBi6nyJKAK4uSl4HLKbIk4Mqi5GWMS5v8smomzIrw9wYJBBCooQBjhWqISVUIIIAAAggggAACCCCAAAIIIIBAywgQFWqZS0VDEUAAAQQQQAABBBBAAAEEEEAAgRoKEBWqISZVIYAAAggggAACCCCAAAIIIIAAAi0jQFSoZS4VDUUAAQQQQAABBBBAAAEEEEAAAQRqKEBUqIaYVIUAAggggAACCCCAAAIIIIAAAgi0jABRoZa5VDQUAQQQQAABBBBAAAEEEEAAAQQQqKEAUaEaYlIVAggggAACCCCAAAIIIIAAAggg0DICRIVa5lLRUAQQQAABBBBAAAEEEEAAAQQQQKCGAkSFaohJVQgggAACCCCAAAIIIIAAAggggEDLCBAVaplLRUMRQAABBBBAAAEEEEAAAQQQQACBGgoQFaohJlUhgAACCCCAAAIIIIAAAggggAACLSNAVKhlLhUNRQABBBBAAAEEEEAAAQQQQAABBGooQFSohphUhQACCCCAAAIIIIAAAggggAACCLSMAFGhlrlUNBQBBBBAAAEEEEAAAQQQQAABBBCooQBRoRpiUhUCCCCAAAIIIIAAAggggAACCCDQMgJEhVrmUtFQBBBAAAEEEEAAAQQQQAABBBBAoIYCRIVqiElVCCCAAAIIIIAAAggggAACCCCAQMsIEBVqmUtFQxFAAAEEEEAAAQQQQKBQAj/99FOh+ktnEUCg8QIPNP6UnBEBBBBAAAEEEEAAAQQQQKCswP/z//4/ZctQAAEEEKhGgKhQNXociwACCCCAAAIIIIAAAgggkE/ghx9++O6773RMZ2fnAw+0wD1pyzU43/WgdLEFWuATWOwLRO8RQAABBBBAAAEEEEAAgdoIfP3112fPni1b16BBg8aOHVu2WMUFDh06NHv2bB1+7dq1J5980uqJtG3WrFkp9e/bt8/3jhkzxivxzNomEhtc21NQGwK9JUBUqLfkOS8CCCCAAAIIIIAAAggg0FABhYQsHJN+1pkzZ9Y1KpR49kjbUmI9ly5dCnuxd+/eKqNCZ86c2bFjh1q1ZcuW/v37JzaPTATaVYDVptv1ytIvBBBAAAEEEEAAAQQQQKBVBfbs2VOq6R9++GGpXZXlX79+ff/9l2aKVVYDRyHQugKMFWrda0fLEUAAAQQQQAABBBBAAIFKBNauXTt37txSRz788MOldjUsf9euXStXroyvOvTjjz+uXr26Yc2wE02dOlWT3ZTWQkgNPjWnQ6DeAu0ZFeroqLdbm9R/8ODPHYEr4+U0LsTgyiiQtxifx1xicMGVSyBXYd5dcOUSyFWYd1cFXDqk0L+srslllqPw0KFDq5x1leNkOYtOmDDh+PHjt2/fPnfuXHwimzKtPiuWs+4KiytM1gyRsgpbz2EIpAq0Z1QotcvsRAABBBBAAAEEEEAAAQQQyCQQefyWNs+fP3/ixAkdPGrUqPHjx6eHS/Sssc8+++zjjz8ePXr0M888M3z48Pjwn0g75s2b9+///u+KCmmtn3hUaM2aNSr/7LPPqpiCR5Fjw0019erVq1qE6PDhw1OmTNHZhwwZEmmtRh7duHHjypUrduDly5fDGvwRaRGEsIyls5zLS4bPX8vrGT81OQhUKUBUqEpADkcAAQQQQAABBBBAAAEE2lYgfPyWgiaTJ0+OdPXIkSOTJk2KZNrmunXr4rO9Tp8+nVg4zHzzzTeXLFmipX52794dxnEUT7FI0Pz588Py8bQeUhauSK2qrEyktQoJDR482A+P9M4fkRYixMdYZTyXnSWsKq+nt5MEAjUUYLXpGmJSFQIIIIAAAggggAACCCDQngIKxHjQZMCAAd5JZeqh8r7piYkTJ4YhIU34sl3jxo175513vFhi4ne/+53lK4YSFnjvvfdsUwOFwvxIetmyZWFISAOLvIBaq72+WX2i4nPl9ay+qdSAQKIAUaFEFjIRQAABBBBAAAEEEEAAAQT+S0CDdBQM2rZt2927d2/duqVxNHqAve3WstD/Ve5+Ss969+ldWtlahxw7dswP8V2Ro3xTj4e3KNLGjRs9U4n169frp3aFA4jCAkrr1Fu3brVMtVAnvXDhgp9a+dqraWVWQAN/enp69Gx721QxbforPizIivnPXOfyoyyRyzNyLJsI1FCAqFANMakKAQQQQAABBBBAAAEEEGgBAQ2l6Sj9Shz7o15dvHhx8eLFFpFRxMQfHq/5WVqgJ+z2woULbVNxllWrVvkhmmzlIZiwfDz9+uuvK1Nn9MYolKPFhpRpSwvFD7EcP7Umi+l0FtnRT6WVY2XmzJlT6vBc+VWeK7tnrlZRGIFcAu25rtDBg/+/cYa5RApYGK68Fx2xXGJwwZVLIFdh3l1w5RLIVZh3F1y5BHIV5t2Vi0uFiy120Lmm/cM0SyuY45lhQiNcws2apzUPS0N4wmq1brSG7djAHy3Q4yNrFMdRvEMlNVTHM/1APeXd0ymJl156yfYq9qS4ktJvv/225Wjh6lIH+qnV2vhqR8pRvtqml0rG21aq2sT8Ks+V3TPx7GQiUCuB9owK1UqHehBAAAEEEEAAAQQQQACBlhDQ06xS5lVFuqB4jR7LFcn0zUj0x/ITF3j2B4HduXPHD79586alE0+hRursvvyzHxVJKOSkqWdamWjXrl02Q83mhSkz5Slm3owVK1ZEKrRN5duSQ14ysViWTK+hsnNl98zSGMogULFAe0aFpk3LFH6uWK1tDrQ/vMCV8YL636kQyyIGVxalsAyfx1CjbBquskRhAbhCjbJpuMoShQXgCjXKpuEqSxQWMC7lFPpXrzUJw4JqMiZI8ZpZs2aF4GXTiSGeMWPG2IGa3qVHv1v6+vXrlvCcSOVPPfVUJCdx89VXX1VUSLPGzp0799e//tXKKDOxsGX6gkH9+vVLLOb5YYMTS5bNrPJc2T3LtoQCCFQj0J5RoWpEOBYBBBBAAAEEEEAAAQQQQKB6gb59+yZWMnTo0MT8SKaCSjbha8eOHXomvfZqs1SkKXJsV1dXJMc2S+UnFs6YWarOUvkZq6UYAo0RYLXpxjhzFgQQQAABBBBAAAEEEECgWAI+lSzSbY39ieSU2rRpVppuZqsXlZqrFT/87Nmz8UzllMpPLJwxs1SdpfIzVksxBBojQFSoMc6cBQEEEEAAAQQQQAABBBAohIAP5/GpZJFu28CfSGbiptYtCvPLrlTtp+7u7g4P9LTn+9w335U30chz5W0b5RHILtBcUSEtkBZ5omH2nlASAQQQQAABBBBAAAEEEECg1wV84tjGjRvjjdFNX9mlpv0oLU2tx5zZptaoLructp969+7dXkmYWL9+fbgZSfsC0pH8xM0qz5VYJ5kINF6g0VGhffdfZ86cCbuqSJByJk6c2KdPn4EDB6oIsaHQhzQCCCCAAAIIIIAAAggg0CoCeuK7IjhqrR4A70syW+N1o2cPFMvel4MHD167/yoV6AmrCk+t+8pwl9LK0drVSqh54WPpBw0aZCVPnToVOSRls7JzpVTILgR6RaChq00rKmxPATxy5EjY27feemvJkiWWo0+pyixfvvzTTz8NP6hh+bLpnp6yRSjws8ChQz//hOtnhQwv41JBxDJo/e3dBVcWKyvD5zG7lUrCBVcugVyFeXfBlUsgV2HeXRVw6ZAi/+rVsTaXWY7Chw8fTi+d9wllkdo2bNhgA4K0PrRCMNrs7Ow8cOCAbvQsLhMpn7Kp8UFlhwiFh/updV+pwUo7d+4cO3asRiEsXLhQUSorqTLhIcOGDbNNG0k0fvx4GwekNj/wQNotcwXnCs9LGoFmEEh7i9e8fefPn7c69THzyhUq8pCQvjKUr8+qvikUQo4Hd/0oEggggAACCCCAAAIIIIAAApUJKGRjUZtSh1cZFdIf+NeuXavnyqv+yLkGDBgwY8aMrVu3ljp1lfk69bZt2+weU7eW48aNi1SovZHxB/3791foSu3UfajfnOooDVGKlIxUVcG5IjWwiUCvCzR0BpktNqbQTxjr9UF6+nBeuP/S14dc9JnMvghZrzvSAAQQQAABBBBAAAEEEEAAARdYtWpVZI6IdulmUJGa0aNHe7F6JBYvXqyAjsJPkcqVo3ztjeRrc8+ePXv37o0fEi8ZyangXJEa2ESgdwUaOlbI1nt/+umnwz6/++67tvnaa69ZYsGCBRZU1jAiRW3DwqQRQAABBBBAAAEEEEAAAQQqE9AzvBQWyXWsH6LpVPEDlWkVJt64TZo0qaen5+uvv9Yz2vXEriFDhtj4gMQ6PTOxqvip08trFM+tW7c0zkDDf7S2UXj2eFXK0UwxDY+yEVK6D7UBCt5lP5fnhJXkOld6Veme4UlJI1ArgYZGhfRdEGm3FhuzgYtLly71GZv+LaDy6QP2IrWxiQACCCCAAAIIIIAAAgggUErg5xV6Hn641N7E/PRDdBNX9pZNBSJlEutMzExskmVmKa9bS738EfIptYW74jXHc8Lyls54rvSqsnjGT00OAtUINHQG2ZgxY9TWkydPeovPnTtn6cgYQltgyIuRQAABBBBAAAEEEEAAAQQQQAABBBCorUBDxwo9+uijar2G8GlInkKkSmsVeuuPHksfdswWh/cHBIa7SCOAAAIIIIAAAggggAACRRD4zzf+87/9t/9mPe1Y01GELtNHBBBosEBDo0I2Vkg9VEIPCNTi07byvEYGabid99wXmX7iiSc8kwQCCCCAAAIIIIAAAgggUCgBDwkVqtd0FgEEGinQ0KiQZpPaA/8iDwhcsWJF2Odjx47ZZhgqCguQRgABBBBAAAEEEEAAAQQQQAABBBCoUqCh6wqprfbAP182SE/+03PobaV378nGjRuVVhmbZeb5JBBAAAEEEEAAAQQQQAABBBBAAAEEaiXQ0LFCarQ/8O/MmTPaHDt2bKQnmj6mR9frNWXKlMguNhFAAAEEEEAAAQQQQAABBBBAAAEEaiXQ0KjQ119/bQ+nnzp1ajweZF3SrLF9+/bVqnvUgwACCCCAAAIIIIAAAggggAACCCCQKNDQqNDKlSv379+vdvT09CS2hkwEEEAAAQQQQAABBBBAAAEEEEAAgcYINDQqpEePKSo0YcKExvSNsyCAAAIIIJBFQCvcZSnWumVGjhypxrd9N2t1geDKJQkXXLkEchW2d5cOabmvr1/N/FWunlIYAQQQ6EWBhq42/dxzz6mrx48f11SyXuwzp0YAAQQQQAABBBBAAAEEEEAAAQQQaOhYIY/360lkq1atQh8BBBBAAAEEEEAAAQQQQACBCgT0nKJjx47pwMOHD2t12tGjRw8aNEg/9YCjCmrjEAQKK9DQD4yeNK/xn6vvvxYsWKCPbmHd6TgCCCCAAAIIIIAAAggggEAFAtu3b9+9e/fFixfjxw4YMOBPf/rTpEmT4rvIQQCBRIGGRoV+/PHHuXPn/u///b81iezxxx9XhOjVV1/t27dvYsuU2dnZSaC3FA75CCCAAAIIIIAAAggggEABBZYsWRL2WpGg27dvW44SkydP3rt376xZs8IypBFAoJRAQ6NCN27cGDx4sDfFBg35Zjxx7dq1J598Mp5PDgIIIIAAAggggAACCCCAQJEFNMhAYw5sJIHGH5w7d27Hjh32zOvZs2c/c/9VZB/6jkBGgYZGhTK2iWIIIIAAAggggAACCCCAAAIIJAocOXJk/PjxWp/E92qKydj7r5MnT9q4oVOnTiku5AVIIIBAKYGGRoW0kJDG8pVqSjyfhYfiJuQggAACCCCAAAIIIIAAApUJ/PDDD1qkWcfaEBulv/rqqxMnTjz66KN6YLSeDhSGWiKn0LFXr169dOmSVneeMmWKYi5DhgxJKa8HT589e7a7u1s/x4wZo1NoNeiUU2i8jyaXXL58+fPPP9epR40a1dXVlTh3JGXZoE2bNmmgkA7XSRcvXhzpApsIIBAXaGhUSF8ZTO+MXwNyEEAAAQQQQAABBBBAAIEGCBw6dMiCJlqsQw+G1poe4Um1QM8nn3ySOMRm3759dqCVt4laSmvYTjxGY+vJehkVC9OJi/4ohDR16tT4AtIzZ85UO7OvNqvwk7Xwiy++sAQ/EUAgXeAX6bvZiwACCCCAAAIIIIAAAggg0GYC8+fP95DQs88+a73T3Culz5w5E+nssmXLwpCQl1cxLe2svZHyBw4c8DCQIk2K7OgVHhUpr5CT1p/1kJBK6igro3oGDhyoYUqRQ0ptaqiR7Xr++edLlSEfAQRCAaJCoQZpBBBAAAEEEEAAAQQQQKD9BfRUaHVSCzbfvXv3woULp0+f9qjN9OnTNdjHCRQk2rp1q20quKNBRiqvn0pbpvZqWpmXV2Ljxo36qQpV+a1btxT00UtHaVNjizSPLCysWWwWclIkSO1RbEgldZSaZKdQrErzwsJDUtKbN2+2vS+//HJKMXYhgIALNHQGmZ/VEholeOfOHf8GscF+iRNHIweyiQACCCCAAAIIIIAAAgggUI3At99+6wu5aqVmxWI06kchHkVhNNjHl/5YuHChnSWcLKa7NgV65syZo7FC2quEDrdiiiLZqJ+dO3dGVh3SZny6mQ81UujHT6qqwtWjNaxpwYIF3lo7Ufzn9u3bLdqlgNRLL70UL0AOAgjEBTp6enriufXOUSRIXxw+RDA8neLBGzZsqDg21NHRodoOHjwY1kkaAQQQQAABBBBAAAEEEGhpgWnTpqW3P8udnUI5NjBHt11KRyrURK0+ffooU1EVi/LoD/ma2xXmRA4ZMWKE3dZp9JDdxCkqNG7cOBVLXD8ocrgGCj3++OOWqZFEkSiS8tetW2cz3cKYVKQS29Q9pg938sYkliQTAQRCgV6YQaZgsD6uiSEhtUwTR/W9oyhv2ErSCCCAAAIIIIAAAggggAACKQLZF99RJYsWLYpXpaDMhAkTlO83a5rbYcVWrFgRL68cz/eSGuNjqwIp/KRbPwWJwvlokUq8zZo7Fg8JqfDcuXPtkO+//z5ybLip6JIPDtq2bVvFgwzCOkkjUBCBRs8gO3r0qM9KVWxIXyL9+vXTEwftmYXr16/XeEXRL1myRA87rPjDrOXrC3L9quymnkGgGuDKyGhciMGVUSBvMT6PucRqy6XfRHOdveUK6zHAavP58+dbruW90mC4crHDBVcugVyF7d2lQ1ru6+tXM3+Vq6d5C2cZE1S2zieeeCKxjM/SUrxGYRpf7kN3bYnlPV8l/eFlmu1lA3x062d3fxqapMki48ePj4R+dBto1aq8HZJ4FmUePnw4nF8WFlNISLeWdiOp/9N5IH2IQxqBsgINHSukbxabd6pmaQSgBiXqg62ZpYr+KKFPrxYV0zhDa/Svf/3rsq2nAAIIIIAAAggggAACCCCAQK0EPCqkUEtYp/6QH256OjF/1apVuq3z+VwqrBkhuhPU9DRNCkkZOuTVZk9EQkI6dfZjKYkAAhJo6Fihq1evGrpCxfFlxmyXwkNasl5DFhXrtfg01wkBBBBAAAEEEEAAAQQQQKABAh4M6uzsDE+nQT2JMzl8sE9YWGnd1uml2o4dO3bu3DkbMaR8TQp57rnnNMssUl7TvjRZJJIZbkYGGdkuQkIhEWkEKhNo6FghH3+o9aRTmqvF6m2vR5FSCrMLAQQQQAABBBBAAAEEEEAgl8Dly5cTy3tU6IEHfh5A4JPCuru7E8t7vj1ROlJGI48UG9qyZcu9e/cU97G9a9as8WLhUYo6pbx8EJMfS0jIKUggUI1AQ6NCmguqtmokoT7tKY32yLFHkVIKswsBBBBAAAEEEEAAAQQQQCCXwLvvvhsvryeO2ZPdbc1pFejbt68V2717d7y8crQybGJ+JFMxJi0YYnPKdApfZNpjPao/18wyQkIRYTYRqFigoVEhGxOo2WH6uklpsZapt70emU4pzC4EEEAAAQQQQAABBBBAAIFcAlroJ/I3eAVlNm/ebJXMmzfPEvpzvlb/UFo3cfEn2SvH1nhWGf/Dv0d8SrVHTyh76KGHbK/mhXn9KRNKVGcYMwpDQkuXLmUtoVLU5COQRaChUSGP8qxcuTKlcQsXLrS99kTDlJLsQgABBBBAAAEEEEAAAQQQqEBAI3c0vUt/sFfARfGdgQMH2uo/lu8VerBGT5ofMWKE/QlfP5VWjhXzMtrUc0K1SxX6ZDRlKr1u3TqFlpTetGmTTU+zYzVKyO779Awya4/l66captCVHm+vZapv3Ljh+WqhRaOU88tf/lLnSnx5eRIIIJAi8PNk0Ya9hgwZYudSZFoPJkxccFqfZ/uy0FeDjydsWAs5EQIIIIAAAggggAACCCDQ9gJ6gruiMLov0yvsrO7CIpPLNAhISwJplWgV053auHHjwvJKa68PFLJdKuYBI0Vw7P7Odqn+GTNmhDVouND7778/ffp0BXq8PSrmcZ+wsKXDXdaweBnlKMaUmE8mAgiEAg0dK6QPvD94Xg8mtBDy0aNHFZ9WMEgPKQzjzZ9++mnYUNIIIIAAAggggAACCCCAAAI1EZg7d+7p06cjVVkEx2d4+F4tCXTt2jVFajzHEspRvvaG+YMGDVI9nhOGhDRZTHd54UAhK6aFZb/55hvNBfOjwriPalPgKfJMNC9JAgEEqhRo6FghtVXxWn8wYRhCjnQjHm+OFGATAQQQQAABBBBAAAEEEECgYgHFYnp6ejS367PPPnvkkUeGDRuWMldDo4Fu3bqlworXaFaXIkeaCJL4tHhVe+HCBa0EpMI3b968fv26WqhnjalwSv0KFelRZXppxIAd1a9fv66ursSjFIqquNcciAACEYFGR4V0en3UNWhQiweFYWNvluLHmpUaGYLoe0kggAACCCCAAAIIIIAAAgjUSkCRmsSVPRLrV2G94oOJ4oUVzdFLt3X+gOl4mcQcHVL2KBVIPJZMBBCoQKAXokJqpcWPFQa+c+eOL32vLxc9+JBPeAVXkUMQQAABBBBAAAEEEEAAAQQQQACBvAK9ExWyVloAKEukOW+vKI8AAggggEB2AS23mb1wK5bU42DU7LbvZq0uDVy5JOGCK5dArsL27tIhfH3lcqMwAgggkEugoVEhPVnQHiiYPiDIi2lFsfhSZLm6R2EEEEAAAQQQQAABBBBAAAEEEEAAgUSBhkaFFBIaPHiw2qFVzRJbY5leTKuIpcePUiphFwIIIIAAAggggAACCCCAAAIIIIBAikBDn0yf0g52IYAAAggggAACCCCAAAII1FVAj4TWX+j14q/vdXWmcgRaSKAZo0JagtoEtb59C1HSVAQQQAABBBBAAAEEEEAAAQQQQKCFBJoxKnTq1CkT1LMMW4iSpiKAAAIIIIAAAggggAACCCCAAAItJFD3dYW+++67H374wUQuX75sCT2TPtFIo4QUElq/fr32DhgwILEMmQgggAACCCCAAAIIIIAAAggggAAC1Qt0aE5p9bWk1KCZq/v3708pUGrX3r17dWypvaXyOzo6tGvNmjWlCpAfCowcOVKb58+fDzNJlxIwLu1FrBRRmA9XqJElzecxi5KXgcspsiTgyqLkZeByiiwJuLIoeRm4nCJLwrhUssi/ev1q5q/c6rf/9FtL1/sOzs9IAgEEiiBQ97FClSHOnDlzxowZlR3LUQgggAACCCCAAAIIIIAAAu0noGkomoyifnV2dj7wQI1vZmtbeW1ra79L2bQ9aoYL1+A21PiDFL+0ixYtmjJliuVfuXJl9erVSmscULyk5QwaNGjYsGGsM13Kh3wEEEAAAQQQQAABBBBAoDIBLeVx9uxZHTtmzJhWfAzZoUOHZs+erfZfu3YtbL/3y1jSJ53s27fP9UKHUpV74VyJ2taW69SNLxzxtwbIVonwMjW+YRWcsRkuXIPbUPeo0Nj7L7sYeq9YVCj9U1rBleMQBBBAAAEEEEAAAQQQQACBdAGFhCyqor/Tt9ztekrXvF9WJoz1RI66dOmSCVh+mzlEOtuwzYh/5LyaCbRhw4Z2er9FOtjqmw19BplGAOlTp1erq9F+BBBAAAEEEEAAAQQQQACB5hTYs2dPqYZ9+OGHpXaRXycBLTQ8ePDgcIhWnU5EtZUJNDQqpCfNa5QQA4Uqu1QchQACCCCAAAIIIIAAAgggUFZg165dP/74Y7yYMm3ySnyXcqZOnaqJaXpp0aLEArkya1tbrlP3YmENAdFq6Hrdu3fv9OnTa9eu9WeLa4iWJg/1Yts4dSmBhkaFSjWCfAQQQAABBBBAAAEEEEAAAQSqFJgwYYJquH379rlz5+JVeaYVixTQIAbNctKrJutY17a2SFObf1OGWktm1apV33zzjbf28OHDnibRPAJ1XFdIgdgbN25YV22J+DAnC0E9FpbPcl7KIIAAAggggAACCCCAAAIISECPQ7p69aqW49EtvZ4j9MwzzwwZMkQhjxQcu++7fPmyDvw//+f/jB49ul+/fuPHj088Ss8U++yzz77//nuFbB577LGhQ4dqVaCK7wTnzZv37//+74oK7dixQ1GJSCPXrFmjnGeffVbFjh8/Htlb6sFPkXxtnj9//sSJEzp81KhRpfoVOcrPFcn32h599FHxKiblJZXwvS+++GK8O1ZSgCqmtB8rfw9sRU5nh0Qy/SwVt8GqTfyplixdunTr1q3aq+WHFi9eHC/mb5jPP/9ce6Xa1dXl3YmXr+w942fJ8rb0kzqONazU5bbyfoqMHdFR1pePP/5YHxN9uIYPH+7XzttQ70Qdo0IKCWn2oHVAw/B0UcOcLB2zo7KUpAwCCCCAAAIIIIAAAggggEBtBbQWTLg2sxaIsfqPHDkyadKkxHNplpAmT128eDG+V/OJNHjE83U/rDE7iSUVuNFjmFLiAl5JPPHmm28uWbJETd29e3cYh9LpLBI0f/78+FHKKfXgpzBfoa7JkydHDk/UCI8KOxLma/2jcEabmq35Vnpyt5qt+MIrr7zioSsV065NmzbNmDEjEjVYtmyZXRfN27KGhQXC03kzwsyatCECEtn8wx/+YFGhkydPRnZps9QbRmtUq21hX1S44vdMqbOozsjbMmzh0aNHM17uvB2xs6xbty58A1imZt6FbWhAmhlkDUDmFAgggAACCCCAAAIIIIBAiwko3BCGhBSp8Q7oVll7fdMTiiJpZIAHehT00b29H/iXv/zFSyqhURiRkr4GjfJVj+7kw/IZ07/73e+spGIf4SHvvfeebWqgUJifPa1wkscIvKk6XJkVNFW1eUTAiTTKadq0aapTD+2ykJBOZOfSLl2OuXPnZm9w2ZKNaYOv8K2QVqRJkTeMHKyzKqZQ18CBA/UmCQ+p7D0TOUv629JPl+tyR05RtiM6y8SJE/0NoE2f1Thu3Lh33nnHm9GARB2jQv7EMa04pbQ6E+b8/Ciyci87qgEKnAIBBBBAAAEEEEAAAQQQQMAFzpw5Y+M7lKPIjqZxXLhwQT+VtjLaq2llXl4JjePwKJLGX2i94WPHjuluWQcqrQE1mhoWlldac4sUANIgFyt569YtnULHWjHdlkfKZ9nUXaTdYG/cuDEsv379em1qVziAKCxQNq0wjWIW27Ztu3v3rjXVNVauXFn28EgBq033xKpNRBohYrEh5Y8YMULxAm0KTevy6KWEhUsUK6kgAhU5tW82oA0a9KTFv+2ML7/8sp9aCX/DqGu66HonyEGwojBYBcI0PCo8ROm87xk/i47N+La0M2a/3H6K7B3R50v124nUKr0H9BHwz5fvsgL1/lnHGWT6sEUeNxbPqXf3qB8BBBBAAAEEEEAAAQQQQCCvwMKFC+2QcHqUpiApyjNnzhwbMqOEbuO9Zr/7U6TD07ZX84DiM85U25YtW/xwSyhTs8w++OADxQh0b6wIiHIiZcpuvv766zpWNfjhCmApxKADbWmhsjWUKqA6feyCGqYpTjZ7Sz/j051KVeL5NlnMNrVs0M6dOzVORJs6i+ILoa30bGac9mp1ngpM/KSRRP3aoHE9p06d2rx5s8nrvFqUJzy7DzdT6Cd8w4hCL00304GKji1YsCA0z/ue8Zozvi3DFma83BV0xD9figT51VRCny8tL+XR1bAx9UvXMSpUv0aXrXnkyJFly1DABeByiowJxDJCWTG44MolkKsw7y64cgnkKsy7C65cArkK8+7KxaXCRRb76cuf4lwdHR3xTOX4sjKJe3NlKpii+2EdouEq8WiOcpSvAnp52EXDJWyAg3bFJwrlOrsK//GPf7TA082bN/2eOXslL730khVWpMZWMnr77bctR2v6Zq8nUlJd8/CE7VK0S4OPrONaRTdXU+OjlsK3ukIhkbN7SEXLfnukI1Im72bN26BwRmJEQ3Sa0BeO0tIbxgJqarMWooq3XAI2wUqLkcffhPHyie+Zat6WGS93BR3xz5eGRMXfM4ka8f7WMKeOM8hq2EqqQgABBBBAAAEEEEAAAQQQSBGIrMCSUrLsrjt37liZFStWJBb2fC/p40G0K7JCcGINnqkZRppNoyESWnlXwQ57aYCJFbh+/bqXzJ5QA2wamuYuqX69bDacMnO1LXLGxBltvkqRU0SOKrWpAU2RXQqaKBJhma+++mpkr55OFcmpfrMxbVCn4uOb/O2qixJGi7xTvoKSnk/nmZbQBc34nqn4bakTZbzcFXREsU7riIYFRbqmTWn4zMT43nrktOdYIT0psB5Y7VenRaPhynhlPXiPWBYxuLIohWX4PIYaZdNwlSUKC8AVapRNw1WWKCwAV6hRNg1XWaKwgHEpp8i/ev1q5q9CE0vXcExQvHLL8QWD9ET5xDKer5J6nLbK+CGJ5UtlKhi0fPlyv3WPF9Pj6hUniueXzVFURSNNVLNq+Otf/2rl46GWsvWEBRLv4X2xJKcID0lJ6+Hr8b1PP/20RmAp31TDAtXEs8J6wnTN26BwhilpYppNA9Tp1CMtoX3w4MEw+qM4kbVEl0mvsFWRdGRsVK73TGVvS2tAxstdQUc81hm/ynbqp556KoJQ181eiwopvKchdul96+zsrMdbP/2k7EUAAQQQQAABBBBAAAEEEJBAYtQgJV+7PEpSFlCP/fbZRhpO8vzzz/v0ru7ubj2mXTVoek7ZehIL6H5bdSoesWPHDqtEm6VuwhNrILMCAUVSPIqnuXsaR6P3g66CJtlp6I0COhXUGR5S8Xsm+9syPF2903379k08xdChQxPz65TZC1EhTaLTCu0+hzClY+HCSynF2IUAAggggAACCCCAAAIIIFBzgfjEHzuFj4+In7HUIZGSGiXgT3lX1CASr9E9o0WFIkfl2lQYQpX4jafPestVSasX1pidXuyCBgcpHvT444+rDboQb7zxRuRCK1/PdEsclePN9hFG1bxnMr4t/aQVJLJ3xCsvtWyWBrh5mQYkGh0VUmzPP/wN6B6nQAABBBBAAAEEEEAAAQQQyCXgt+4as5N4oOf7EAxP+K7EAz3TJ45ozpGfzvf6wiueU0FCK/6EoaXGL+JbQZurOURDoiKLYas2fyp8NTVXc6yapMfYxR9a528YVR5fcTnxjBW8Z/wsGd+WiedNz/RTZO+Iv+E1lUxPW4vXX/EQuXhVWXIautq0xo+FISEteK6Hw6W84u/pLF2iDAIIIIAAAggggAACCCCAQMUCPrFl9+7diZWsX78+ku8DOrRLYzoie+ObPtpIj7eP79W0r3hm3hw1SbecdpRiT97CvPU0eXmPSuhZXZGmalWdlDWbIoXrt2kPrVP9GhSmVaLtRH6zr/dYljeMjqrgPeMXPePbsgKECjrin6+NGzfGz6iwiQ9wi++tR05Do0KnTp2yPugzee/evWPHjv1tifkS//glrEfPqRMBBBBAAAEEEEAAAQQQQCAuoLEbumVTvm7j42vBKMdiDSrjozx0b7x06VIdol0bNmyI1xnJ8ZE7/rgxL6BYRq3uirXCsZYl0atUeMtP2rqJRx991Br/8ccfR3rx4YcfRnJ6a3Pnzp126oULF1pCN/v+Hkt5wyhE4jGjCt4zed+WFfhU0JHw8xVZD1ud1Xo7FTSjmkMaGhX6/PPPra266iwjXc1l41gEEEAAAQQQQAABBBBAoGIBPddJwZ1SLy3r4zfqWhB6xIgRNsRDP5X2JaK9jDVDmwMGDFBaj5TS3/3DWTBK24PnvcF+L611Z9QM3fxrl+qfOHGiloX2YlUmdBbdgeulRJVVNe3hHivZunXrsmXLdO0UWdDKLbpS6c/2amSPNE/KLms4XEihuvANo5Z7k9QFhUvUnT59+vjEscreM7nelt6AXIm8HVHl/tkRiz4sdtX0QRg4cKCuY66zV1+4oVEha64uvD6W1TedGhBAAAEEEEAAAQQQQAABBCoQ0GAcBXdKvWxpXq2eazXrTn7cuHEdHR36qbRlam/ktk437e+//77d56t+rTGsQ+yldDxCsWjRIqtKzdDN/z/+4z+qfgWJlHn69Gnbxc+yAmJfu3atFVNAYfDgwQ8++KBWbtGV0gQ6v4hl66l3gcThQuEbRi3Xu0VvA/1UFxQuicdHKnjP5H1bVuAQOUWWjuiz41dNHxa7avogaKidPkE27K6CllR2SEOjQi+++KJaqX5aJLiyFnMUAggggAACCCCAAAIIIIBAvQUWL16suVcW5QnPpRzla2+YaWkNCdFDr2xmUGSvjoo8akrPoVf0x5f+sVlpKqbMxCV4IxWy6QJ6BryW6/VNSwj2X//1X31+WWRv4zfD4UIaymQNUOY333wTBkHsbWB7FRhSVKuzs9NbW9l7Jtfb0s+VK5G3I6pcV03rcEfOoi4rnKduRvLrutnR09NT1xOElSsYpBiwcnRpE79EwsKVpRVW1IFr1qyp7PCiHTVy5Eh1+fz580XreGX9NS7EMurBlRHKi/F5dIosCbiyKHkZuJwiSwKuLEpeBi6nyJKAK4uSlzEubRb5l9VfzfyVg/z2n35r6Wru4HRHFk7s8sojCa3GouEPnqlDdK+uGT16dtKQIUPCXV4mktAMIE38uXz58vfff6+jtLxuZGBRWF6t0hK0jzzyyLBhw3ztXptPpHN5jg7x9itSEK5J4vmRlodnCdOJ5T2zVOWRfKvQeqp05NSV1SZqHajaErkSTbxfdkaN8wovU2IzEjO9ngra4BVGELxOS3ixyGW1veqdnj2nx3L169evq6srsYxXqKoyvmf8ECWyvC29kbkud3iWXB3RgSqf5aqFp6htuqFRITXdnkyvALBCyFm+TfL2lqhQLjF+NamAS4cU+VeT7GL8JpfdykryecwlBhdcuQRyFebdBVcugVyFeXdVwKVDivyrV82jQrkuAYURQKAIAg80spOKzCnmp5FsmiyqQUNKvP7668op1YbE4FypwuQjgAACCCCAAAIIIIAAAggggAACCGQXaOhYIY2M0ipK2Run2aqJA+dSarCxQtUMqkypvP12HTp0SJ3yVevbr4O17ZFxIZZRFa6MUF6Mz6NTZEnAlUXJy8DlFFkScGVR8jJwOUWWBFxZlLyMcWmTX1bNxO50lOZmx98kJBBAoHqBhq42XX1zqQEBBBBAAAEEEEAAAQQQQAABBBBAoCYCDZ1BpqWn4kujp3RD5VP2sgsBBBBAAAEEEEAAAQQQQAABBBBAoGKBhkaFtLz0rFmzKm4rByKAAAIIIIAAAggggAACCCCAAAII1EqAGWS1kqQeBBBAAAEEEEAAAQQQQAABBBBAoJUEiAq10tWirQgggAACCCCAAAIIIIAAAggggECtBBo6gyzSaD2S7M6dO5cuXbL8MWPGKJH3oWOROtlEAAEEEEAAAQQQQAABBBBAAAEEEMgi0NAn03uDFAmaM2fOxYsXPccTM2fO3LBhQ8WxIXte45o1a7xCEikCI0eO1N7z58+nlGGXCxiXNhFzk5QEXCk4ibv4PCaylMqsLdevZv6q1InaI/+nL39SR34xnAHCma4nXJmY/l4Irr9LZPoXrkxMfy9kXNri68tIfvtPv7UET6b/+3uEfxFAoAYCvfAL4rJly5599tnEkJA6tH///sGDB2/fvr0GnaMKBBBAAAEEEEAAAQQQQAABBBBAAIESAo2eQXb06NGtW7daYxQbWrFiRb9+/bq6us6ePdvd3b1+/frbt29r75IlS6ZMmVLxiKESnSUbAQQQQAABBBBAAAEEEECgfQR++OGHq1ev2rIkgwYNGjt2bPv0jZ4g0BCBhkaF9ImdPHmy9evIkSOTJk3yPloAaPHixfv27Zs9e7byf/3rX9+6dcsLkEAAAQQQQAABBBBAAAEEEEBAArptPHz48MmTJ21UgZloNRKiQrw9EMgr0NAZZAri+sc1DAmFjZ41a5bGEClHH29FkcJdpBFAAAEEEEAAAQQQQAABBBDQSAKtPRKGhDBBAIHKBBoaFfLHjWk96ZTm7ty50/Z6FCmlMLsQQAABBBBAAAEEEEAAAQQKKKDxBEuXLl27dm0B+06XEaiVQENnkGmMn9qtj276gkE+6k9RpGeeeaZWXaUeBBBAAAEEEEAAAQQQQACBNhC4du1aZ2fnAw/8fD/79ddfr169ug06RRcQ6BWBhkaFtIC0hvnp6WP63KYEhs6cOWMWhIR65T3BSRFAAAEEEEAAAQQQQKAtBbRGx3fffaeuWUhF6a+++urEiROPPvroc889N3LkyIcffrhUx31dZ/2xX3d2ulkbMmRISnnd9NkzhfRzzJgxOoVWg045xY8//njjxo3Lly9//vnnasOoUaP0VKJSt42l8ks1nnwEECgl0NCokEd5Vq5cqeXBSrVp4cKFtmvAgAGlypCPAAIIIIAAAggggAACCCCQS+DQoUP2bB+NtdmzZ09kiI3uvz755BO/awtr9ocCWab+2G+JyEOELFPxnblz53oZZYbpvXv3ajFZK+k/FUKaOnWqBhB4jiW0gLTaaWOCIrvYRACBmgg0dF0hxZKt0fpS0CPqEzugrxv7LtBXUv/+/RPLkIkAAggggAACCCCAAAIIIFCxwPz58z0kZE/7UVVavFlpn7rhlS9btsxiSZbj5bWpZ0xrr5e0xIEDBzwMpNs6RXb0Co+KlNc94ODBgz0kpJI+PkD1DBw4kMcQRcTYRKCGAg2NCml4oQLD1np9fYwYMUKff4WHFBhWYvv27crxr5tPP/20hv2kKgQQQAABBBBAAAEEEEAAARM4fvy4Elqn+e7duxcuXDh9+rRHbaZPn67BPg6lINHWrVttU8EdDTJSef1U2jK11x8rZDkbN25UQhWq8lu3buleTy8dpU2NLdI8MitmPzWLze4BFQlSexQbUkkdpSbZKRSr2rRpU3gIaQQQqKFAQ2eQqd0aK3ju3Dn7WtEH3mNAkS5t27aNmaIREzYRQAABBBBAAAEEEEAAgVoJfPvttz45Qw/8USxGo350p6YojAb7+CQvX98jnCymmzUFeubMmaM/9qs9Suhwa5iiSDbqR4+Wjqw6pM1JkyZF2u9DjRT68ZOqjJqk18mTJ9UeDWtasGCBtzZSA5sIIFCNQEdPT081x1d2rL4p9OXiQwTDShQP1nPrKw4JdXR0qLaDBw+GdZJGAAEEEEAAAQQQQAABBFpaYNq0aentz3Jnp1CO/WFet11KRyrURK0+ffooU8N8LMqjWR2a2xXmRA7RbA+7rdPoIbuJ073euHHjVCxx/aDI4Roo9Pjjj1umRhJFokjKX7dunc10C2NSkUq8kYmdihRmEwEEIgKNHitkp1fQV98y+vTeuXPHRxtqVbO+fftWHA+KdIxNBBBAAAEEEEAAAQQQQKA4AorpxKMqpbq/aNGi+C4dPmHCBE0u87/f637Niq1YsSJeXjnKtzCTl9S9nuaCaYCP8jVNZMaMGaNHjy61XLQvGKS5Y4mN16rVFhX6/vvvExtAJgIIVCnQO1Eha7QFgBKXuK+yV+fPn6+yhoIcrgdDqqdwZbzcxoUYXBkF8hbj85hLrLZcv5r5q1xnb7nCP335k9r8i+ENXUyw5ZS8wXA5RZYEXFmUvAxcTpElYVwqyddXhCvLmKDIIfHNJ554Ip6pHJ+lZTEm/xN+v379Est7vkr6nZ1me1koR/PR9NKBGsWjWWbjx4+PhH700HqrVuXtkMSzKPPw4cPh/LJSxchHAIG8AvyCmFeM8ggggAACCCCAAAIIIIBAewp4VEhzu8IednV1hZueTsxftWqVpo/58tUqrEeJaQUiTU/TI4bCpay9HhIIINBbAr05Vqi3+sx5EUAAAQQQQAABBBBAAAEE4gIeDOrs7Az3alBP4lofPtgnLKy0xvXopdqOHTvmjxtS/pIlS5577jnNMouU1+OGpkyZEskMNyODjMJdpBFAoBqB+kaFtHJQqa+JLI2eOnUqH/4sUJRBAAEEEEAAAQQQQAABBLILXL58OTHK41EhWwnIJ4V1d3cnVu75Y8aMiRfQyCMLD+n5Ym+99ZZCQiqzZs0ahYqscHhUYnvidZKDAAK1FahvVEghoVLPns/SDa1jT1QoCxRlEEAAAQQQQAABBBBAAIHsAu+++278IfH6o76WmlYlWnPaqtLjgCyxe/fuxYsXx+tfv359PDOeoxiTDlclWsdap/CFsX3Cmna99tprpRaljldIDgII1EqAdYVqJUk9CCCAAAIIIIAAAggggEBrCGihH19J2lqs5X42b95s6Xnz5llC43e0ULTSiubEn2SvHD1rTHtVxkf6+GPFrIb4Tz2h7KGHHrJ8DQLw+jds2BAvbDmqk9WISuGQj0CVAvUdKxQ2TvFm/3IJ81PSHjlOKcMuBBBAAAEEEEAAAQQQQACBvAJaDVoRGcVitITQgQMHli9fbiEe5Wval9emAgohaVOzQDZu3Lhz506tCnTmzJmFCxf6A+zDgM6hQ4dUTE+snzhxot/QaWLarl27rLxmk4VjgjRK6OTJkzq1nkH2l7/8RVV5gEmRoC+//PLtt9/Wg8w0j8Tz1Rg14Pr169bIK1euWOKLL74IQ1csSGIs/EQgXaBxUSENFPz222/nz5+v2BDzwtKvCnsRQAABBBBAAAEEEEAAgfoJrF27VlEYhXss4uMn0kAeTS7zTSUUi9FS0LYkkMI648aNC/cqrb1hvEY5KuYLiSjG5MEj7VL9M2bMCGvQveH7778/ffp0BYa8PSpmIaqwZJjesWNHpOXaG55XmyxIEoqRRqCUQH1nkCnGrE+mvnHs9Err20TPI1TYWMFdBgGWuirkI4AAAggggAACCCCAAAL1E5g7d+7p06cj9VsEx1eY9r1aEkgRFkVqPMcSylF+ZL2hQYMGqR4vGYaENDTp008/DQcKWTENPvrmm2+WLl3qR4UhIdWmwFPkmWhekgQCCFQpUPexQvpO0WvlypV6HqFWm7fVy/TTEgoYvfrqqypQZTc4HAEEEEAAAQQQQAABBBBAILuAYjE9PT2a2/XZZ5898sgjw4YN8wlf8Uo0GujWrVsqrHiNFiTSHdyQIUMSp4Co2gsXLmglIBW+efOmzfPSs8ZUOKV+hYq23H9pxWs7ql+/fl1dXaWOUtlw2lq8wcohkJTIQiYCEYG6R4XsfPqQ69tBDyDUV8N7772nleot+qtRi3op+qt5p0z7jFwbNhFAAAEEEEAAAQQQQACBugooUhN/GFmpM6qwXln+qK9ojl6KJek2sFRtifk6JMtR1pLEGshEAIFcAvWdQRZvij69GmGoMLNGEvoQQaU171QzyzTjrOyS9fE6yUEAAQQQQAABBBBAAAEEEEAAAQQQyCvQoUGDeY+pYXktLfTJJ5/oCYg2oUw1R9aWz3uujo4OHdK7ncrb5l4srwcE6OwapdWLbWihUxsXYhkvGVwZobwYn0enyJKAK4uSl4HLKbIk4Mqi5GXgcoosCbiyKHkZ49Imv6yaid3pKF3NzY4e0WXrQFd52+WXiQQCCLS6QKPHCsW9NIVVA4ji+eQggAACCCCAAAIIIIAAAggggAACCNRPoEHrCsU7oFXE9uzZs2vXrnB5+QkTJtQkQuRx9Ph54znxWHuuw1Vhu9ag2Xya1hcXK5UTd2iGGjQe7cEHHyzV5nh+vBfNUIPamettGe9F3hpUPl5JrjaohoMHD+pn+MpbQ/VtqEcNzfDGrr4NzfDGrr4NenflelPF3w95a1D5eCW52tDGNVT/tmyGGvS2nDZtmi5Txlf8/VD9G7v6GtT4XG/LeC/y1qDy8UpytaGNa2iGN3b1baj+bdkMNeR9Y8ff1XlrqNMbW9XyQgABBGol0OiokP5P0ljQjRs3hk8o1GrT8+fPnzdvnhYkq1XHqKd6geovRzPUEH/yZV6ZZqghb5spX1eBZnhjV9+GZnhjV9+Gul5oKs8rUP3bshlqqP5t2Qw15L12lK+rQDO8satvQzO8satvQ10vdKtUroVc9WqV1tJOBBBogECDokL644CeTL9jx479+/eHveLJ9KEGaQQQQAABBBBAAAEEEEAAAQQQQKBhAnWPCpWaKfb666+/9NJLhPwbdqU5EQIIIIAAAggggAACCCCAAAIIIBAK1Dcq5Evc2ykHDBjw5ptv/u53v6vJ4kFhNyLpxDnAkTIpm1UerppbpYayD8JolY6kXM0aXo5qHoRRQEnnCq9OezjU8E0V4pT9PIaF69SGyCnKbrbHBS1CL7K8u6p3aJu3pa2JVs0zj6rHbKEaUt5dLdSLlK+76nsRfjRSuFLaENaQXixlb/UdoQbjbQaHlAvNLgQQQCCvQH2jQmFrtJK0Vg5SzrFjx8L8lLR+Iat+FnRK/exCAAEEEEBAAh1rO9rb4eDIg0XoZq0uIly5JOGCK5dArsL27tIhbf8tncLy0cyPUvayCwEEEKheoHFRoeP3X7lafO3aNaJCucQojAACCCCAAAIIIIAAAggUUEDPNfruu+/U8c7OzoIsVFLALhfwjd2ALjcuKtSAznAKBBBAAAEEEEAAAQQQQACBmgso4GJzPg4fPqz1QEaPHj1o0CD9zBJ/0aOHDhw4oCaNGTPmySefrHnbrELN0Jw9e7bSGltQv7PUqfGVVds8XW7MJa5MiaPKCtQ3KqSP/d69e8s2olSBei8/VOq85COAAAIIIIAAAggggAACCEhg+/btu3fvvnjxYlxD68b+6U9/mjRpUnxXmKOnUVu8JrGSsGTrps+cOaMnbqv9W7ZsqdVtbD3qrJNwES5xneiaodr6RoUUoy1ImLYZriVtQAABBBBAAAEEEEAAAQRqK7BkyZKwQkWCbt++bTlKTJ48WeMAZs2aFZaJpE+cOKEcHfjMM89EdrXN5vXr1/fv36/ubNiwoVZRoXrUWSfwIlziOtE1Q7W/aIZG0AYEEEAAAQQQQAABBBBAAIGmFVi7dq1mZt27d+/WrVv6efr06ZkzZ1prNQ7o0qVLKS3ftWuX9s6YMSOlTPW79KgitVAvrStUfW0tUUPzdLkxl7glLkorNrK+Y4VaUYQ2I4AAAggggAACCCCAAAIImMCRI0fGjx8fPgVIawmNvf86efKkjRs6depUqXFAChhZmXpHhdTCsJFFuHxN0uWGXeIiXNNe6SNRoV5h56QIIIAAAggggAACCCCAQK8JfP3115cvX/7444+1YrQCOsOHD1esJ/GZVinLBm3atMkWDDp79uzixYsTO6OAkeXrRJECOt3Vq1cVU9AK1lOmTFEzhgwZkhjZiTRMm+fPn//zn/+s82rGli1aEikTOZeWQ75x44a6/Pnnn2vXqFGjurq6Elc7idRj57IZUjoqEiBTVVbzlStX7Iw6RXjqyAPRtGj3Z5999v3332shnscee2zo0KFaijdSJnudkaaG57W0ClQjnNLr8FwplzgsRrppBYgKNe2loWEIIIAAAggggAACCCCAQI0FFMVQJGX16tWRejUpTAvZ5HqMlyIaVskXX3wRqc03tVK10ppuFnla2b59++xcVtIW5VFaQ5PicajwYVt79uwJG69wkgV3wjKRcI9CYJpsFV/rWq1SbZGGhfUoxKOFk7wvloi0UMGmwYMHe5lIec1os8YoHjRhwoR4G3Tgs88+q5OGbc5YZ9jU8HBrTMXCWXrt/VWi1CUOy5BuZgHWFWrmq0PbEEAAAQQQQAABBBBAAIFaCrzyyithVEWhCqt93Lhx77zzTq4z+biY559/PvFAhUIsDjJnzpywwLJly8KQkMIivldRFe31zUhi/vz53nhveaRMZFPBEUVtPByjc2ndayujUNTAgQM1oCZyiG3qXB7i8UO0S5kKMyUekpKps3gb1HIFpLxO5auFFdSZcrpqhHP1utQlTmkbu5pNgKhQs10R2oMAAggggAACCCCAAAII1EXg6NGjx48ft6q1gPTdu3ePHTum8Sy2dLTvynjuzZs3W8mXX3458RBVbvmaeOUF9MD1rVu32qbOq7NfuHDB26B87S21fLW10Ja+VuU9PT0aBOQ1xxOKWVj4SSEYHaX4i86lBbN9tWyteaR5cPEDlaNz6aht27ZJSYeELVy5cqUfokE6aoYexGY5KqZNf4VDeJYuXaoGaJdarliV1alW2YEKQlVQpx8SJqoUztJrP13iJfa9JFpCgKhQS1wmGokAAggggAACCCCAAAIIVCWguWO///3vrQoFL1atWmWL+ChyoSCFxzUynmP79u0Wo9Hom5deeinxKBt8pKEx4WpBCxcutMKaiqXzWtzE2qAc2xUZWxRW/u2336rlHm0Jaw6LWdqHHSn0o6N8SWwtlq1T22gdDT5S8Ch+rHIUxNF6Sa6k6WZWTIOMhJl4SKlMNXjLli3eACumTLXKhkoJs1bDhaoUztXrxEtcCoH85hRoz3WFNMGyObmbs1Vw5b0uiOUSgwuuXAK5Ctfq3XVw5MFc523RwgXpZq2uDly5JOGCK5dA3sJFfoP99OVPca6Ojo54pnI0CCUx3zO1Wo09DkwjdDyq4nv1jLDly5dbAc8sldBYniVLlthe/XccWZrH8jVnysJG8+bN83oU+FDQQZsKhcTXD1KO8lVAL5WMN1Ija/r37++1pScU6/HlihKHFC1YsMDmo2kF6Hhj1JLIudRNRbisU8KMNy+9PaX2/vGPf7RJWzdv3qy+ziqFc/U68RKX6ib5TSvAWKGmvTQ0DAEEEEAAAQQQQAABBBDIKlBqfRw/XkEHS2uFZs/0hEIeL7zwgm+mJBRt8cFBmmBVKpDhj6aaOHGi13bnzh1Lr1ixwjPDhOd7yXDvq6++Gm6mpx1EsaTEIUVz5861GvRQsHhV4ZQu3+sRrsTmebFSCY0w0vQuDVNat27drL+/fCKeVvsudWD2fG+YS0aO9XwvGRbI1evESxzWRrolBNpzrFBiJLglrkeDG2l/ZocrI7uPSkAsixhcWZTCMnweQ42y6dpydaztKHvGli5gf2afdn5aS/eiYY2HKxc1XHDlEshV2IcIFfnr66OZH8XRyo4Jih9iOR50iMxj8vJPPfWUp0slFBLScBIbUqRoS6kH0uvwd999Vz8jY098waB+/folnsLzVTLezr59+yYelZip59ZbvgYE2ZigxGLKPHz4sEI0kb2JsTN/7Fpi8yI1RDYVDEofjaXH1cebEamk7GaVwrl6nXiJy7aQAs0m0J5RoWZTpj0IIIAAAggggAACCCCAQJMIlIqtDB06NL2FkZCQ1sQpVV6DYmz2VuLYEx3V1dWVeGyp/MTCLZSpdb79sWuKlOmpbaNHj7b2d3d323Q88dawR6UkS+XnPXXZS5y3Qsr3lgBRod6S57wIIIAAAggggAACCCCAQC8I6InyidO+NGQmpTXZQ0KqRMNerKrw6WNh5RrIk9gGH+ATFq4yrWluiUNgvNrE+WW+t/qEAij+uHctmRQZA6WVgHyRpurP5TXUW7jsJfaWkGhyAaJCTX6BaB4CCCCAAAIIIIAAAgggUAMBn/109erVxOpSxqrkCgmp8gMHDuinHvIViYD4pgbIJLbB8721icWyZIY1JEagslRSkzJamtrq0TrfLuA1+3pPnlNNwut3yUhtnh/6RMpk2Sx1ibMcS5mmEqjjatMKeWp5/Nq+qp9m2VT6NAYBBBBAAAEEEEAAAQQQaIyAj4hZv369Rq9ETqrbN3u6ViRfm3lDQjrEQgZ6yFekNp+8tnv37sgu21TbEvMryPQniOlc8f5WUGGWQxKXcPYBUHPmzIlXsmPHjnhmmJNYZ1ggTDdMuNQlDhtDuiUE6hgVaon+00gEEEAAAQQQQAABBBBAoAgCipJofWj1VGtFa9ljf0SXchQSKrUAUBgSWrp0acpaQm6oBY9tOeoXX3zRMy2hMTsaL6O0JlJp9eXIXuXYgSpT/egeRcH8XBs2bIicyzflUH3MaNCgQVahP5bL61fCH1bjjxvzvbKyBZg8xxPpdXqxSKIxwimXONIeNptfoI4zyPSls3fv3toS+AejttVSGwIIIIAAAggggAACCCDQ9gIKBtnTuLbefylINGrUKIUqbJSQJnxZUCZ08CeOKfOXv/xlPJRjhcNZHR9++KFl+oLKYYUK0FgcRKsvb9y4cefOnWPHjtXz2hcuXKhQkZVMCeKEVZVNa5TQyZMn1Sn1+i9/+Yuq9WCTIkFffvnl22+/LYlr1655ftk6EwsMGzbM8m2sk1ZTsjE7nZ2dDzzwgMWn1Gs5C1BBIuWoy2vWrCk1Pku1pdeZ2AzLbIBw+iVOaRu7mlCgjlEhvdHDr4Ym7DxNQgABBBBAAAEEEEAAAQSKI6B7tNOnT0+fPt2iP+Hz2hUh0jPI/DlZbhLGiVIWRQ5v/T744AMdroFFCoh4PZ5Q/EXLP1tVCgONGzfOd1lCe6uM0XiF6u/7779v/VVQRi/tSgx++SGVJTQkQuOSVL+4QiWPNy1atMjObsJhG3RF4ghqRtk6SzW1AcLpl7hUw8hvTgFmkDXndaFVCCCAAAIIIIAAAggggEDtBTQwR7EYhWw0CMhqVzjjyJEjmhrmT5WqJiijGWc25Ofll18u1frFixcrXKLISKSAcpSvvZH8ajbV32+++Ub99UrCOJcQFITSiB7fW3Fiz549misT75RVqGFTiv5MmDDBNq0NKqxMtbDUSdPrLHWU8usqnOUSp7SNXc0mkBC7bbYm0h4EEEAAAQQQQAABBBBAAIFaCWgQypYtW1SbZlGFw3n0xPr4KRSmiWem5Lz33nu2t9Qz6W2vAk+3bt1SfEHxES1SoydnDRkyREN7EmvWlCtrRkr4JqWM+qj+6qXlk/TAr+vXr/fr16+rq0unE0XkjCn1qKQaYC2JH6izaMCUjZnSWkXqmpW3+rVX0Z9jx45pl9YeeuSRRzRBzCuxOuPdT68zvak1FI70OuMljsCy2bQCRIWa9tLQMAQQQAABBBBAAAEEEECgjgIKOnjt/gwyW6HZ8/OOG7KHi2lQTDzG4XV6QmERvfxh6p4fSaiqsrVlKaO+6JUyNkfnTa9HYqoh0rz4Zkol2jVp0qTIIZXVmXIWr78mwpFe57rE3hISTSvwX98CTdtEGoYAAggggAACCCCAAAIIIFATAS1yHI5SsToVEtLAE0u/8cYb1Zzo6fsvLaNTTSUc28wCXOJmvjoVtI2oUAVoHIIAAggg0FYCPat72qo/sc4cOnRIeW3fzVi/K8yAKxccXHDlEshV2N5dOoSvr1xuZQvv2LFDyx5rLM9vfvMbLS/d3d199uxZWwhZx2qgUNmRO+mnKPWQsvSj2NtCAlziFrpYWZpKVCiLEmUQQAABBBBAAAEEEEAAgfYR0APR489E15LMmzZtap9O0hMEEMggQFQoAxJFEEAAAQQQQAABBBBAAIG2ENCiMJredeDAAVsOWT+17rKekDVmzJgsq9u0hQGdQACB/xIgKvRfFqQQQAABBBBAAAEEEEAAgfYW0BLFWm5Zr/buJr1DAIGMAr/IWI5iCCCAAAIIIIAAAggggAACCCCAAALtJEBUqJ2uJn1BAAEEEEAAAQQQQAABBBBAAAEEsgoQFcoqRTkEEEAAAQQQQAABBBBAAAEEEECgnQSaa12hH3744aGHHnrggeZqVTtdb/qCAAIIIBAX6FjbEc9sp5yDIw+qO23fzVpdMrhyScIFVy6BXIXt3aVDivz19dHMj3KhURgBBBDIK9DosUL77r/OnDkTNvTHH39UzsSJE/v06TNw4EAVUU5YgDQCCCCAAAIIIIAAAggggAAC9RDQ6ISv77/y3odWfGA9ekGdCFQm0NBROfrMzJ49Ww09cuRI2Ny33npryZIllnP79m2VWb58+aeffsqTEUMl0ggggAACCCCAAAIIIIBArwjoAfbHjh3TqQ8fPty/f389yX7QoEH6mWWeh0ItBw4c0LFjxoxpzlu8Q4cO2Y3qtWvXcrWw4gNrfhGbH7nmXabCWgk0NCp0/vx5a/f48eO9AwoVeUjo2WefVf7FixcVG1q5cqUGDXkxEggggAACCCCAAAIIIIAAAg0W2L59++7du3WPFj/vgAED/vSnP02aNCm+K8w5d+6cxVwSKwlLNltaM1p27NihVm3ZskWxsGZrXtie1kUOe0G6VwQaOoPs+vXr6qRCPw8//LD39tSpU5betm3bhfuvtWvXKmf//v0KSHsxEggggAACCCCAAAIIIIAAAg0W0J/ww2iOIkHeAP0tf/LkyWX/ln/ixAkdogOfeeYZP7YlErqB1W2pXhrK0OQNbl3kJoctQvMaGhXq7u6W6dNPPx3Kvvvuu7b52muvWWLBggWWaP7PXtgR0ggggAACCCCAAAIIIIBAWwroL/eaXXXv3r1bt27p5+nTp2fOnGk91TigS5cupfR6165d2jtjxoyUMr27a+rUqeqdXp2dnblaUvGBuc6SpXDzI2fpBWV6RaChM8jOnj0b6aRmPyryqsylS5f6lFQfm6fyuWZ1RipnEwEEEEAAAQQQQAABBBBAoBoBrQmrBUDC2R66cRt7/3Xy5EkNF1Llmv9RahyQAkZWppmjQupd2MHsXBUfmP0UWUq2BHKWjlCmVwQaGhXS6mKKAem7w7uq2Y+W1kJlnqmEZpmFwxTDXaQRQAABBBBAAAEEEEAAAQSqEdATty5fvvzxxx/rRkwBneHDhyvWo7katoiHhsz43+xTlg3atGmTLRikP+cvXrw4sT2+YIjf8UXOojN+9dVXmgD16KOPPvfccyNHjkwP0Ojwq1evKg6ida+nTJmixg8ZMiTlEPVUzdO0Ff3UDanOonWyI2eJNEkd0fCFGzduXLlyxTolq7B37hM/MCymdPbWRqrSppbltXlho0aNigTmImeJI0cKsIlAikBDo0L6BKopChXrLW6fW1uLXpl6LH3YSgsJ6eMaZpJGAAEEEEAAAQQQQAABBBCoRkDxjg0bNqxevTpSiSaFaRmdXI/iUpDFKvniiy8itfmmVqpWWtPNPMwUPrdrz549kZZo+aFPPvmk1MgjrWFkLbT6bd6J0hrQFI9eqadz5871MioWpvfu3Ttr1iyrJ2ySzVZRSGjw4MG2Vz+1fJKnldBcMysWPzAslqu1YVUKQkXOqGoT+2iniyOHzSCNQLpAQ9cV8m8NJbScuz4kW7duVfs0MshnjWnTF5l+4okn0lvPXgQQQAABBBBAAAEEEEAAgewCr7zyShiImTBhgh07bty4d955J3s9KukjaJ5//vnEA3VnZ3/vnzNnTrzA/PnzvSX2NGqV0RgCpXW3GC+/bNmyMCTkh6ikYijaGzlEQxA8DKRgkyJTeoVHRcrXdjNva/3sYvGQULi2tzI17smLeSId2YuRQKCUQEOjQoqn6nOopuirQV86/pFesWJF2L5jx47ZZhgqCguQRgABBBBAAAEEEEAAAQQQyCtw9OjR48eP21FaQPru3bu6+dLIF7tN810Zq928ebOVfPnllxMP8Ts7TYCKF7DTWTP0MGoNVvKQzfTp0zXSJzxEcSIbUqBMtVZt1iHecmVqb2TR640bNypfdaqbWiRbgxL00lHa1Lib9IkpunXt6enReCJrg06kTX/ZQCHblfizgtZ6PWJRMEhP6LZmh31cuXKlF/NEOrIXI4FAKYGGRoXUCA0R1EfLP+16u+tbwEfuWSv905syO7RUf8hHAAEEEEAAAQQQQAABBBCICyjO8vvf/97yFWtYtWqV3XApxqFwiUdA4gcm5mzfvt3COrq5e+mllxLL2OAjDUcqdWf37bffejO0gLVCNnoMkarSiCFfbMRqXrhwoSUU0FFrLS5jLVeO7QpHJCkuY8OUdu7cGTm7NjXdTKezo+rxM29rI21Qy7VOk18d3URbAQ19igTLlF8WOVI5mwhEBDoU74xkNWbTxgTGP4oa/2Zj/7RyWCRalKVhHR0dKnbw4MEshSmDAAIIIIAAAggggAACCLSEwLRp09LbWfbOTvOPbK0cjbVRYCVSm8INAwcOtOeFKWaUPhxGo3L8L/2lCmsx2T59+ugs4Qo+2tSpbdZIYjP8KNWvIJE10lseZobtHzFihMWAvDG639T0lPjZw6M87U3yw21Xqfz0AytorSr0cyX2UevwWgwu0kLniiB7C0kgUFag0WOFvEH3H2WYEJ3VrDF9HvSqICTklZNAAAEEEEAAAQQQQAABBAoloABBen9v3rxpBfQH+HhJrQb9wgsvxPPjOfpDvg8O0kSnUvEjfzBW5MlCXuGiRYs87QkNkLGljizKY/l37tyxRGTtET/K872k7jdtUR5FoDTsQEGi+CgbP7y2CW+DtypSv+d7ybCA1hUKNy09b948S0QOKYscr4ocBCICDX0Gmb4+dPqMqwWtW7dOK8aX+oqJdCOyOXXq1EgOm4kCWuhe+XAl4sQzjQuxuExiDlyJLCmZfB5TcOK7asvVsbYjfop2yjk48qC6M+38tHbqVP36AlcuW7jgyiWQq7C9u3RIkb++Ppr5URyt7Jig+CGWo0eMWaLUE76eeuqpUsd6vu7pNJjFhhRpMZBSD6RX+XfffVc/VbjUDWCphwt5ecW5bBaVLxjUr18/b0mY8HyV9N4tWLDAVrPWkkN6qbxGJ2mWWfpT3sNqK0tX1lo/V2LMzh/cFHZQh5RF9mpJIFBKoKFjhfSp1peCxYZKNcjyFRLy5ejTS7IXAQQQQAABBBBAAAEEEEAgu0Dfvn0TCw8dOjQx3zMjISEtCeS7IgkNzLHnfyWOfIkUjmx6VCh+59jV1RUpbJuJ+WpeuKatSqpJepKX5rVpUaQGDB1KbJWaUSo/sWspmdUgp1TLrqIJNDQqJFwFlTU1LP0TSEioaO9C+osAAggggAACCCCAAAINE/AnykfOePjw4UhOuJk9JKSjzp07Z8cmPn0srDae9mBQZ2dnZO/Zs2cjObZZKl/3nlqcSGtaKzxk61hb+SVLlngLEyusSWapVpXKz3tS70IFyHnPRfk2FmhoVMiG/2mVrFdeeaVUYMhDQpoF6kHiNr4AdA0BBBBAAAEEEEAAAQQQaICAz0K6evVq4uk8HBPfmyskpMPtCWK6p/P5XPE6SwWnvBla6siO8kq6u7vj9SjH872PYTHdVyo8tGXLlnv37mkhJNu1Zs2asEwN01W2NntLsiBnr42ShRVoaFRIn0ZNPZW1AkPLly+Po4chIa0uZlGkeDFyEEAAAQQQQAABBBBAAAEEcgn47dX69evjf6TXk7PsKVfxOvOGhFSDBSy0sk+8Ns+xNXF80xLeDFtz2jJ9ytvu3bsj5W1TPUrMj2QqzKSFkLSqifLV2bLrc/vhkTWePT8xUavWJlYeZmZBDsuTRiBRoKFRIbVAczstMKTlvhQDCtsUCQkxUCjEIY0AAggggAACCCCAAAIIVCPgf6TXsh76I30YE1EsptQCQGFISJOwUtYS8rZpRWRbjvrFF1/0zHhCq/z4wsy2V7GqzZs3W9qfuqVNPYNIC0UroaEDely1FfCfyrHTqYw/rSjsnZcMExrH9NBDD4U58fSgQYMs0x/1FS8Tz6mgtfFKyuZkRC5bDwUQaHRUSOIrV660uK/Wkz569KhdAy33ZctL68OpjzohId6aCCCAAAIIIIAAAggggEBtBXzGhv5Ir0WX9Yd53ZHpyfGDBw/W2Bndi8VP508c065f/vKXCsEkvsIDP/zwQ9scPXp0mB9Pq3LN7VJMSvEgVTtw4EB7WJjlh+U3bNhgm3rS/IgRI/SkeW3qp9LKsV1eRpt6XKl2qU6fj6ZMpdVl3W8qvWnTJp+hZofHfw4bNswyNRZJd6wKxKip1tp44TDHW5KxteGxGdPZkTNWSLHCCvxtomYj+6/P3r/+679qaSF972gF+NOnT+vsWu5LPwkJNfJCcC4EEEAAAQQQQAABBBAolIAmken+a/r06Ta4Jnzus6Z06BlkHmFxFitpm3bX5rvChII7vvnBBx8orYFF6WEXnVEN0IghvfxYJXRXGJ9cpgE4WhLIGqCwzrhx48JDlNZeHyhku1TMu6MwkwWDbJdOMWPGjEgN8U0NVtD4IzVPCGHfr127FjlX5NgKWhupoexmRuSy9VAAgV4YKyR0fTsoamuhaH2e7SNNSIi3IwIIIIAAAggggAACCCBQV4GxY8cqPqKQjQIldiIFPo4cOaKpYf5Mq/SQR3rzNB7H4i8vv/xyesm5c+faEIGwmIVvfMHmcJeWBFI4xu4iw3zlKF97w0xN/vIOKj8MCam/n376aXrEyqvas2ePnl8WP6kXKJXI1dpSlZTKz45cqgbyEXCBXhgrZOdW2FWfTH1QPfasTSaO+YUhgQACCCCAAAIIIIAAAgjUQ0C3XXogl2rWvK0wOJL4UDAFXHK14b333rPyWR6XrhBVT0+PYhyfffbZI488ohlb6beEClfdunVL5XUXqflcCh4NGTLEV9EO26ma9Ux6rS6kwjdv3rx+/br26gllKhw/xdSpU62bnZ2dYSVKy0fDoGwklNWmTC+WcqCKZW+tCqdXpTNaC63xuZBVOS8EUgTqGBXSV8yNGzdSzq1db775po3E0+hBfcb0CsvrrR9+SYW7SCOAAAIIIIAAAggggAACCFQjEN5tabkcewaZhtKEdeYdN2SPCdNKsonBmrBmTyvSMWnSJN8sm1B5vRLHE0WOVRv0UhcUJIrsCjetWJiTmI4Xi+fED8zY2vSqdKXCC1EBcrxh5CBgAnWMCikkpEXLMkJrQqlekcKKhoZv/cheNhFAAAEEEEAAAQQQQAABBHIJaIXm+JAchYQ0VsXqeeONN3JVGCn89P3XokWLIvls1lAA5BpiUlUdo0LgIoAAAggggAACCCCAAAIINJXAjh07tHyyxvL85je/0fLS3d3dZ8+e9fWeNVAoyxiclB5pAdmUveyqiQDINWGkEhOoY1RII+W0Llc10KqhmsM5FgEEEEAAgSwCPat7shRr3TJ6Oq8a3/bdrNUFgiuXJFxw5RLIVdjeXTqEr69cbhkLa7KYzRcLy2sJaj2vPcwhjQACbS9Qx6iQJkbaolxtj0gHEUAAAQQQQAABBBBAAIGWENCSNJredeDAAS3DrAbrZ1dX1+jRo7USM8t3tMQVpJEI1FagjlGh2jaU2hBAAAEEEEAAAQQQQAABBKoU0B/vtfSyXlXWU/Hh95/oNaviwzkQAQRqK/CL2lZHbQgggAACCCCAAAIIIIAAAggggAACLSHQXFEhPZlez7NvCTgaiQACCCCAAAIIIIAAAggggAACCLS0QKOjQlosXS89DTFUUyRIORMnTuzTp8/AgQNVgNhQ6EMaAQQQQAABBBBAAAEEEEAAAQQQqLlAR09P4x68oqFAivuoD0eOHJk0aZJ3Zvv27UuWLPFNJQYMGPDpp59WsNpZR0fHz/Ws+fkHr7ICB0ceVJlp56eVLUkBCRiXEohleT/AlUUpLMPnMdQom64t10czPyp7xpYu8NOXP6n9vxje6D8FtSgaXLkuHFxw5RLIVdjeXTqEry9z++0//dYSjbyDy3XJKIwAAq0o0NBfEM+fP29G48ePdyyFijwk9Oz9l3bdvn175cqVXoYEAggggAACCCCAAAIIIIAAAqUEdF/59f1XceadFLDLpa4++dUINDQqdP36dbVVkR+te++NPnXqlKW3bdt24f5r7dq1ytm/f789K9FLkkAAAQQQQAABBBBAAAEEEOgtAYUhLl26dH9RkOiqIClNUpjGDlHQJqVYlbsOHTo0+P7rxo0bVVbVKoc3T5cbc4lb5bq0XDsb+mT67u5uAT399NMh07vvvmubr732miUWLFiwevVqpfWl079//7AwaQQQQAABBBBAAAEEEEAAgUYKKKZz+PDhkydPakqHn3fmzJkZH29/7ty52bNn68CLFy/64W2W0Dq5O3bsUKe2bNlSq3vYetRZJ/YiXOI60TVDtQ0dK3T27NlInxVT1JggZS5duvSBB/4WovJPUbx85HA2EUAAAQQQQAABBBBAAAEE6iqgmI7u2sKQUK7TnThxQuW1dOwzzzyT68AWKqxpMSLSSyMbatXsetRZq7ZF6inCJY50uZ02GxoVGjNmjOwUY3ZBxRQtPXr0aM9UQrPMwk3SCCCAAAIIIIAAAggggAACvSigezT9Ld+W+8jVjF27dqn8jBkzch2Vt/DUqVOv3X91dnbmPbZFyzdPlxtziVv0MjV/sxs6g+zRRx+ViGLMCqDa0kIHDhwwIz2WPsSysYWDBg0KM0kjgAACCCCAAAIIIIAAAgg0WEDBFoVabG6H1gay5T4ytkHrENkgo3pHhXSDafeYGRvWBsWapMsNu8RtcMmaswsNjQrZWCFBKLFz506NiNu6das2FXX2WWPa9EWmn3jiieZUo1UIIIAAAggggAACCCCAQOsKKLhz+fLljz/+WJM2NLFr+PDhCvroj/d2L+YxIOvgk08+WXFP/eFCkdkhqlCnu3r1qmIKWrRoypQpasaQIUMSIzuRhmlTj7f+85//rCVHNmzYYM2LlIk0WEuXaBVqdfnzzz/XrlGjRnV1dSX2K1KPnctmSOkoPU070kKr+cqVK3ZGnSI8dURSvJ999tn333+vSTOPPfbY0KFDdWscKaPDM9YZaWp4XkurQDXCKb0Oz5VyicNipJtWoKFRIX3qtCaZJltqKNC4ceMcZcWKFZ5W4tixY7YZhorCAqQRQAABBBBAAAEEEEAAAQQqEFDEQZGU+Hif06dP68/2tiy0BgclRkwqON3u3bt1lG4DfRlZq0QrWNu5bFM3iZY4cuTIpEmTLO0/9bAtb9iePXvCxiucZE0Ny0QarxCYJlvF17pWq1RbpGFhPQrxTJ482ZuR2EIFm/ToMy8TKe+SigdNmDAh3gYdqEESOmnY5ox1hk0ND7fGVCycpdfeXyVKXeKwDOlmFmjoukKC0Kdu7969vmyQlhzTxNRZs2aFRhs3btSmykSisGEZ0ggggAACCCCAAAIIIIAAAnkFXnnllTCqolCF1aA/27/zzjt5a0svr1CIxUHmzJkTlly2bFkYEvLbQ5VRVEV7w8Jhev78+d54b3lYIJ5WcERRGw/H6Fy6CbViCkUNHDhQA2riRylH5/IQjx+ifGUqzJR4SEqmzuJtUMsVkPI6la8WVlBnyumqEc7V61KXOKVt7Go2gUZHhRSIVQzowoULCkXrdevWrVWrVoUoelfp0fX6kEQGEIVlSCOAAAIIIIAAAggggAACCOQVOHr06PHjx+0o/Xn+7t27mqih8Sy6/1Km78pbbanyPgtEE6+8jB64bguJKEfn1dl1e+htUKb2alqZlw8T1kK1XOVVeU9PjwYBhQUiad1dWvjJhiMo/qJz6SZUt6LWZa15tGnTpshRtqlz6aht27ZJSYeELVy5cqUfokE6aoaGPliOimnTX+EQHq3VrQZol1quWJXV6at3KwhVQZ1+SJioUjhLr/10iZfY95JoCYFGR4UcZez9l296QrPG9AnRKzKAyAuQQAABBBBAAAEEEEAAAQQQyCuguWO///3v7SgFL/TneZucociF7r88rpG32pTyNvhIQ2PCWSALFy60QzRZTOe1uIm1QTm2KzK2KDzFt99+q5Z7tCWsOSxmaR92pNCPjtLSRZavm1Gd2kbraPCRgkfxY5WjIM7ixYtdSRNfrJgGGQkz8ZBSmWrwli1bvAFWTJlqlQ2VUhCqVsOFqhTO1evES1wKgfzmFGjoukINIzg48mDDztUGJ4Ir70VELJcYXHDlEshVuFbvrp++/CnXeVu0cEG6WaurA1cuSbjgyiWQtzBvsIhYR0dHJMc2NQglMd8ztVqNPQ5Mw2Q8quJ79Yyw5cuXWwHPrCahOVM2tGfevHlejwIfCjpoU6GQ+PpBylG+CuilkvFGamRN9sVnFevx5YoShxQtWLDA5qNpBeh4Y9SSyLk08UURLuuUMOPN827mSvzxj3+0SVs3b96svs4qhXP1OvES5+o7hZtBoNfGCjVD52kDAggggAACCCCAAAIIINAeAqXWx/HeKehgaa3Q7JmeUMjjhRde8M3qE/5oqokTJ3ptd+7csXSpBUM830v6sUq8+uqr4WZ62kEUS0ocUjR37lyrQQ8Fi1cVTunyvR7hSmyeFyuV0AgjTe/SMKV169Zpcoy9Nm/ebOW12nepA7Pne8NcMnKs53vJsECuXide4rA20i0h0GtjhRTC1LdS+vteAd3ET29Z2Wnnp5UtQwEJ2J/Z4cr4ZvBRCYhlEYMri1JYhs9jqFE2XVuuj2Z+VPaMLV3A/sz+i+H8KSjTZYQrE9PfC8H1d4lM/8KVienvhYxLW3x9/Z3kb/+WHRMUKe+bfvMVmcfkBZ566ilPV5949913VUlk7IkvGNSvX7/EU3i+Ssbb2bdv38SjEjP13HrL14AgGxOUWEyZhw8fVoAmsjcxdqYHyVuxxOZFaohsKhiUPhpLj6uPNyNSSdnNKoVz9TrxEpdtIQWaTaAXokKKBykAaePu0jk02bWyqFB6texFAAEEEEAAAQQQQAABBAorUCq2MnTo0FqZaFCMzd5KHHuis3R1dSWeq1R+YuEWytQ63/7YNUXKnn/++dGjR1v7u7u7lyxZonSp5Y0q62YpyVL5ec9S9hLnrZDyvSXQ6KiQQkJ66l5v9ZbzIoAAAggggAACCCCAAAIFF7h8+XLi+jUaMlMrGQ17sarCp4+FlWsgT2IbfIBPWLjKtJ4jljgExqut91gEBVD8ce9aMikyBkr3yBYV8vbUJFFv4bKXuCa9oJIGCDR0MLk+DL7Kl+KjWmFei3Wpk/ZkQX86oOd0dnY2gIBTIIAAAggggAACCCCAAAJtL+Czn65evZrY2RqOVTlw4IBOoYd8RSIgvqkBMolt8HxvbWKxLJlhDYpApbwiq0pnqTxXGS1NbeW1zrcLeA2+3pPnVJPw+l0yUpvnhz6RMlk2S13iLMdSpqkEGhoV0odBkVH1X2GgCxcuaJl3+/hppKI+ovZ0QCugaZ/6bGjBs6bCojEIIIAAAggggAACCCCAQIsK+IiY9evX6w/2kV5oxEqWVT4iR5XatJCBHvIVKeCT13bv3h3ZZZtqW2J+BZke69G54v2toMIshyQu4ewDoObMmROvZMeOHfHMMCexzrBAmG6YcKlLHDaGdEsINDQq5B8GX+w9bqTQpg0gmj59enwvOQgggAACCCCAAAIIIIAAAhUIKEqiP8/rQD1+Xsse+yO6lKOQUKkFgCo4kRY8tifcv/jii5HDNRpA42WUqdEAWn05slc5dqDKqGRkb95NRcH8XBs2bCh1uByqjxkNGjTI6vfHcoWn8xkz/rgx3ysrW4DJczyRXqcXiyQaI5xyiSPtYbP5BRoaFbpy5YpENIww/RO+Zs0aFdPXQQ1HMDb/laCFCCCAAAIIIIAAAggggEBdBRQMsvq3bt3ap08fPR9dqyDryfFa+1UDhXSnlnh2e5i6QjZ67dmzx8p88cUXlmM/wxjThx9+aGV8QeWwWg/QaPXlESNGqHLt1U+lfT1mLxMeWEFao4SsU5qMosd7KfjllSgSpNDGsmXL5OAzvHxv3sSwYcPsEI112r59u2rWufSyeJPHp4QsLrNSlyWvlVVKnSu9zlJHKd/16iecfolT2sauJhRo6BSt//iP/xDBCy+84BD27MPIE/g0lUwfXUWFvvrqKx/154eQQAABBBBAAAEEEEAAAQQQqEBA4Qkt56ppGTYkJ3xeu4YRaWUPj8uElWuKU3w8iwb7hIXD50d/8MEHOnzp0qWJS4JoiICWf7b1lVXJuHHjwnMprb3pwwgi5VM21d/333/f+qsuWC/sZjPlqAp26b5V45JUv2DDpaPFYn1ZtGiRnd3QwjboisQR1IaydZZqZwOE0y9xqYaR35wCDR0rZKHicASQPfvw3/7t30IdhU7tS+qvf/1rmE8aAQQQQAABBBBAAAEEEECgGgH9DV6xGIVsfJSKwhl6ENCqVav8qVLVBGV0u6f61cKXX365VDsXL16scImN4gnLKEf52htmVplWf7/55hv11+uxm03bFIKCUDV5zJFGUe3duzfeKTuR7oUV/bHFUpRjbVBhZaqF3rZIIr3OSOFws67CWS5x2BjSTS7Q0dPTU78mKr5jMSB9zBQn1uhEeyCfn1Sj5iwsqi8OXyxdY+osgHr37l0Fd3M1r6Oj4+fya3IdVNzCB0ceVOennZ9WXII8PTcuxDKawZURyovxeXSKLInacn0086MsJ23dMj99+ZMa/4vhDf1TEFytK5Cr5by74MolkKuwvbt0CF9f5vbbf/qtJfxmKpdnYmHNbwqH82hCky04HTmF7unCCWKJVdkdn3Zp/pQNlslyN6eaFR/RfCvdDA4ZMqTU3V/kvjKxAVnKaEqXHmp0/fr1fv36dXV16XTxuSnp9UjMppvpwFKtVfNSKtEurT30yCOPaIKYn10N01GJ7fHOxuuM53hhT9REONLrXJfYW0KiaQXqO4Ps0KFDFt+xgXP//M//bBD2sVdaEVPFR/VFoBitQtRakl3rb9k3kcKoKR+zpgWlYQgggAACCCCAAAIIIIBASwiEISEFJuxGzFZoDtuv4IXHL8L8xLQ9XCzj3ZzV7OMDEitUpm4My94bZimjMVB6pYzNKXsuiamGUu30/JTGaJcexu0lLVFZnSln8fprIhzpda5L7C0h0bQCDf2zod6RNkzx7bffNhG9vTZt2mRpTbPUSCL7JlKOrTndtHA0DAEEEEAAAQQQQAABBBBoOQFN17D5HGHLFRLy52S98cYb4a686aefflpxJe7m8rq1UHkucQtdrCxNre9YoXgLFPTROLcwX0vBa/yezSyzfH2JaC2uxPXqwwNJI4AAAggggAACCCCAAAII5BKwpaM1luc3v/mNlnnt7u4+e/asLYSsenQvVnbkTvrptB5IegH2troAl7jVr2Ck/Y2OCtkAtkgjNILu3r17mp+p7yOFqDUQLlIg72bP6joulpS3Mc1cXlP81Dy4Ml4j40IMrowCeYvxecwlBlc+ri9//rb/l2H/kuuowhY+BFeeaw9XHq1/gKsCLh3C11cut4yF9dd6vSKFtSSzz+SI7GITAQTaVaDRUaFSjjZTMct0ylI1kI8AAggggAACCCCAAAIIIJAuoEVhNDPjwIEDNo9MP7XusiZqjBkzhtuxdDr2ItCWAs0SFWpLXDqFAAIIIIAAAggggAACCDSVgGZmaLllvZqqVTQGAQR6S6Chq033Vic5LwIIIIAAAggggAACCCCAAAIIIIBARKBBUaHBgwd35H9pJfxIc9lEAAEEEEAAAQQQQAABBBBAAAEEEKiJQIOiQjVpK5UggAACCCCAAAIIIIAAAggggAACCNRKoD3XFepY21EroPau5+DIg+ogXBmvsnEhBldGgbzF+DzmEqst10czP8p19hYt/L+++l8t2vJeaTZcudjhgiuXQN7CvMHyilEeAQQQyC7QoKjQtWvXWNA++1WhJAIIIIAAAggggAACCCCAQGMEfvjhB3siW2dnp56Onf2kFR+Y/RSURKDeAjne8fVuCvUjgAACCCCAAAIIIIAAAgg0rYCCIFevXr106ZJaOGjQoIwPMvvxxx8PHDigQ8aMGdOcYwUOHTo0e/ZstTDvaIaKD6z5JW5+5Jp3mQprJUBUqFaS1IMAAggggAACCCCAAAIItKHAvn37Dh8+fPLkydu3b3v3Zs6cmTEqdO7cOYu5XLx40Q9vicSZM2d27Nihpm7ZsqV///7N3ObWRW5m1YK0jahQQS403UQAAQQQQAABBBBAAAEEKhGwmE4lR94/5sSJE/p3wIABzzzzTMWV9MqB169f379/v069YcOGJo8KtS5yr1xZThoKEBUKNUgjgAACCCCAAAIIIIAAAggkCDz77LPPP//8Y489tnr16oTdpbN27dqlnTNmzChdpJf3TJ06VXPH1AitK5SrKRUfmOssWQo3P3KWXlCmVwSICvUKOydFAAEEEEAAAQQQQAABBFpDQBETX4b566+/zhUV0iJENu+smaNCD99/VXAxKj6wgnOlHNISyCntZ1fvChAV6l1/zo4AAggggAACCCCAAAIINFpAwZ3Lly9//PHHo0eP1sSu4cOH69lbpZ6oVc0S0adOnbK+6USWiJxFD//66quvNAHq0Ucffe6550aOHKlQSwqHr3itpY6mTJmixg8ZMiTlEPX07Nmz3d3d+qnlrnUWrZMdOUukSTq7Fm++cePGlStXrCWyCpvkMbL4gWExpbO3NlKVNs+fP2/zwkaNGjV+/PiUPsaRI81gE4EUgfpGhZpnQF0KAbsQQAABBBBAAAEEEEAAgYIIKN6hVXLi431Onz6tZXQqexRXCt3u3bu1V0tT+xPfw+d27dmzJ9ISLT/0ySeflFqBSOteh4sc2aI/qv/IkSOTJk2KNEM9nTt3rpfR3jC9d+/eWbNm2SFhkywEppDQ4MGDvcLJkyd7Wgl/VFn8wLBYrtaGVSkIFTmjqk3so50ujhw2gzQC6QK/SN9d5V6FM/Wh0su/AqqskMMRQAABBBBAAAEEEEAAAQQqFnjllVfCQMyECROsqnHjxr3zzjsVV5t4oMYB2XPH5syZEy8wf/58b4kWLbICmm6mtB7+FS+/bNmyMCTkh6ikYijaGznkwIEDHgZSsEmRKb3CoyLla7uZt7V+drF4SEjN9nxlatyTb3oiHdmLkUCglEB9o0Klzko+AggggAACCCCAAAIIIIBAgwWOHj16/PhxO+natWvv3r177NgxjXxRuESZvqtWrVLlVpUmQMXrtNNZMy5cuKDBSh6ymT59ukb6hIcoTrR161bLUWvVZh3iLVe+9mp5nfCQjRs3alN1qpu3bt3SyB29dJQ2Ne5G88jCwpG0Rjb09PRoPJHl60Ta9Jf2RspHNitordcgFgWDtm3bZs0O+7hy5Uov5ol0ZC9GAoFSAkSFSsmQjwACCCCAAAIIIIAAAgi0j4DiLL///e+tP4o1rFq1ypaqUYxD4RKPgNSwwzb4SMORSq2J8+2333ozxo4dq5DN0qVL1QCNGNJIn7AlCxcutE0FdNRai8tYy5Vju8IRSYrL2DClnTt3Rs6uTU030+nC+mubztvayNnV8sWLF/vV0Tw7K6ChT5FgmfLLIkcqZxOBiEB91xWKnKxhmwdHHmzYudrgRHDlvYiI5RKDC65cArkK1+rd9dOXP+U6b4sWLkg3a3V14MolCRdcuQTyFuYNFhHr6OiI5NimRrIk5num1sqxx4FprE18tIueEbZ8+XIr4IdUk9B6yTYaaN68eYn1qBn9+/eP7NKaRzYmSCN9fN0fzZyyEI8G/sTXD1KO8lVAL5WMdE2LJdU1ABRpvzaraa0OV18iLFqPRZE1w9RFDDtYFjnePHIQiAgwVigCwiYCCCCAAAIIIIAAAggg0HoCChCkN/rmzZtWQI/uipdU6OGFF16I51ec4w/GmjhxYmIlixYtiudrgIwtdaQQj++9c+eOpVesWOGZYcLzvaQiQbYoj5Yi0hI/GjoUH2UT1lDDtLfBWxWp3PO9ZFhA6wqFm5b2yFrkkLLI8arIQSAiQFQoAsImAggggAACCCCAAAIIINB6ApF5UvEOaNSMZZZ6wtdTTz0VP6rinHfffVfHxke+eIVPPPGEp8OEj5TxOJcvGNSvX7+wpKc930tq14IFC6yABh9pLe0HH3xQg4+0spJX64fXNuFt8FZF6vd8LxkWSIzZjRkzxspEDimLHNZMGoFEgfacQTbt/LTE3pIZEbDJF3BFWEpt+lwVxEoRhflwhRpZ0nwesyh5mdpyfTTzI6+5LRM2+eIXw/lTUKbLC1cmpr8XguvvEpn+hSsT098LGZe2+Pr6O8nf/i07UyxSPr7Zt2/feKZyhg4dmphfQaYG5tjzvxJHvqRX6FEhPV0rEurq6upKPDYxXysWqUeaiebDjtQka5XWcn7ttdfq/aTsxFap/aXyE7uWklkNckq17CqaAL8gFu2K018EEEAAAQQQQAABBBAotMDly5cT+3/48OHE/Aoyz507Z0clPn0svUIFg6xAZ2dnpOTZs2cjObZZKl+Dg7SCtda01lrato61lV+yZIm3MLHCmmSWalWp/Lwn9S5UgJz3XJRvYwGiQm18cekaAggggAACCCCAAAIIIPA3AZ+FdPXq1UQUD8ck7s2VaU8Q08o+pWarqbZSwSlvho/l8Uq6u7sTm+H53sewmAYfKTy0ZcuWe/fuaZSQ7VqzZk1YpobpKlubvSVZkLPXRsnCChAVKuylp+MIIIAAAggggAACCCBQIAGfjbV+/fr40st6cpY95aomIhaw8JV9Euu0NXEiu7wZtua07fUpb7t3746Ut031KDE/kqkwk574rqWOlK/OZl9gKLLGc6TayGatWhupNr6ZBTl+FDkIRASICkVA2EQAAQQQQAABBBBAAAEE2lBAQ2bWrl2rjunx83oIfRgTUSymggWAShlpRWR7wv2LL75YqozytcRPZO1kxao2b95sh/hTt7SpZ7HrMfZKaIWgffv2WQH/qRw7ncr4U9vD3nnJMKFxTA899FCYE08PGjTIMv1RX/Ey8ZwKWhuvpGxORuSy9VAAAaJCvAcQQAABBBBAAAEEEEAAgUIIKBhk/dRjufr06bNu3To9k0tPjh88eLDGztij3OMQeqy7Ii/22rNnjxX44osv/p73879hFObDDz+0MqNHj47XFuZo2I7mdikmpXiQKhk4cKAapgKWH5bcsGGDbepJ8yNGjFCTtKmfSivHdnkZbR46dEi7VKfPR1Om0uqyLT69adMmn6Fmh8d/Dhs2zDI1Fmn79u0KxKip1tp44TDHW5KxteGxGdPZkTNWSLHCCrTnM8gKeznpOAIIIIAAAggggAACCCBQSkCTyE6fPj19+nQbXLN69WovqWFEemKXR1g8X4kdO3bYo7vCTMVWwsLXrl3zGWoffPCBSmp15/Swi86oBvz8VLD9+8OaFZyKTy7TABwtCaRVolVSp9aT5sNDlNZeHyhku8IWKsxkwSDbpVPMmDEjUkN8U6OrNP5IzROXndrKqLORc0WOraC1kRrKbmZELlsPBRBgrBDvAQQQQAABBBBAAAEEEECgKAJjx45VfEQhGwVKrM8KfBw5ckTPcfdnWqWHPNKlNB7H4i8vv/xyesm5c+cqRBUpY+EbX7A53KslgRSOiQ9oUo7ytTcsrMlf3kHlhyEh9ffTTz9Nj1h5VRobpeeXxU/qBUolcrW2VCWl8rMjl6qBfARcgLFCTkECAQQQQAABBBBAAAEEEGh/AQ2B0QO51E/N2wqDI6UeCqbCPiWqlI4/Rf69996zMlkel64QVU9Pj2Icn3322SOPPKIZW2pbqVMoX+GqW7duqbwG72g+l4JHQ4YM8TFK4YGqWc+k17w2Fb558+b169e1V08oU+H4KaZOnaq4kgp4L7wq+WiOm17KsdrCYikHqlj21qpwelVqmLXQGp8LWZXzQiBFgKhQCg67EEAAAQQQQAABBBBAAIG2FQhDQloux55BpqE0kQ4rEmHBiEh+4qY9JkxPEEsM1iQeosonTZqUuCsx835z+ieOJ4qUVxv0UnRGQaLIrnDTioU5iel4sXhO/MCMrU2vSldKvfDKK0D2Y0kgEBEgKhQBYRMBBBBAAAEEEEAAAQQQaFsBrdAcH5KjkJDGqlif33jjjWo6//T916JFi6qphGPTBUBO92FvLgGiQrm4KIwAAggggAACCCCAAAIItLCALR2tsTy/+c1vtLx0d3f32bNnfb1nDRTKMgYnpf967FfKXnbVRADkmjBSiQm0Z1SoZ3UPFziLgJ7XqGJwZbFSGeNCDK6MAnmL8XnMJQZXPq4vf/62/5dh/5LrqMIWPgRXnmsPVx6tf4CrAi4dwtdXLreMhTVZzOaLheW1BLWe1x7mkEYAgbYXaM+oUNtfNjqIAAIIIIAAAggggAACCFQgoCVpNL3rwIEDWoZZh+tnV1fX6NGjtRJzuHJNBTVzCAIItKIAUaFWvGq0GQEEEEAAAQQQQAABBBCoRECrGmvpZb0qObgWx/gjvWpRGXUggEC1Ar+otgKORwABBBBAAAEEEEAAAQQQQAABBBBoQQGiQi140WgyAggggAACCCCAAAIIIIAAAgggULUAUaGqCakAAQQQQAABBBBAAAEEEEAAAQQQaEEBokIteNFoMgIIIIAAAggggAACCCCAAAIIIFC1AFGhqgmpAAEEEEAAAQQQQAABBBBAAAEEEGhBAaJCLXjRaDICCCCAAAIIIIAAAggggAACCCBQtQBRoaoJqQABBBBAAAEEEEAAAQQQQAABBBBoQQGiQi140WgyAggggAACCCCAAAIIIIAAAgggULUAUaGqCakAAQQQQAABBBBAAAEEEEAAAQQQaEEBokIteNFoMgIIIIAAAggggAACCCCAAAIIIFC1AFGhqgmpAAEEEEAAAQQQQAABBBBAAAEEEGhBAaJCLXjRaDICCCCAAAIIIIAAAggggAACCCBQtQBRoaoJqQABBBBAAAEEEEAAAQQQQAABBBBoQQGiQi140WgyAggggAACCCCAAAIIIIAAAgggULUAUaGqCakAAQQQQAABBBBAAAEEEEAAAQQQaEGBB1qwzeWb3NHRUb4QJRBAAAEEEEAAAQQQQAABBBBAAIECCzBWqMAXn64jgAACCCCAAAIIIIAAAggggECBBYgKFfji03UEEEAAAQQQQAABBBBAAAEEECiwQHvOIOvp6SnwNc3RdZtqB1dGMp+ZiFgWMbiyKIVl+DyGGmXTcJUlCgvAFWqUTcNVligsAFeoUTYNV1misIBxKYdfvUIW0ggggEBtBRgrVFtPakMAAQQQQAABBBBAAAEEEEAAAQRaQ4CoUGtcJ1qJAAIIIIAAAggggAACCCCAAAII1FaAqFBtPakNAQQQQAABBBBAAAEEEEAAAQQQaA0BokKtcZ1oJQIIIIAAAggggAACCCCAAAIIIFBbAaJCtfWkNgQQQAABBBBAAAEEEEAAAQQQQKA1BIgKtcZ1opUIIIAAAggggAACCCCAAAIIIIBAbQWICtXWk9oQQAABBBBAAAEEEEAAAQQQQACB1hBot6hQT0/PvXv3WsO+CVoJV66LYFz6meuowhaGK++l13cX767saHBlt1JJuHJx2ddXrkOKXBiuXFcfrgq4+M8xFxqFEUAAgbwCHXzP5iWjPAIIIIAAAggggAACCCCAAAIIINAGAu02VqgNLgldQAABBBBAAAEEEEAAAQQQQAABBBogQFSoAcicAgEEEEAAAQQQQAABBBBAAAEEEGg6AaJCTXdJaBACCCCAAAIIIIAAAggggAACCCDQAAGiQg1A5hQIIIAAAggggAACCCCAAAIIIIBA0wkQFWq6S0KDEEAAAQQQQAABBBBAAAEEEEAAgQYIEBVqADKnQAABBBBAAAEEEEAAAQQQQAABBJpOgKhQ010SGoQAAggggAACCCCAAAIIIIAAAgg0QOCBBpyjMaf4+uuvz549e+7cuccee+zFF18cNmxY//79G3PqVjzLDz/8cPXq1UuXLqnxgwYNGjt2bCv2ogFt/u67744dO6YTHT58WO+o0aNHi0s/H3igfT47tWL88ccfb9y4oY9hd3e3fqraMWPGPProo/r55JNP1uosbVyPv9nUx6lTpz788MNt3Nm8Xdu3b1/6IbNmzUovUOS9emt99dVXf/7zn/XBtO+xZ+6/imwS9v3MmTPXr18PcxLTfJVFWPSLxKFDh+wL395X/fr1e+mll/j/MQJlm+I6deqUfvXSx1DvpfHjxw8ZMoTv+cp+HeV3/sT3GJkIIIBA5QI9rf+6d+/ehAkT4gRr165t/c7VuAd79+6dOXPmgAEDQi7l1Pg0bVHdtm3bnn322RDK0wI8cuRIW/SyZp3QW8t94gm9x7799tuanawdK9L3WPh+u3btWjv2svI+xd9UkZzKq27rI0v9/yg9vvn9yosi8nZK3NS3nB9S8ITeV/oVK1FJ/z9evHix4D7x7pf6L/L06dPxwkXIqfjX0VLfafzOX4S3DX1EAIH6CbT8DDL9CfR//I//cfz4cfvtROEhv7NavXr1unXrEn9rKWzm7Nmz9+/ff/v27cIKZO/4kiVL9Kutlw9DaQKcPHly2cELfmwBE/4xtL7rXafPpgYTFZAiY5ffeuut8P2W8SiKIZAioP8fBw4c6P8/qmTkg5lyLLviAhrfEc8sZs7y5cv1K5b3XV/v/l+k/n/U20zDr3wvCY1k1G9f7hB+DMeNG3f06FHfVZxEZb+O8jt/cd4h9BQBBBos0PJRoWXLltmtlH4p0R8QNNnnwoUL+jO7/YKi31r41ST+ltJvJEuXLi31h754+SLnSElvJ721bt26pZ/6s57/VVm/09gUvCL7eN81sU5W8rl7967C2PoY6qfo/A+k+pzqRsLLkwgFNBheUUjl+J1VuJe0C+h7Xm+qxJeXIWECmpfx+OOP298AzM0/mPqQarQjMQ5/q2zZsiXxTaVMDRq1Yvp/k5mwRqFfq7Zu3WppfcPr7aRfvfRfpL7k/f/H6dOnO2/BE+LS30UMQf9Likv/P+qn/w6mPzIp2FFMpby/jvI7fzHfJ/QaAQQaIVC/YUgNqFn/rZqRbqV0xx6eUXentku/DYf5BU/rd1yHUtqImEeQ+K7QXZPeYIm7/NZdNwyJBcgMBfx3X/3+F+aTNgF9JCWjD6O+rDyIpo8nPqEAX1ahRpa0f+6UyFKeMokC+guKvff02UwsUMBMj5TFf7/y38qExpeYvTdSfmFwyQJ+SCv4ddTfXfzOX8CvHbqMAAL1FmjtsULvvPOO/br25ptvRlY31PLJdqOlwfOF/SOM4YQ/9afOCFS4l3QoMGnSpFLLQG7atMlK2prK4VGk4wI+RIgZUnEc5fjcMeYkJvqQWYGABgrZBB/dPq1cubKCGjhEAmL0QTFaAB4TE/D/+NasWRMx0X+aPlzo8uXLkb0F3NS8aZ+z/7vf/S4i4Dn6tBZthnUFv47yO3/k/cMmAgggUEOB1o4K7d692yz8f9aQZv78+bZpz5AKd5FGoBoBn3nxxRdfVFNPQY71sKwFagvS64zdFI7NHdMfjXlsYkY0ipUV8Mi1EvwloCxXqQJ6wJbt0oihUn8kKHVsG+f7/4CJD27z/xb/+Z//uY0RMnZNz+W0kvrvL/4Nrxz/b/GTTz7JWGdhi/E7f2EvPR1HAIEGCLR2VMiHHsT/r5WdnvppgleuXGkAJacojoD/CfT5558vTq8r7umePXvs2BUrVlRcSbseaM9T143Ba6+91q59rGG/FETTIh0aVKWXFmPSUI4aVt5OVf3lL3+x7tgNvKC0CJrQ9NOjtO3U3zr1ZePGjVbzH/7whzqdohWr9b/DuY/3Qp9K+8UsMQjixQqYePrppxN77fnff/99YgEyXYDf+Z2CBAIIIFBzgdaOChmHz9mO6PTt29dy/PfjSAE2EahMYPPmzXbgyy+/XFkNRThKN596tIqiHj6ThSkYkeuuu3R7PpSGJDCgI4KTuCkuPbJHC73rNXjw4D59+ugNRpgjbuXjNTo7OydOnCgo3aULTT+1BLVyQIujRXIUQbO7UP2O8cwzz0T2FnlTf4fTikISkI8+gArUavaTIo/6wvcvef4GEHmHaMHp+Bwx5fhC1N3d3ZFD2EwU4Hf+RBYyEUAAgSoFWjgqpD9JWedfeOGFKhU4HIHsAtu3b7c7ed1fvfTSS9kPLEhJRTo67r9086lHq9ivvJoe9c033zAFI3wP6LZcd+nK0TqjPNsolMmV1htM77RiPto5Bcr/qP7KK6/Y91VYWDlC4xGKoUk8/eGHH1qmFi6M7y14jibma/lt3Z/rA6hA7YMPPqjIo77w9cbT/4xaSNhGQRZcSd0Pv9vPnTsXAQlzfLWmSBk2TYDf+XknIIAAAnUVaOGoUFkX/8/Y/xRT9hAKIJAuoPsoWwVGxRjfkW7le3XnMGTIEMbCOIgl7K5JOCwGHJFJ3NStpmKLutv89ttv9SQaPSLQRitY4SI/2jnOFY4DspCQlsURndxk6H9pV1A7PnghXlsxcyRjgxzV/Xnz5hUTIb3XM2bMSPyb3B//+Ef/7Su9hoLs9eW3d+zYEX7ilFZOQRAa0E1/1/E7fwO0OQUCCLSfQDtHhfxq+S/BnkMCgQoEdK/lg4N0c+W/glRQVRsfonVM9DdkvTQExj56egKLbtpHjBgR3qy2sUCWrvncMa0wSrwsi9iFCxcWL16sD51mr2jQmR4RqNEKCnMoWmSHMzbBGf/7f//vnlZCwze2bNkiOrnJUKP2/IN54MCBsCRpF/ClfxV8ZJCjs3hC32ADBw7022+FHT1Ka9/2PrLDDylsQp8+67u4NKhq3bp1wtHPELCwOPXoOL/z10OVOhFAoO0FWjgqVPYXNf+lJPHPWW1/aelgbQUU0dD9pz1iVvEO3VzVtv62qU03n7o/12vVqlW3bt3SyA77S6luTf/n//yfbdPNajqi95LNHZMM65VUI6n/BXz5kvg8qWpqbuljw/8cdYMUeY8pCrlgwQLr4OHDh1u6p/VrvC8eF3/4ev1O2io1a8ysvsH0v6H+Tzx9+vS9e/cU+LAorf4eoF7o2/7Xv/51q3Sn3u1UIFtjG/0sGoOmNdH003+dsF2JT03xo0iEX2uJGvzOn8hCJgIIIJBRoIWjQv4/6MmTJzP2lmIIVCYQCQkp3lFZPQU8Sp9T/0vp1q1bw/HzBdSwLnt0bNGiRfpFNnz5AxP1nDvLRyz9feKr26qYxNILF3CvB4DCvr/66qu2yf+eIYun9YVvQUbF1EaPHu35JEzAV1xSTHbs2LE+2lH37fp7gA3fU8hDq1AjZgIa26g/kGhEVQii0VWKqQ0dOtQyeaeFOPE0v/PHTchBAAEEaijQwlEhV7C/t/imJ+7cuWNpezSv55NAIJcAIaFcXPHC+mXOF1YIF9eMlyxIjt5R1lOt0qo/GocvX8pEszAs/8aNGwVhqaybuhH1d9fNmzcrq6T9jnKTF198Md47Hz1U6n/P+CGFytm1a5f1VzE1D3kUSiCls4pT+9dUGJP1Q7SukKWZn+gmStgfSHp6ejTvVYt8KaHRVYqp+V8CBg0aFJYnXUqg1LcWv/OXEiMfAQQQyCLQ2lEhn8ee+CwV/3OWVrrNYkEZBOIChITiJhXkPPXUU3bU9evXKzicQxAoJaDnYfviJk888USpYkXL97+rnzhxIt53/x/TV2WKlylyjkeF5s6dW2SHxL57nFoDqRIn9XR1ddmB//Zv/5ZYQ8EzheaLEirE5m+2kSNHFlymbPf5nb8sEQUQQACBigVaOyr0+uuvW889ABRC+P+148ePD/NJI5BRgJBQRqj0Yrpv978t+yCF9EPae6+m1OlvxYkvLVllfdc6FFags7OzvTWq7J0eBeg1+L2W5xQ28Yc//MH67v8PhhT+P+bTTz8d5pOWgOY92WAEhcx4R8XfEm4iJQ8vhsX27Nljm7y7QpbEtIZT2ZtN3/yJIbbEowqbye/8hb30dBwBBBog0NpRIX8glH7x9UkZpqYHZNj/tZrIzf+1DXgntd8pwpCQ3kWsJZR+iSMfwLDwO++845sM3BOFxnHozirx5WtM6O/tVoAJLBIr9e5SwHHjxo327vI/I/ubrcgJhV99eZf4rbuHiubMmVNkpcS++8PCfSZUYrEiZ/oQMw8vukY4+GXKlCmeTyIuoA/m8uXLLd8T8WLkuAC/8zsFCQQQQKDmAg/UvMZGVqj7Jf2BxR7loF9T9CjZ4cOH/+d//uepU6fsET9qjP9toZENa9pz6a+gPoXHZ7N/8cUXCqJ5m7VSAHE0aegdZYFFpX/5y1+GRG6lhBbXDDcLm3788cclpvsohTP0/lHgQ0v/ap6/cnyCD38OLezbo8qOR95devK6vuT1lKjwuWOlPqFVnrp1D9dHT6tTqf36YOqjp8lQ+lRqaJXuP+2bTfl+l9W63axty8MJiYwyLmWrRabtVyz99vUf//EfM2bM0ErJ//f//t/33ntv9+7d9u7S/LKJEyeWqqFo+f/4j//45ptvKkym/xz19XX16lV9gy1ZssQctm3bVsBfuir4dZTf+Yv2waG/CCDQUAGteNfSLz0S1ZfVjMPp+Q4t3buaNz7FyvU0b6Xm523FCh0kPdGKXatHm9OVtFdDOepx3jar057rLC4+huGVLfvu0oS7sDxpE9DdZik63bTzHou/T/wDqPGh8b3kuEDZ3yX4SLqVEqU+hsrXWy4sWZx02beQcOLfUfzOX5x3CD1FAIEGC7T2DDL9n6E/HehPxPHfffUrr0JCer5Dyn/G7EIAgVoJaDCChh4k1qZ8fRj1vJXEvWQiUFYg5f5Bu/RMHz34uWwlBSywePFiffT0v2Gk70LTWFFNUYzks+kTEn1hJkwSBfR7l8IZ8beWCuvdpZt5PpKhW+J/jsq8ePEiw41DqLJpfucvS0QBBBBAoDKBDkWhKjuyCY/SjJXLly8/8sgjepRDAYfjZrkiWp5DI+TTS2p1W/2/m16mCHv1dsrSTe6sQiV7g+lj+P333+s5u3omlD6J/jiksCTpRAF9PG0NHT6GcR+bk2ir5Ni7C6W4UmKO3lRfffWVpg+PGTNGn0f+f0xUUqZ/7fPFXoooku+fyn79+vn04UgZNiVg3+1nz55VWh9Dvruq/3VU7z1+5+fDhQACCNRKoK2iQrVCoR4EEEAAAQQQQAABBBBAAAEEEECg7QVafgZZ218hOogAAggggAACCCCAAAIIIIAAAgjUQ4CoUD1UqRMBBBBAAAEEEEAAAQQQQAABBBBodgGiQs1+hWgfAggggAACCCCAAAIIIIAAAgggUA8BokL1UKVOBBBAAAEEEEAAAQQQQAABBBBAoNkFiAo1+xWifQgggAACCCCAAAIIIIAAAggggEA9BIgK1UOVOhFAAAEEEEAAAQQQQAABBBBAAIFmFyAq1OxXiPYhgAACCCCAAAIIIIAAAggggAAC9RAgKlQPVepEAAEEEEAAAQQQQAABBBBAAAEEml2AqFCzXyHahwACCCCAAAIIIIAAAggggAACCNRDgKhQPVSpEwEEEEAAAQQQQAABBBBAAAEEEGh2AaJCzX6FaB8CCCCAAAIIIIAAAggggAACCCBQDwGiQvVQpU4EEEAAAQQQQAABBBBAAAEEEECg2QWICjX7FaJ9CCCAAAIIIIAAAggggAACCCCAQD0EiArVQ5U6EUAAAQQQQAABBBBAAAEEEEAAgWYXeKDZG0j7EEAAAQQQyCbwww8/fPfddyrb2dn5wAMt8x+c2qyWh12suP0u4LX179//4Ycf9k0SCCCAAAIIIIAAAgiEAh09PT3hNmkEEEAAAQR6V0ChjUOHDuVtw9SpU3XU7NmzdeC1a9eefPLJvDX0VvlZs2bt378/PHvF7d+3b58JeG179+5V/b5JAgEEEEAAAQQQQACBUKBl/pQaNpo0AggggEAbC2jsTCS0kaWziqRkKUYZBBBAAAEEEEAAAQQQcAHWFXIKEggggAACCPSmgEbv2qvigU4aFmQ1ECPrzQvJuRFAAAEEEEAAgdYRYKxQ61wrWooAAggUQ0Cr6iQGNQYPHmwAiXt1lCaR2S6li0FFLxFAAAEEEEAAAQQQqEqAqFBVfByMAAIIIFBzAS0UnT5YptReHcjKyjW/HFSIAAIIIIAAAggg0MYCRIXa+OLSNQQQQKBYAv4ErsgzvCL52jx//vyJEyceffTRKVOmRGJMvvfFF18cO3ZsuuCPP/5448aNy5cvf/755yo5atSorq6uSIXpNWTf+/XXX589e7a7u1s/x4wZo8YPGjRo5MiRBMKyG1ISAQQQQAABBBBAICJAVCgCwiYCCCCAQKsKlHoGWZi/Z8+e1atXew+XLFkyYMCAK1euKLaiEM8rr7xy/Phx26ti2rVp06YZM2YkPudeYRrNWbt48aLXZomZM2fqLImHREpm3FTD5s6dGz6nLEzzlLGMjBRDAAEEEEAAAQQQiAuw2nTchBwEEEAAgfYUmD9/voeEnn32Wevk7du3p02bpvSGDRssJKRgkF7K0S49DU0RGSsZ/tQz4LXOkYeEVJsdojIK2QwcOFBjjsLy1aQPHDjgYSCdRVEnvbz91dTMsQgggAACCCCAAAIFFyAqVPA3AN1HAAEECiSgoI+iKhpcc/fu3QsXLpw+fdpiK8ofMWKEAkbaPHLkyDf3X0pYoEcRGQ0LCpm+++47RYuUowJr165VbEi13bp1SxUqXqN8hZM0yCg8pJr0xo0bdbjapmbrLApI6aUzalON1DyyairnWAQQQAABBBBAAIEiCxAVKvLVp+8IIIBA4QQ0WUyPb7e1eLRs0M6dO41AkR2FeBRqmTRpkiZ/6aXEm2++aXu1lE8otWzZMttU6GfVqlXPPPOMbapCxWsslqQYk4JH4VGVpc+cOWMjktTUyBJC2lQjyy5+VNl5OQoBBBBAAAEEEECgCAJEhYpwlekjAggggMDPAhMmTIgEVrRas9MsWLDA05YYP368JQ4fPuy7FOvx+VxaV8jzPeH1fPbZZ55ZfeL69evVV0INCCCAAAIIIIAAAgiEAkSFQg3SCCCAAALtLPD6669HuqcgkS/Q8+qrr0b2Dh8+PJKjTV8wSHPHIjEmK+zrEH3//ffxw/PmaCiQDT7SnDWNUdLQIS0+nbcSyiOAAAIIIIAAAgggkChAVCiRhUwEEEAAgTYU0GPj4716+umnLdMngnkZzSPztCd8NpnmiHUkvbQKtRUORxj54RUkfPDR1q1bx40b9+CDD2oS3NGjRz0+VUGdHIIAAggggAACCCCAgASICvE2QAABBBBAoKkFtHSRVsj2MU1qq6awTZ48uU+fPtu3b2foUFNfPBqHAAIIIIAAAgg0t0DCX0Gbu8G0DgEEEEAAgaYQ2LZt25QpU1Kakji/LKV8yi4NDtJLSxodO3bs3LlzGjRkhZcsWfLcc8+x4HQKHbsQQAABBBBAAAEEUgSICqXgsAsBBBBAAIGowJgxYzzrySef9HQDEv3797fwkJ599tZbbykkpJOuWbNGoaIGnJ1TIIAAAggggAACCLSfADPI2u+a0iMEEEAAgToKKDRjte/evbu3Zm9pwaPFixfbnLLjx4+zwFAdrzdVI4AAAggggAACbS1AVKitLy+dQwABBBCotYDmhc2cOVO1Xrx4ccOGDaWqV6SmJjGjshEfPaHsoYceKtUM8hFAAAEEEEAAAQQQSBEgKpSCwy4EEEAAAQQSBDRKyJ4Wr8eQaUrX119/7YUUCbp06ZIeIa+loG/cuOH5FScOHTo0YsSIffv2aVEhr0TpdevWKSylHM0mS3xWmhcmgQACCCCAAAIIIIBAKQHWFSolQz4CCCCAAALJAhou9P7770+fPv327dt6HJheKqc4kTaTD6guV9Gf2bNnWx2aNWbBINvUSWfMmFFd9RyNAAIIIIAAAgggUFwBxgoV99rTcwQQQACBigX02K9vvvlm6dKlXkMYElLsRk8o6+zs9L0VJwYNGhQ+kz4MCWki26effspAoYptORABBBBAAAEEEECgo6enBwUEEEAAAQSaX8AnapV68peW4LFpVgrHhLGSUvnWZR1ia/ckVmsn1eAgX2Q6DqUyN2/evH79er9+/bq6utILxw/XHDQbbZTyP7J1wc6iGvQctPSzqEmDBw9Wyb1796r++EnJQQABBBBAAAEEEEBAAswg422AAAIIINAaAolRm7DpCpToFeZYulS+7VW4JyXiU/akqkRl9NLoofipc+Vo8SArP3Xq1EhHrAtlz6Jg0NmzZ1XJlStXcp2awggggAACCCCAAALFFCAqVMzrTq8RQAABBJpOwBcPunbtWiQqlLGtCgl5JRkPoRgCCCCAAAIIIIBAkQWIChX56tN3BBBAAIHeF9B0sEgjKgsJqRItQqTFhsLalBNukkYAAQQQQAABBBBAIBRgXaFQgzQCCCCAAAIIIIAAAggggAACCCBQFAGeQVaUK00/EUAAAQQQQAABBBBAAAEEEEAAgVCAqFCoQRoBBBBAAAEEEEAAAQQQQAABBBAoigBRoaJcafqJAAIIIIAAAggggAACCCCAAAIIhAJEhUIN0ggggAACCCCAAAIIIIAAAggggEBRBIgKFeVK008EEEAAAQQQQAABBBBAAAEEEEAgFCAqFGqQRgABBBBAAAEEEEAAAQQQQAABBIoiQFSoKFeafiKAAAIIIIAAAggggAACCCCAAAKhAFGhUIM0AggggAACCCCAAAIIIIAAAgggUBQBokJFudL0EwEEEEAAAQQQQAABBBBAAAEEEAgFiAqFGqQRQAABBBBAAAEEEEAAAQQQQACBoggQFSrKlaafCCCAAAIIIIAAAggggAACCCCAQChAVCjUII0AAggggAACCCCAAAIIIIAAAggURYCoUFGuNP1EAAEEEEAAAQQQQAABBBBAAAEEQgGiQqEGaQQQQAABBBBAAAEEEEAAAQQQQKAoAkSFinKl6ScCCCCAAAIIIIAAAggggAACCCAQChAVCjVII4AAAggggAACCCCAAAIIIIAAAkURICpUlCtNPxFAAAEEEEAAAQQQQAABBBBAAIFQgKhQqEEaAQQQQAABBBBAAAEEEEAAAQQQKIoAUaGiXGn6iQACCCCAAAIIIIAAAggggAACCIQCRIVCDdIIIIAAAggggAACCCCAAAIIIIBAUQSIChXlStNPBBBAAAEEEEAAAQQQQAABBBBAIBQgKhRqkEYAAQQQQAABBBBAAAEEEEAAAQSKIkBUqChXmn4igAACCCCAAAIIIIAAAggggAACoQBRoVCDNAIIIIAAAggggAACCCCAAAIIIFAUAaJCRbnS9BMBBBBAAAEEEEAAAQQQQAABBBAIBYgKhRqkEUAAAQQQQAABBBBAAAEEEEAAgaIIEBUqypWmnwgggAACCCCAAAIIIIAAAggggEAoQFQo1CCNAAIIIIAAAggggAACCCCAAAIIFEWAqFBRrjT9RAABBBBAAAEEEEAAAQQQQAABBEIBokKhBmkEEEAAAQQQQAABBBBAAAEEEECgKAJEhYpypeknAggggAACCCCAAAIIIIAAAgggEAoQFQo1SCOAAAIIIIAAAggggAACCCCAAAJFESAqVJQrTT8RQAABBBBAAAEEEEAAAQQQQACBUICoUKhBGgEEEEAAAQQQQAABBBBAAAEEECiKwP8HxMbV5r4Kj/IAAAAASUVORK5CYII=", + "image/jpeg": "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" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "from IPython.display import display\n", + "from pdf2image import convert_from_path\n", + "import os\n", + "import glob\n", + "\n", + "folder_path = '../tmp/gantt_charts'\n", + "files = glob.glob((os.path.join(folder_path, '*')))\n", + "latest_file = max(files, key=os.path.getmtime)\n", + "images = convert_from_path(latest_file)\n", + "print(latest_file)\n", + "display(images[0])" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "markdown", + "source": [ + "This can be utilized for arbitrary complex goals." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } } ], "metadata": { From 26e5c0709d67d5cae2e38b3c9fa8936c428a4b21 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 13 Aug 2024 13:54:07 +0200 Subject: [PATCH 26/43] added complex monitor sequence --- scripts/giskard_examples.ipynb | 244 ++++++++++++++++++++++++++++----- 1 file changed, 206 insertions(+), 38 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index b982f0372f..f4810c2c5f 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -12,7 +12,13 @@ "from giskardpy.goals.weight_scaling_goals import MaxManipulabilityLinWeight, BaseArmWeightScaling\n", "from copy import deepcopy\n", "from giskard_msgs.msg import WorldBody, CollisionEntry, WorldGoal, GiskardError\n", - "import numpy as np" + "import numpy as np\n", + "from giskardpy.goals.joint_goals import JointPositionList\n", + "from giskardpy.monitors.joint_monitors import JointGoalReached\n", + "from IPython.display import display, Image\n", + "from pdf2image import convert_from_path\n", + "import os\n", + "import glob" ], "metadata": { "collapsed": false, @@ -52,9 +58,10 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 45, "outputs": [], "source": [ + "# Define some helper functions\n", "def reset_giskard():\n", " gs.clear_motion_goals_and_monitors()\n", " gs.world.clear()\n", @@ -88,7 +95,24 @@ " gs.motion_goals.allow_all_collisions()\n", " gs.monitors.add_end_motion(start_condition=f'{done} and {done2}')\n", " gs.execute()\n", - " gs.clear_motion_goals_and_monitors()\n" + " gs.clear_motion_goals_and_monitors()\n", + "\n", + "\n", + "def visualize_last_task_graph():\n", + " folder_path = '../tmp/task_graphs'\n", + " files = glob.glob((os.path.join(folder_path, '*')))\n", + " latest_file = max(files, key=os.path.getmtime)\n", + " print(latest_file)\n", + " display(Image(filename=latest_file))\n", + "\n", + "\n", + "def visualize_last_gant_diagram():\n", + " folder_path = '../tmp/gantt_charts'\n", + " files = glob.glob((os.path.join(folder_path, '*')))\n", + " latest_file = max(files, key=os.path.getmtime)\n", + " images = convert_from_path(latest_file)\n", + " print(latest_file)\n", + " display(images[0])" ], "metadata": { "collapsed": false, @@ -962,34 +986,22 @@ }, { "cell_type": "code", - "execution_count": 42, + "execution_count": 44, "outputs": [ { - "name": "stdout", - "output_type": "stream", - "text": [ - "../tmp/task_graphs/goal_33.png\n" + "ename": "NameError", + "evalue": "name 'visualize_last_task_graph' is not defined", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mNameError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[44], line 1\u001B[0m\n\u001B[0;32m----> 1\u001B[0m \u001B[43mvisualize_last_task_graph\u001B[49m()\n", + "\u001B[0;31mNameError\u001B[0m: name 'visualize_last_task_graph' is not defined" ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": "" - }, - "metadata": {}, - "output_type": "display_data" } ], "source": [ - "from IPython.display import Image, display\n", - "import os\n", - "import glob\n", - "\n", - "folder_path = '../tmp/task_graphs'\n", - "files = glob.glob((os.path.join(folder_path, '*')))\n", - "latest_file = max(files, key=os.path.getmtime)\n", - "print(latest_file)\n", - "display(Image(filename=latest_file))" + "visualize_last_task_graph()" ], "metadata": { "collapsed": false, @@ -1032,17 +1044,7 @@ } ], "source": [ - "from IPython.display import display\n", - "from pdf2image import convert_from_path\n", - "import os\n", - "import glob\n", - "\n", - "folder_path = '../tmp/gantt_charts'\n", - "files = glob.glob((os.path.join(folder_path, '*')))\n", - "latest_file = max(files, key=os.path.getmtime)\n", - "images = convert_from_path(latest_file)\n", - "print(latest_file)\n", - "display(images[0])" + "visualize_last_gant_diagram()" ], "metadata": { "collapsed": false, @@ -1065,9 +1067,175 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 49, "outputs": [], - "source": [], + "source": [ + "reset_giskard()\n", + "\n", + "# %% Define goals for later\n", + "right_arm_goal = {'r_shoulder_pan_joint': -1.7125,\n", + " 'r_shoulder_lift_joint': -0.25672,\n", + " 'r_upper_arm_roll_joint': -1.46335,\n", + " 'r_elbow_flex_joint': -2.12,\n", + " 'r_forearm_roll_joint': 1.76632,\n", + " 'r_wrist_flex_joint': -0.10001,\n", + " 'r_wrist_roll_joint': 0.05106}\n", + "\n", + "left_arm_goal = {'l_shoulder_pan_joint': 1.9652,\n", + " 'l_shoulder_lift_joint': - 0.26499,\n", + " 'l_upper_arm_roll_joint': 1.3837,\n", + " 'l_elbow_flex_joint': -2.12,\n", + " 'l_forearm_roll_joint': 16.99,\n", + " 'l_wrist_flex_joint': - 0.10001,\n", + " 'l_wrist_roll_joint': 0}\n", + "\n", + "base_goal = PoseStamped()\n", + "base_goal.header.frame_id = 'map'\n", + "base_goal.pose.position.x = 2\n", + "base_goal.pose.orientation.w = 1\n", + "\n", + "# %% Monitors observe something and turn to True, if the condition is met. They don't cause any motions.\n", + "# All monitor related operations are grouped under giskard_wrapper.monitors.\n", + "# Let's define a few\n", + "# This one turns True when the length of the current trajectory % mod = 0\n", + "alternator = gs.monitors.add_alternator(mod=2)\n", + "# This one sleeps and then turns True\n", + "sleep1 = gs.monitors.add_sleep(1, name='sleep1')\n", + "# This prints a message and then turns True.\n", + "# With start_condition you can define which monitors need to be True in order for this one to become active\n", + "print1 = gs.monitors.add_print(message=f'{sleep1} done', start_condition=sleep1)\n", + "# You can also write logical expressions using \"and\", \"or\" and \"not\" to combine multiple monitors\n", + "sleep2 = gs.monitors.add_sleep(1.5, name='sleep2', start_condition=f'{print1} or not {sleep1}')\n", + "\n", + "# %% Now Let's define some motion goals.\n", + "# We want to reach two joint goals, so we first define monitors for checking that end condition.\n", + "right_monitor = gs.monitors.add_joint_position(goal_state=right_arm_goal,\n", + " name='right pose reached',\n", + " start_condition=sleep1)\n", + "# You can use add_motion_goal to add any monitor implemented in giskardpy.monitor.\n", + "# All remaining parameters are forwarded to the __init__ function of that class.\n", + "# All specialized add_ functions are just wrappers for add_monitor.\n", + "left_monitor = gs.monitors.add_monitor(monitor_class=JointGoalReached.__name__,\n", + " goal_state=left_arm_goal,\n", + " name='left pose reached',\n", + " start_condition=sleep1,\n", + " threshold=0.01)\n", + "\n", + "# We set two separate motion goals for the joints of the left and right arm.\n", + "# All motion goal related operations are groups under gs.motion_goals.\n", + "# The one for the right arm starts when the sleep2 monitor is done and ends, when the right_monitor is done,\n", + "# meaning it continues until the joint goal was reached.\n", + "gs.motion_goals.add_joint_position(goal_state=right_arm_goal,\n", + " name='right pose',\n", + " start_condition=sleep2,\n", + " end_condition=right_monitor)\n", + "# You can use add_motion_goal to add any motion goal implemented in giskardpy.goals.\n", + "# All remaining parameters are forwarded to the __init__ function of that class.\n", + "gs.motion_goals.add_motion_goal(motion_goal_class=JointPositionList.__name__,\n", + " goal_state=left_arm_goal,\n", + " name='left pose',\n", + " end_condition=left_monitor)\n", + "\n", + "# %% Now let's define a goal for the base, 2m in front of it.\n", + "# First we define a monitor which checks if that pose was reached.\n", + "base_monitor = gs.monitors.add_cartesian_pose(root_link='map',\n", + " tip_link='base_footprint',\n", + " goal_pose=base_goal)\n", + "\n", + "# and then we define a motion goal for it.\n", + "# The hold_condition causes the motion goal to hold as long as the condition is True.\n", + "# In this case, the cart pose is halted if time % 2 == 1 and active if time % 2 == 0.\n", + "gs.motion_goals.add_cartesian_pose(root_link='map',\n", + " tip_link='base_footprint',\n", + " goal_pose=base_goal,\n", + " hold_condition=f'not {alternator}',\n", + " end_condition=base_monitor)\n", + "\n", + "# %% Define when the motion should end.\n", + "# Usually you'd use the local minimum reached monitor for this.\n", + "# Most monitors also have a stay_true parameter (when it makes sense), with reasonable default values.\n", + "# In this case, we don't want the local minimum reached monitor to stay True, because it might get triggered during\n", + "# the sleeps and therefore set it to False.\n", + "local_min = gs.monitors.add_local_minimum_reached(stay_true=False)\n", + "\n", + "# Giskard will only end the motion generation and return Success, if an end monitor becomes True.\n", + "# We do this by defining one that gets triggered, when a local minimum was reached, sleep2 is done and the motion goals\n", + "# were reached.\n", + "gs.monitors.add_end_motion(start_condition=' and '.join([local_min,\n", + " sleep2,\n", + " right_monitor,\n", + " left_monitor,\n", + " base_monitor]))\n", + "# It's good to also add a cancel condition in case something went wrong and the end motion monitor is unable to become\n", + "# True. Currently, the only predefined specialized cancel monitor is max trajectory length.\n", + "# Alternative you can use monitor.add_cancel_motion similar to end_motion.\n", + "gs.monitors.add_max_trajectory_length(120)\n", + "# Lastly we allow all collisions\n", + "gs.motion_goals.allow_all_collisions()\n", + "# And execute the goal.\n", + "assert gs.execute().error.code == GiskardError.SUCCESS" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 50, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "../tmp/task_graphs/goal_41.png\n" + ] + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAACb4AAAV0CAYAAAAScpltAAAABmJLR0QA/wD/AP+gvaeTAAAgAElEQVR4nOzdeVhU58E28HvYN1lUFlEQMYriXjAxInEBBXQmIMmgyRto8sbCm1xVUmuq+WIC1izamlST2rrEpuLbJjoalhlUBFwKomlArYJbFMGVAUGQPSzP90c+5wNBHRA8gPfvurguOZx5uM8ZGIc59zyPTAghQERERERERERERERERERERERERNRLGEgdgIiIiIiIiIiIiIiIiIiIiIiIiKgjWHwjIiIiIiIiIiIiIiIiIiIiIiKiXoXFNyIiIiIiIiIiIiIiIiIiIiIiIupVjKQOQEREREREREREREREREQPVlFRgebmZgBAZWUlGhsbW329vr4eNTU17d7W1tYWMpms1TZLS0uYmJgAAMzNzWFmZtYNqYmIiIiIuheLb0RERERERERERERERERdrKKiAuXl5bhz5w7u3Lmj+/f922pqalBZWYna2lrU1dWhoqICDQ0NuHv3rm7bk2BjYwNjY2NYW1vrynDW1tYwMTGBtbU1rKysYGdnBzs7O9ja2j7w3yzREREREdGTIhNCCKlDEBEREREREREREREREfV0paWl0Gq10Gq1uHnzJkpKSnDr1i1otVoUFxfj5s2bKC4uRnFxMZqamtrcvl+/fq2KYnZ2drCwsICVlRUsLCxgamraqoBmZmYGc3Nz9OvXD0ZGP89n0d4MbUZGRujXr1+b79fU1IS7d++22d5yBrnq6mr89NNPKC8vR0NDQ6sS3t27d9HQ0ICKigpUVVW1KfH99NNPbca2sLCAk5MTnJyc4ODgAGdnZzg4OMDR0RGDBg2Cg4OD7uvm5uaduh+IiIiIiAAW34iIiIiIiIiIiIiIiIjw008/4fr167h69SquXr2KgoICXLt2Tfd5YWEhamtrdfsbGRm1KXQNGjQIjo6OcHBwQP/+/dvMinavvNZXVFdXt5rB7s6dOygrK2u3DFhUVIQ7d+60ur2DgwNcXFzg6uoKV1dXuLm56f7t6uoKBwcHiY6MiIiIiHoDFt+IiIiIiIiIiIiIiIjoqVBXV4cff/yxzcelS5dQVFSkmwXNzMxMV75ycXHB0KFDMXToUAwePFhXcmMpq+Pq6+t1ZTitVttuubCoqAj3Ll+amZnBzc0NzzzzDEaOHIkRI0boPlxcXCCTySQ+IiIiIiKSEotvRERERERERERERERE1KfcunULubm5yM3N1ZXbLl68iGvXrkEIAZlMBldXV12J6plnnsHQoUN1RTcnJyepD+Gp9dNPP7Uqw125cqVVSbG8vBzAz0u+tizCeXh4YOzYsfD09ISFhYXER0FERERETwKLb0RERERERERERERERNQr3b17F3l5eThz5gzOnDmDvLw8nD59GqWlpQB+XkrTw8OjzWxhI0aMgJmZmcTpqTOKi4t1RcaWpcaLFy+irq4OBgYGcHd3x/jx4zF27FiMGzcOY8eOxTPPPNPnlpolIiIietqx+EZEREREREREREREREQ9XklJCbKzs3Ufp0+fRkFBAQCgX79+8PT0xPjx4zFmzBiMGzcO48aNg729vbSh6YlpamrCpUuXcObMGd1sf6dPn0Z+fj6amppgZmYGT09PTJw4Ed7e3vD29saECRNgYmIidXQiIiIi6iQW34iIiIiIiIiIiIiIiKhHKS8vb1Vyy87ORmFhIQDAzc0N3t7e+MUvfqErubm5uUEmk0mcmnqi2tpanD17VleIy8nJwYkTJ3D37l2YmJhg/PjxuiKct7c3xowZw5nhiIiIiHoJFt+IiIiIiIiIiIiIiIhIMkIInDt3DkePHkVmZiaOHTuGH3/8EQAwePDgVqUkb29vDBw4UOLE1Ns1Nzfj4sWLrYqVp06dQnV1NczNzfGLX/wCU6dOxbRp0zB16lT+zBERERH1UCy+ERERERERERERERER0RNTV1eH7OxsXdEtKysLZWVlsLS0xHPPPQcfHx9MnjwZ3t7eGDRokNRx6SnR1NSEs2fPIjs7G8ePH8fRo0dx9uxZAMCoUaPg4+OjK8KNGDFC4rREREREBLD4RkRERERERERERERERN2ovr4ex44dQ3p6Og4dOoTs7GzU19dj0KBB8PHx0X1MmjSJS0xSj1JWVoasrCxdSTM7Oxt1dXVwdHSEr68v/Pz84OfnxyIcERERkURYfCMiIiIiIiIiIiIiIqIu09zcjP/85z9IT09HWloaMjIyUFNTA3d3d8yaNQu+vr7w8fHB8OHDpY5K1CH19fXIycnB0aNHceTIERw5cgRVVVUYOnSorgTn5+cHR0dHqaMSERERPRVYfCMiIiIiIiIiIiIiIqLHcv36dezbtw9paWk4ePAgbt++DXt7e8yaNQv+/v7w8/PDsGHDpI5J1KUaGhrw/fff60qe33//PRobGzFu3Dj4+flhzpw5mDFjBszMzKSOSkRERNQnsfhGREREREREREREREREHdLc3Ix///vf0Gg0SE5OxqlTp2BpaYkXXnhBN+vVhAkTIJPJpI5K9MRUVVXhX//6F9LS0pCeno4zZ87A3Nwc/v7+mDdvHubNm4fBgwdLHZOIiIioz2DxjYiIiIiIiIiIiIiIiB6puroaBw8ehEajgVqtxq1bt+Dm5oY5c+ZALpdj9uzZnNmKqIXi4mLs378fGo0G+/fvR2VlJTw9PaFQKCCXyzF16lQYGBhIHZOIiIio12LxjYiIiIiIiIiIiIiIiNpVXFyM+Ph47N69G0eOHEFzczOmTp2KefPmQS6XY8yYMVJHJOoV6urqcOjQId0siYWFhXBwcEBwcDCUSiVmzpwJIyMjqWMSERER9SosvhEREREREREREREREZGOVqtFfHw8VCoVjhw5AlNTU8ydOxfz589HYGAg+vfvL3VEol7v9OnTSE5Oxu7du3HixAkMGDAA8+fPx8svv4xZs2bB2NhY6ohEREREPR6Lb0RERERERERERERERE+50tJSJCcnQ6VSYf/+/TA2Noafnx+USiXmz5+Pfv36SR2RqM8qLCxEQkICVCoVsrKyYGtrC7lcDqVSiYCAAJiYmEgdkYiIiKhHYvGNiIiIiIiIiIiIiIjoKVRXVwe1Wo24uLg2ZbfQ0FBYWVlJHZHoqXP16lXdjItZWVmwsbFBWFgYwsPD4ePjA5lMJnVEIiIioh6DxTciIiIiIiIiIiIiIqKnRHNzMw4dOoQdO3Zgz549qK+vR1BQEMLDwzFv3jyYm5tLHZGI/p/CwkJ888032LFjB86ePQsPDw+Eh4fjtddew9ChQ6WOR0RERCQ5Ft+IiIiIiIiIiIiIiIj6uPPnz+Pbb79FXFwcrly5Ak9PT0REROCNN96Ag4OD1PGI6BHy8vKwY8cO/P3vf0dJSQmef/55KJVKhIeHo3///lLHIyIiIpIEi29ERERERERERERERER9UH19PZKSkrBlyxakpaVhyJAhCA0NxX//939jwoQJUscjok5oamrCoUOHEBcXhz179qC5uRkKhQKRkZHw9/eXOh4RERHRE8XiGxERERERERERERERUR9y4cIFbN68Gdu3b0dVVRVCQkIQFRWFGTNmwMDAQOp4RNRFysvL8Y9//AObN2/GmTNn4OXlhaioKLzyyiuwsrKSOh4RERFRt2PxjYiIiIiIiIiIiIiIqJf76aefkJiYiC1btiA9PR3Ozs547bXX8Otf/xpDhgyROh4RdbOcnBxs2bIF//u//wtDQ0O88soreOuttzBx4kSpoxERERF1GxbfiIiIiIiIiIiIiIiIeqmSkhL89a9/xV/+8hfcvn0bcrkcUVFRCAgI4OxuRE+h0tJS/P3vf8eWLVtw8eJF+Pr64je/+Q2Cg4P5mEBERER9DotvREREREREREREREREvcy5c+ewfv167NixAxYWFoiKisJbb73F2d2ICAAghMDBgwexYcMGJCcnw93dHdHR0XjjjTdgaWkpdTwiIiKiLsHiGxERERERERERERERUS+RmZmJL774At999x3c3NywePFiLFq0iEUWInqgy5cv44svvsC2bdtgaGiI119/HcuWLYOLi4vU0Yiohfz8fCQmJiIhIQFnzpyROg7RE2FmZgZ/f38EBwcjMDCQz2mpw1h8IyIiIiIiIiIiIiIi6sGampqwc+dO/PGPf8SpU6cwffp0LF26FHK5nEsXEpHeSktLsWnTJvz5z39GWVkZFixYgBUrVsDT01PqaERPrRMnTujKbqdPn4adnR3mzZuHqVOnwtDQUOp4RN3uzp07SE5ORlZWFoyNjTF79mwEBwfjxRdfhL29vdTxqBdg8Y2IiIiIiIiIiIiIiKgHamxsxD//+U98/PHHuHz5MsLCwvDb3/4WXl5eUkcjol6svr4e33zzDdatW4dz587h5ZdfxsqVKzFu3DipoxH1eU1NTTh27Bg0Gg2+++47/Pjjj3BwcEBAQACUSiUCAgJgYmIidUyiJ660tBTJycnQaDTYt28fampqMGnSJMjlcixcuBCjRo2SOiL1UCy+ERERERERERERERER9SANDQ345ptv8PHHH+PSpUt46aWXsHr1anh4eEgdjYj6ECEENBoNVq1ahRMnTmDevHmIiYmBt7e31NGI+pTa2lqkpaVBo9EgMTERWq0W7u7ukMvlUCqV8PHxgUwmkzomUY/B3xnqCBbfiIiIiIiIiIiIiIiIeoB7hbePPvoIBQUFWLhwIVauXImRI0dKHY2I+rB7BbjVq1fjhx9+gL+/Pz7++GM8++yzUkcj6rU4exVR12hvlkQXFxcEBQVBLpdzlkRi8Y2IiIiIiIiIiIiIiEhKQgjs3r0b7733Hq5evYqFCxfiww8/xDPPPCN1NCJ6yqSlpWHlypX4/vvv4e/vj88++wzjx4+XOhZRr1BQUIDExERoNBocOXIEhoaGmDZtGuRyOcLCwjBo0CC9xjl79iwSExNRUFDQvYGJJGZoaAgfHx/MmzcPtra2et0mLy8PKpUKGo0GJ06cgK2tLfz9/SGXyxESEgJra+tuTk09DYtvREREREREREREREREEjlw4ABWrFiB06dPIzw8HKtWrYKrq6vUsYjoKZecnIz33nsP586dwxtvvIHY2Fg4OztLHYuox8nLy4NGo4FarUZWVlanSjjNzc04fvw4EhMTkZCQgIsXL8LBwYGlU+rzamtr8e9//xsAMH36dISEhCA4OBhDhgzR6/ZdVTal3o3FNyIiIiIiIiIiIiIioicsNzcXK1asQHJyMvz9/bFu3TpMmDBB6lhERDrNzc3Ys2cPVqxYgaKiIixevBgrVqzQe1Yeor6oq5ZdbGxsxPHjx6FSqbB7927cvHkTbm5uePHFF6FQKDBjxgwYGRk9gSMiklZ1dTUOHjwIlUqFxMRE3L17F56enlAqlVAoFPDy8tJrHC4v/PRi8Y2IiIiIiIiIiIiIiOgJyc/Px/vvv4+dO3fiueeew9q1a/HCCy9IHYuI6IHq6uqwceNGfPLJJzAwMMDKlSvx9ttvw9jYWOpoRE9EbW0t0tLSoNFokJiYCK1WC3d3d8jlciiVSvj4+EAmkz1ynJYFn6SkJFRUVHSq4EPUV9XX1yMjIwNqtVpXCB02bBgUCkWHCqFd9TtLvQOLb0RERERERERERERERN2strYWa9aswR/+8AcMHToUn3zyCebPn8+LbkTUa5SXl2PNmjX44osv4Obmhi+++AL+/v5SxyLqFl01e1RJSQn27dsHlUqFAwcOoKmpCVOmTIFSqURoaChcXFy6+UiIeqfm5macPHkSarUau3btwrlz5zBgwADMnTsXCoUCc+fOhaWl5SPH6apZGqnnYvGNiIiIiIiIiIioi9XW1uLf//43GhoapI5C1C1MTU0xefJkmJmZSR2FqFdQq9WIjo5GcXExli1bhvfeew+mpqZSxyIi6pTr16/j//yf/4MdO3ZALpfjyy+/hJubm9SxiB5bQUEBEhMTodFocOTIERgaGmLatGmQy+UICwvDoEGD9BonPz8farUaKpUKWVlZMDMzg5+fHxQKBUJCQuDg4KDXOKdOncLt27cf55CIerTx48fr/fvQVb9XeXl50Gg0UKvVyMrKgq2tLfz9/SGXyxESEgJra+vHOSSSAItvREREREREREREXaC0tFS3jEZKSgpqamqkjkTUraysrBAYGIiQkBDMmzcPtra2Ukci6nEuXbqE6Oho7N27F3K5HBs3boSrq6vUsYiIusTBgwexePFiFBQU4N1338WKFStYiqdepytKMF01M1VjYyOOHDmCxMREJCYm4urVq11xiEQ9loGBAaZOnYrg4GCEhITgmWee0et2XTWTYleVXUlaLL4RERERERERERF1UmFhIRISEpCYmIiMjAwYGhpi1qxZCAkJQWBgIPr16yd1RKJuUVFRgb179yIhIQGHDx8GAEyfPh0hISEIDg7GkCFDpA1IJLHa2lp89NFH+Oyzz+Dh4YEvv/wSL7zwgtSxJHPp0iWMGDEC33zzDRYuXIh169bh3XffBQAMHjwY169ff6zxd+7ciU8//RQXLlxAXV0dAODMmTMYO3bsY2fvTTIzM+Hr64tDhw5hxowZUsfpEx72s3r/z/XTqr6+Hp9//jk+/vhjDBo0CH/+858REBAgdSyiB+qqZQ/r6+uRkZEBtVqN3bt34+bNmxg2bBgUCgUUCgVmzJgBIyOjR45TXV2N/fv3IzExEcnJySgrK8O4ceN0RSB3d/euOGyiHqepqQn/+te/dMWzsrIyjB07Vvez7+XlBZlM9shxqqurcfDgQahUKiQlJaGiogKenp5QKpVQKBTw8vLSK09XLW9MTx6Lb0RERERERERERB1w/4wA5ubmmDVrFpRKJYKDg2FjYyN1RKInquWFhsTERNy9e7dTFxqI+orMzEwsWrQIRUVF+P3vf4+3335brwvffdmDCkITJ07E7du3H6v4dvToUfj6+mLZsmX48MMPodVqMWPGDOzbt++pK7797ne/w7Zt26DVaiGEgJeXF6ytrZGZmdmp8aqqqjBp0iR4eHhAo9F0cdrepb2fVRbfWrt27RqWLl2K3bt34/XXX8fnn38OOzs7qWMRAfi5kJ6WlqaboVur1cLd3R1yuRxKpRI+Pj4s2BBJqL1CqoODAwICAqBUKp94IbWrHjPoyWDxjYiIiIiIiIiI6CGam5uRlZUFjUaDhIQEXLhwAfb29ggMDIRSqcScOXNgamoqdUyiHqGrLjQQ9Ua1tbVYtWoV1q1bh9mzZ2Pz5s1c1vT/6c7i2zvvvIMNGzbg+vXrGDx4cKuvWVlZYeLEiZ0ufvU2Hh4eeO655xAXF4eGhgZMmjQJ1tbWyMrK6tR4lZWVmDhxIjw8PLB3797Hytbb7wsW3/SXnJyM//mf/0FDQwM2btyIl156SepI9JTqqnJZdyypePjwYRgZGXFJRaIH6ElLEHdVKY+6D4tvRERERERERERE96mrq0NmZqbuBdKioqJW7+6dOnUqDAwMpI5J1KN11YUGot4gIyMDb775JkpKSrB27VpERkZKHalH6c7i20svvYTvvvsOtbW1MDMza/W13l626ojz589j9OjR2L17d48sGvX2+4LFt44pLy/H8uXLsXXrVrz88svYuHEj7O3tpY5FT4GW5bIjR47A0NCwU+Wy/Px8qNVqqFQqZGVlwczMDH5+flAoFAgJCYGDg4Ne4+Tl5UGlUkGj0SAnJwd2dnYdLu8QPe0KCwuRkpICtVqNlJSUVr/XSqUSzs7Oeo3Tlb/Xj1vKo67F4hsRERERERERERGAsrIypKenQ61WIyEhAdXV1boZAcLCwuDp6Sl1RKJerasuNBD1JFVVVfjtb3+LrVu3Yv78+di4cSOcnJykjtXjdGfxLSQkBImJiU998W3t2rWIiYnB7du3YWVlJXWcNnr7fcHiW+fs378fkZGRqKurw8aNG6FUKqWORH1Qy3LZiRMnetzMUC4uLggKCoJcLufMUESPqaysDBqNpt2ZHBcsWIDRo0frNU53zOT4OGVbejx8WyoRERERERERET21rl69ii1btkChUMDJyQmvvvoq8vPzsXr1aly9ehXZ2dmIjY1l6Y2oC7i7uyM6OhqZmZnQarXYtGkTAGDx4sVwdnbGtGnTsGHDBly7dk3ipET6ycnJgZeXF+Lj4/Htt99iz549LL09wDPPPAMhhN7loJKSEixZsgRubm4wMTGBvb09QkNDcerUKd0+CQkJkMlkSExMBACYm5tDJpNhypQpWLduHWQyGaqrq3H06FHIZDLIZLJHLrV873YymQxDhgzBDz/8AD8/P/Tr1w8WFhaYOXMmjh492uZ2paWlWLp0KYYPHw4TExPY2dkhKCgIhw4darVffX09PvzwQ4waNQoWFhbo378/FAoFkpKS0NTU1OFz0FJSUhJmzZoFKysraDQa3XHIZDLU1dV1OO+983v/GPdvLygowIIFC2Bra4sBAwZALpfj8uXLbc5pR++Le86fP4+QkBDY2NjAwsICzz77LDQaDfz9/XVjLVq0qMP3RWNjI3bu3InZs2fDyckJ5ubmGDduHDZs2IDm5ma9snX05/ppFBgYiNzcXISGhmLBggV48803UV1dLXUs6uWampqQmZmJFStWYOTIkRg7diz+9re/wcvLC4mJiSgqKsKuXbsQERHx0NJbfX090tLSEB0dDRcXF3h7eyMuLg6zZ89GamoqioqKEBcXB6VS+dDSW21tLdRqNaKiouDs7AxfX1+o1WqEhoYiIyMDhYWF2Lx5MxQKBUtvRI+pf//+iIiIwK5du1BcXIyEhAR4eXlh06ZN8PT0xPDhw3V/cz5sDjB7e3tERERArVajrKwM8fHxcHd3R0xMDFxdXTFmzBjExsYiJyfnoXnc3NwQHR2N1NRU3Lp1C5s3b4adnR1WrlyJIUOGwNvbG7GxsTh//nxXnwpqSRARERERERERET1FcnNzxZo1a4SPj4+QyWTC0tJSyOVysX37dlFeXi51PKKnTlVVlUhKShLh4eHCxsZGABCenp4iJiZGZGdnSx2PqI3m5maxfv16YWpqKmbOnClu3LghdaRea8KECWLw4MGttt28eVMMHTpUODo6iuTkZFFZWSlyc3PF9OnThZmZmcjKymq1f3BwsAAgamtr24xvaWkpfHx8OpXL0tJSPP/88yIrK0tUVVWJH374QYwfP16YmJiIw4cP6/a9deuWGDZsmHB0dBRqtVpUVFSICxcuiNDQUCGTycTWrVt1+y5atEjY2NiIAwcOiJqaGlFUVCSWLVsmAIhDhw51+hxotVphYGAgNm3a9Mhz05G8Dzu/97YHBwfrzlFqaqowNzcXkydPbnNOO3Nf/Pjjj8LW1lYMHjxYHDhwQHce/P39hb29vTA1NW21f0eOTa1WCwDik08+EWVlZaKkpER88cUXwsDAQCxbtqxNlvZ+VqljUlJShKOjo/Dw8BAnTpyQOg71MjU1NSIpKUlERkYKR0dHAUC4u7uLJUuWiIyMDNHc3KzXOC2fd1pbW3f6eeft27fF9u3bhVKpFFZWVsLAwEB4eXmJmJgYce7cuc4eJhF1UmNjo8jIyBDLly8XI0eOFACEg4ODCA8PF0lJSaK+vl6vcRoaGkRGRoZYsmSJcHZ2FgCEm5ubWLJkiUhNTRUNDQ16jdNVj1mkHxbfiIiIiIiIiIioT2tqatK9AOrh4SEACHt7+w6/AEpE3a+urk6kpqa2utAwbNiwDl9oIOouxcXFYt68ecLIyEjExMSIpqYmqSP1au2ViX75y18KAOIf//hHq+23bt0SpqamwsvLq9X27iq+ARAnT55stf306dMCgJgwYYJu2+uvvy4AiG+++abVvnV1dcLZ2VmYm5uLoqIiIYQQw4YNE1OnTm3z/UaOHNmq+NbRc/DVV18JmUzWpoTZ3rnpSN4HjdFyu1qtbrX95ZdfFgBESUlJq+2duS+USqUAIHbv3t1qe3FxsbCwsGhTfOvIsanVajFjxow23/O1114TxsbGoqKiotV2Ft+6RlFRkQgICBDGxsZ8DKVH6qpyWXFxsdi+fbuQy+XCxMREGBoaCh8fH7F+/Xpx7do1vce5cuWKWL9+vfD39xdGRkbCzMxM+Pv7i/Xr14ubN2925hCJqJvc/4ZHW1tboVQqxfbt29v8H/8gTU1NIjs7W8TExAhPT08BQAwYMECEh4eLXbt2icrKSr3GaVnKGzFiRKdLefRgXOqUiIiIiIiIiIj6nLq6Ot2yNYMHD4avry9UKhUCAgKQkZGhW7aGy80Q9Sympqbw9/fXLXmanZ2NiIgIpKam6paji4iIgEql4lJp9MQdOHAA48ePx7lz55CZmYnY2FgYGPAyS1dLSEiAgYEB5HJ5q+1OTk4YM2YMcnJycP369W7PYWlpiYkTJ7baNm7cODg7O+M///kPbt26BQCIj48HAMybN6/VvqampvDz80NtbS1SUlIA/LzsY1ZWFiIjI3H8+HHd8qYXLlzAjBkzdLft6DlITEyEt7c3nJ2dH3lcHcmrj8mTJ7f63MXFBQBw8+ZNvcd4kP379wMAAgICWm23t7fHqFGj2uzfkWOTy+Vtlj8FgAkTJqChoQF5eXmPnZ/acnR0RHJyMmJiYvDxxx9DoVCgpKRE6ljUgxQUFGDDhg26531RUVG4c+cOPvroI1y/fh3Z2dmIjY1t9zGgpfz8fGzYsAHTpk2Do6Mj3nrrLQDA1q1bcfv2bWRmZiI6OhpDhgx56Dh5eXmIjY2Ft7c3hg0bhlWrVsHOzg7btm2DVqtFamoqoqOjMWjQoC47B0T0+MaMGYPly5cjMzMTV65cwdq1a1FbW4tFixbB0dERs2fPxoYNGx76fMXAwABeXl6IjY1FXl4eLl++jA8++AD5+flYsGABHBwcoFAosGXLFhQXFz9wHENDQ0ybNg1r1qzBxYsXkZubi6VLlyI/Px/BwcFwcnJCWFgY4uLicPfu3e44HX0e/yIjIiIiIiIiIqI+oaysDCqVChEREXBwcEBAQLijilYAACAASURBVACOHj2KqKgo3YuU9y5+sKhA1PO1vNBw9uzZNhca7O3t9brQQPS4hBD45JNPEBQUhJkzZ+LkyZN47rnnpI7VJ9XX16OiogLNzc2wsbGBTCZr9XHixAkAwI8//tjtWWxtbdvd7uDgAAAoLi7W5TUzM0O/fv3a7Ovo6AgAKCoqAgBs3LgRcXFxyM/Ph5+fH6ytrREYGKgrbAEdPwc1NTVIS0tDcHDwI4+po3n1YWNj0+rze28oaG5u1nuM9tTX16OyshJmZmawsrJq83U7O7s2+3fk2CoqKvDhhx9i3LhxsLOz053fd999F8DP55W6h6GhId5//30cOXIEZ8+ehZeXF3JycqSORRLqinJZc3MzcnJyEBsbC09PTwwfPhwfffQR3N3dsXPnThQXF0OtViMiIuKBj+8A0NTUhMzMTKxYsQIjRozA2LFj8fXXX8PLywtJSUkoKirCrl27EBERAWtr6+44HUTUxYYOHYrIyEio1WoUFRVh8+bNsLOzw8qVK+Hi4gJvb2/Exsbi3LlzDx3H3d0d0dHRyMzMhFarxaZNmwAAixcvhrOzM6ZNm4a1a9fi0qVLDx3n/lJeTEwM7ty506FSHrXGV/iIiIiIiIiIiKjXunr1KrZs2QKFQgEnJye8+uqryM/Px+rVq3WzRd27+EFEvZs+FxruzRRH1FWqqqoQFhaGmJgYfPLJJ/jnP//JC93dyNTUFLa2tjAyMkJDQwOEEO1+zJw5U6/xZDJZp7OUlpZCCNFm+72irYODA0xNTWFjY4O6ujpUVla22Ver1QL4eaa2e3nCw8ORlpaG8vJyJCQkQAiB0NBQfP755wA6fg5SU1NRW1urV/Gto3m7UkfvC1NTU/Tr1w91dXWoqqpq8/X7C88dPTaFQoHVq1fjV7/6FS5evIjm5mYIIfCnP/0JANq976lrTZ06FTk5ORg9ejR8fHzw9ddfSx2JnpCW5bKRI0di7Nix+Nvf/tbhclnLWb7vlVfi4uIwe/ZspKam4tatW4iLi4NSqYSlpeUDx6mtrYVarUZUVBScnZ3h6+sLtVqNl156CRkZGSgoKMDmzZs5WzhRH9C/f39ERERg165dKC4uRkJCAry8vLBp0yZdafbe35wPey5gb2+PiIgIqNVqlJWVIT4+Hu7u7vj0008xYsQIjBkzBrGxsY8sdg8dOhTR0dFITU19rFLe047FNyIiIiIiIiIi6lXy8vKwdu1aTJs2DW5ubli6dCkA4Kuvvmq1bI0+y30RUe/0oAsNMTExcHV11ftCA9HDXL58GVOnTsXhw4eRkpKC5cuXSx3pqRAaGorGxkYcPXq0zdfWrl0LV1dXNDY26jWWhYUFfvrpJ93nHh4e2LJli163raurww8//NBq25kzZ3Dz5k1MmDBBN/PQ/PnzAQDJycmt9q2vr0d6ejrMzc11S3Xa2tri/PnzAABjY2PMnj0bCQkJkMlkrW7fkXOQmJgId3d3jB07Vq/j6kjertSZ+yIoKAjA/1/y9J6ioiJcvHixzf76HltTUxOOHj0KJycnLFmyBPb29rpiXm1tbccPjjqtf//+2Lt3L9555x28+eabiIqKQkNDg9SxqBu0Vy5TqVQICgpCRkYGCgsL9SqXlZeX62b5vjczUlpaGn71q18hOztbt8Spv78/jIyMHjhOaWkp4uLiEBYWBgcHB4SEhCAnJwdvvfUWzp8/j7y8PKxZswbTpk17rBI1EfVc5ubmUCgU2Lx5M27cuIGMjAwolUrs378fvr6+cHR01P3N2fI5zP0sLS2hUCgQFxeH27dvIyMjA/7+/vjqq690M1lGR0cjLS3toc9hu6qU91QSREREREREREREPVhjY6PIyMgQy5cvFyNHjhQAhL29vQgPDxdJSUmivr5e6ohE1EPU1dWJ1NRUsWTJEuHs7CwACDc3N7FkyRKRmpoqGhoapI5IvcT+/fuFnZ2dmDhxorhy5YrUcfqsCRMmiMGDB7faptVqxfDhw4W7u7vYu3evKC8vF6WlpWLTpk3CwsJC7Ny5s9X+wcHBAoCora1tM35gYKCwsbERV69eFVlZWcLIyEicPXtWr1w2NjbCz89PZGVliaqqKvHDDz+I8ePHCxMTE3H48GHdvrdu3RLDhg0Tjo6OQq1Wi7t374oLFy6I0NBQIZPJxJYtW3T72tjYiOnTp4v//Oc/oq6uTmi1WhEbGysAiI8++qjD56CpqUnY29uLd955p93jaO/cdCTvw87vg7YvX75cABAnT5587Pvi0qVLon///mLw4MHiwIEDorKyUpw5c0YEBgaKoUOHClNT01b7d+TYZs2aJQCIP/zhD6KkpETU1NSIgwcPCldXVwFApKamthq7vZ9V6lrffvutsLCwEC+88ILQarVSx6EucPv2bbF9+3ahVCqFlZWVMDAwEF5eXiImJkacO3dO73G0Wq3Yvn27kMvlwsTERBgaGgofHx+xfv16ce3aNb3HuXLlili/fr3w9/cXRkZGwszMTPj7+4v169eLmzdvduYQiaiPys3NFWvWrBE+Pj5CJpMJS0tLIZfLxfbt20VFRYVeYzQ1NYns7GwRExMjPD09BQAxYMAAER4eLnbt2iUqKyv1Gqfla2IjRowQAISDgwNfE2uBxTciIiIiIiIiIupxampqRFJSkoiMjBROTk4CgHB3dxdLliwRGRkZorm5WeqIRNTDtbzQMHr06DYXGqqqqqSOSD3Ul19+KQwNDUV4eLioqamROk6f9Mc//lEAaPXx/vvv675eWloqli5dKtzd3YWxsbGwt7cXc+bMaVVGio+PbzMGAHHs2DHdPufPnxe+vr7C0tJSuLi4iI0bN+qV717J6ezZsyIgIED069dPmJubi+nTp4vMzMw2+9++fVu88847YtiwYcLY2FjY2NiIgIAAkZ6e3mq/U6dOiaioKDF69GhhYWEh+vfvL6ZMmSK2bt3a5rmNPucgMzNTABCHDh1q9zgeVE7TJ2975/e//uu/xLFjxx54392/fd68eY99X1y4cEGEhIQIa2trYWFhIaZOnSqOHDkiZsyYISwsLDp9X5SUlIioqCjh4uIijI2NhaOjo3j99dfFihUrdPm9vLwe+bNKXevEiRNi6NChwt3dXVy8eFHqONQJXVUuu3z5sli/fr2udGJhYaErndy5c0fvcXJzc0VMTIzw8vISAISdnZ1QKpVi+/bt4u7du505RCJ6yhQUFIjNmzcLuVwujI2Nhampqe5x7caNG3qP0/JxzcDAQJibmwu5XC42b97cocL3/aU8W1tb3eOavqW8vkYmBOfAIyIiIiIiIiIi6ZWVlSE9PR1qtRoJCQmorq7GpEmTIJfLERYWBk9PT6kjElEvlp+fD7VaDZVKhaysLJiZmcHPzw8KhQIhISFwcHCQOiJJTAiB999/H2vWrMEnn3yCFStWSB2JJDJx4kTcvn0b169flzrKQ/3ud7/Dtm3boNVq213ST6FQYO/evaivr3/okn+90ahRo1BbW4vCwkKpo1AXKykpgUKhQH5+PjQaDZ599lmpI9Ej5OXlQaVSQaPRICcnB3Z2dvD394dcLkdISAisra0fOUZzczNOnjwJtVqNXbt24dy5cxg4cCCCgoKgUCgwd+5cWFpaPnKcpqYmHDt2DCqVCvHx8bh27RpcXV0RGBgIuVyOgICAhy6lSkT0MGVlZdBoNNBoNNi3bx9qamp0r1stWLAAo0eP1muckpIS7Nu3DyqVCqmpqWhsbMSUKVOgUCgQGhqKESNG6DVOYWEhUlJSoFarkZKSAkNDQ0ybNg1yuRxKpRLOzs6Pc7i9BotvREREREREREQkmftfpBNC4LnnnoNSqXyqXqQjoier5YWGAwcOoKmpCVOmTIFSqURoaChcXFykjkhPWFNTE9566y18/fXX+Otf/4pFixZJHYkk1FuKbx4eHnj22WexY8cOAMDYsWOh0Wjg5uYGAPjFL36BO3fu4MqVKxKm7LyioiJ4enpCq9XC2NhYt72goAAjRozAa6+9hq+//lrChNRdampqsGDBAhw6dAg7d+7EvHnzpI5ELdwrl2k0GuzZsweXLl2Ci4sLgoKCOlQuq6urQ2ZmJtRqNXbv3o2bN29i2LBhUCgUUCgUmDFjhl6l3draWqSlpUGj0SAhIQHFxcXw9PSEQqGAXC6Hj48PZDJZVxw6EZFOy8eepKQkFBUVwd3dXVc60/exp6amBunp6VCpVEhKSkJFRQU8PT2hVCqhUCjg5eWlV56uKuX1Riy+ERERERERERHRE5WXlweNRgO1Wo2srCxYWFhg5syZUCqVCA4Oho2NjdQRiegpUl1djYMHDz72hQbqvaqrq7FgwQIcPnwYu3btwty5c6WORBLrLcW3+40dOxbTp0/H2rVrcfDgQYSEhODTTz/F8uXLpY7WKUVFRRg0aBDeeOMNrFq1CgMGDEBubi4WL16MS5cu4YcffoC7u7vUMambNDU14e2338a2bdvwl7/8BZGRkVJHeqq1Vy7rTMHjzp07SEtLg1qtRmJiIu7evdup512lpaVITk6GRqPB3r17UVtbqyt4vPLKK/Dw8HjcQyYi0lvLQnB8fDwuXrwIe3t7BAYGQqlU6l0IbmxsxPHjx6FSqbBnzx7cuHEDbm5uePHFFztdCE5MTIRWq+3UY3ZvweIbERERERERERF1q656AZCIqLu1vNBwb+aRzlxooN6jtLQUc+fOxZUrV5CcnIzJkydLHYkktG7dOrz77ruttr3//vv46KOPJErUMd9//z2WL1+OnJwcODk54c0338S7774LQ0NDqaN1Wnp6OjZu3IiTJ0/i5s2buiUUV61aheHDh0sdj7qZEAIrV67Ep59+io8//hjvvfee1JGeKi3LZffPHrRw4UKMGjVKr3GKi4uxf//+dmfafemllzBkyBC9xrly5QqSkpKg0Whw+PBhGBkZ6Zb0CwsLw6BBgx7ncImIukxXvOGz5RLQKpUKZ8+exYABAzB37lwoFAoEBQXBysrqkeO0fE3uu+++w48//ggHBwcEBAT0mdfkWHwjIiIiIiIiIqIu11VLPhARSaXlhYZdu3bh3LlzrS40zJ07F5aWllLHpMdQWloKf39/3LlzB6mpqRgxYoTUkYiIqB1//vOfsWTJEqxatQoffPCB1HH6tIKCAiQmJj52uSw/P19X1sjKyoK5uTlmzZoFpVKJF198Eba2tnqNk5eXB5VKBY1Gg5ycHF35VS6XY/78+ejXr9/jHC4RUbcrLCxESkoK1Go1UlJSYGBgAF9fX93rY87OznqN0/Jx9dixYzA1NYWfnx8UCgWCg4Ph6Oio1zgPK+WFhITA2tr6cQ5XEiy+ERERERERERFRlygrK0N6ejrUajUSEhJQXV2tmxEgLCwMnp6eUkckIuq0+y/gmpmZ6S40hISEwMHBQeqI1AHl5eWYPXs2tFotDh8+zOUSiYh6uG3btiEyMhKxsbEsv3Wxh5XL9C1BtHzDwM6dO3H+/HkMHDgQQUFBHXrDwL2ZiVQqFeLj43Ht2jW4uroiMDAQcrkcgYGBMDY27orDJiJ64h72utmCBQswevRovcYpKSnBvn37oFKpkJqaisbGRkyZMgUKhQKhoaF6v6Hn/lKeoaGhruzckVKe1Fh8IyIiIiIiIiKiTrv/RTIhBJ577jkolcpe9SIZEVFHtLzQcP+SXaGhoXBxcZE6Ij1EeXk55syZg6KiIhw6dIjLJRI9wrfffotXXnkFAGBqaoq6ujqJE9HT6quvvkJkZCR+//vfY+XKlVLH6bVaLnu3Z88eXLp0qVW5TN9l7+rq6pCZmal7Y8CtW7cwbNgwKBSKDi0R33K28ISEBBQXF8PT0xMKhQJyuZyzhRNRn9RVKyXU1NQgPT0dKpUKSUlJqKio6NRjaFlZGTQaTbvLW3eklCcFFt+IiIiIiIiIiKhDHrYsQnBwMGxsbKSOSET0xFRXV+PgwYNtLjQolUooFAp4eXlJHZFaqKiowOzZs1l6I+oEf39/ZGZmtiq+VVVVYdKkSfDw8IBGo9F7rM7ejmjr1q2IiorC6tWr8f7770sdp9foqnLZnTt3kJaWBrVajcTERNy9e7dTz3tKS0uRnJwMjUaDvXv3ora2VleweOWVV+Dh4fG4h0xE1Gu0LCTHx8fj4sWLsLe3R2BgIJRKpd6F5MbGRhw/fhwqlQp79uzBjRs34ObmhhdffBEKhQLTp0/Xa9bMlv9nJCYmQqvVdqqU96Sw+EZERERERERERA/VVS/AERH1dS0vNOzevRs3b95sdaFB35lPqHvU1NRg1qxZuHHjBg4fPszS21PAysoKEydORGZmZp/8fk9ae8W3yspKTJw4ER4eHti7d2+r/R92Ph52O6JH+fLLLxEdHY0NGzZg8eLFUsfpsR5WLlu4cCFGjRql1zjFxcXYv39/uzPdvvTSSxgyZIhe41y5cgVJSUnQaDQ4fPgwjIyMdEvqLViwAE5OTo9zuEREfUZXveH03lLWKpUKZ8+exYABAzB37lwoFAoEBQXBysrqkWP0htcEWXwjIiIiIiIiIqI2umrJBSKip1VzczNOnjwJtVqNXbt24dy5c60uNMydOxeWlpZSx3xqNDU1ITQ0FFlZWTh69ChGjhwpdSR6Alh861rtFd8epq+fD5LWmjVr8P7772P37t2YP3++1HF6jIKCAiQmJrZbLgsLC8OgQYP0Gic/P1+3hGlWVhbMzc0xa9YsKJVKvPjii7C1tdVrnHulC41Gg5ycHNjZ2cHf3x9yuRzz589Hv379HudwiYj6vMLCQqSkpECtViMlJQVCCDz33HNQKpVQKpVwdnbWa5yWj+vHjh2Dqakp/Pz8oFAoEBwcDEdHR73GeVgpLyQkBNbW1o9zuJ3C4hsREREREREREQEAysrKkJ6eDrVajYSEBFRXV+tmBFiwYAFGjx4tdUQiol7r/gvIZmZmugsNISEhcHBwkDpin7ZkyRJs3boVaWlp8PHxkToOPSEsvnUtFt+op1m8eDG2bduGtLQ0TJ06Veo4kumKclnLwv7OnTtx/vx5DBw4EEFBQVAqlZgzZw5MTU0fOc69mYFUKhXi4+Nx7do1uLq6IjAwEHK5HIGBgXots0dERG097HW7sLAweHp66jVOSUkJ9u3bB5VKhdTUVDQ2NmLKlClQKBQIDQ3FiBEj9Brn/lKegYEBfH19dW+a1beU97gMnsh3ISIiIiIiIiKiHqmwsBBbtmyBQqGAk5MTXn31VeTn52P16tW4du0asrOzERsby9IbEdFjcnd3R3R0NDIzM6HVarFp0yYAP1+0d3Z2xrRp07B27VpcunRJ4qR9z7p167Bx40bs2LGDpbc+oL6+Hh9++CFGjRoFCwsL9O/fHwqFAklJSWhqagLw830uk8lQXV2No0ePQiaTQSaTtVpquLGxETt37sTs2bPh5OQEc3NzjBs3Dhs2bEBzc7Nuv4SEBN3tZTIZLly4gLCwMAwYMEC3bcWKFY/8fvoqLS3F0qVLMXz4cJiammLIkCHw9/fH3//+d9TW1ra7n4mJCezs7BAUFIRDhw49MHtBQQEWLFgAW1tbDBgwAHK5HJcvX26T4fz58wgJCYGNjQ0sLS3h6+vbbnnt/vHvFeIedf4fdLsncWzUt6xfvx4BAQEIDg7GxYsXpY7zxDQ1NSEzMxPR0dFwdXXF2LFj8fXXX8PLy0s3W/euXbsQERHx0NJbXV0d0tLSEB0djSFDhsDb2xtxcXGYM2cOUlNTcevWLcTFxUGhUDy09FZTUwO1Wo2IiAgMHDgQvr6+SEtLw6uvvoqMjAwUFBRg8+bNUCgULL0RET2G/v37Q6lUIi4uDlqtFgkJCfDy8sLmzZsxZswYDB8+XPc358PmQLO3t0dERATUajXKysoQHx8Pd3d3fPrppxg5ciTGjBmDFStWPHKcoUOHIjIyEmq1GkVFRdiyZQvs7OywcuVKuLi4wNvbG7GxsTh37lx3nI7/TxARERERERER0VMlNzdXrFmzRvj4+AiZTCYsLS2FXC4X27dvF+Xl5VLHIyJ6qlRVVYmkpCQRHh4ubGxsBADh6ekpYmJiRHZ2ttTxej2VSiUMDAzEZ599JnUU6iKLFi0SNjY24sCBA6KmpkYUFRWJZcuWCQDi0KFDrfa1tLQUPj4+7Y6jVqsFAPHJJ5+IsrIyUVJSIr744gthYGAgli1b1mb/4OBgAUBMnz5dHDp0SFRXV4vjx48LQ0NDUVJS8sjvp49bt26JYcOGCScnJ6FWq8Xdu3dFUVGRWL16tQAg/vSnP7Xaz9HRUajValFRUSEuXLggQkNDhUwmE1u3bm03e3BwsMjKyhJVVVUiNTVVmJubi8mTJ7fa98cffxS2trZi8ODB4sCBA6KyslKcPn1azJkzR7i5uQlTU9MHnpva2tpW2x91Ptq7XXcemxBCzJw5U/Tv318cO3bsgbmod6mpqRFTpkwRw4cPF1qtVuo43aampkYkJSWJyMhI4eDgoHu+sHz5cpGRkSGam5v1GqesrEzs2rVLhIeHC2tr604/7ygpKRHbt28XSqVSWFpaCgMDA+Hj4yPWrFkjzp8/39nDJCKiTmhsbBQZGRli+fLlYuTIkQKAsLe3F+Hh4SIpKUnU19d3aJwlS5aIwYMHCwDCzc1NLFmyRKSmpoqffvpJr3Fa/p/l6OgoAAh3d3exZMmSDv2fpS8W34iIiIiIiIiI+riuegGMiIi6V0NDg+5Cg7Ozc5sLDQ0NDVJH7FVOnTolzM3NxeLFi6WOQl1o2LBhYurUqW22jxw5ssPFtxkzZrTZ/tprrwljY2NRUVHRavu9gtXevXsfmO1xi2+vv/66ACB27tzZ5muBgYG64tu9/b755ptW+9TV1QlnZ2dhbm4uioqK2mRXq9Wt9n/55ZcFAF1xTwghlEqlACB2797dat8bN24IU1PTbi++deexCSHE9OnThZ2dncjKynpgLup9ioqKxLBhw8TMmTNFY2Oj1HG6zO3bt9uUy7y8vERMTEyHymVXr14VmzdvFnK5XJiYmAhDQ0Ph4+Mj1q9fL65du6b3OPn5+WL9+vXC399fGBkZCTMzM+Hv7y/Wr18vbt261ZlDJCKibtBVb3jNzc0VMTExwtPTUwAQAwYMEOHh4WLXrl2isrJSrzGexGuSXOqUiIiIiIiIiKgPqq2thVqtRlRUFIYMGQJfX1+oVCoEBgYiIyMDWq1Wt2yNiYmJ1HGJiAiAkZERpk2bhg0bNuiWm/7lL3+JtLQ03XKMERERUKlUqKqqkjpuj1ZZWYmFCxfi2Wefxeeffy51nG6Tm5vbarlHmUyGX//61312OwAEBgYiKysLkZGROH78uG550wsXLmDGjBl6nzu5XN5q6cx7JkyYgIaGBuTl5bV7u2effbbjd5Se4uPjAQBBQUFtvrZv3z688847rfabN29eq31MTU3h5+eH2tpapKSktBlj8uTJrT53cXEBANy8eVO3bf/+/QCAgICAVvs6Oztj5MiRHTqezujOYwOAw4cPo6ysDM8//zyAp/N3qC9ydHREQkICvv/+e8TExEgd57FcuXIFGzZs0P2/HxUVhTt37uDjjz/G9evXkZ2djdjYWHh4eDx0nPz8fGzYsAHTpk3D0KFD8Zvf/AYAsHXrVty+fVu3VOqQIUMeOk5eXh5iY2Ph7e0Nd3d3/P73v4ednR22bduG4uJipKamIjo6Gk5OTl12DoiI6PGMGTMGy5cvR2ZmJq5cuaL7e2jRokUYOHCg7m/O+58ntTdObGws8vLycPnyZXzwwQfIz8/HwoUL4eDgAIVCgS1btkCr1T5wDENDQ0ybNg1r1qzBhQsXkJubi9/+9rfIz89HcHAw+vfvD4VCgbi4ONy9e7dTx2vUqVsREREREREREVGPU1ZWhvT0dKjVaiQkJKC6uhqTJk1CVFQUFixYgNGjR0sdkYiI9GRgYAAvLy94eXkhNjYW+fn5UKvVUKlUWLBgAczMzODn5weFQoGQkBA4ODhIHbnHEELgjTfewJ07d5Ceng4jo757KWTs2LEQQrT7tb66fePGjXj++eexfft2+Pn5AQB8fX0RFRWF+fPnt3ub9lRUVOCzzz5DfHw8rl+/jvLy8lZfr6mpafd2lpaWen+Pjqivr0dFRQXMzMzQr1+/Tu/n6OgIACgqKmrzNRsbm1af33vzQ3Nzs27syspKmJmZwcrKqs3tHRwccPHiRf0PqoO689ge5Gn8Heqrxo8fjw0bNiAyMhKTJ09GcHCw1JH0lpeXB5VKBY1Gg5ycHNjZ2cHf3x/btm3D/PnzH/qYcE9zczNOnjwJtVqNnTt34vz58xg4cCCCgoKwfPlyzJkzB6ampo8cp6mpCceOHYNKpcJ3332H69evw9XVFYGBgYiJiUFgYCCMjY274rCJiOgJGDp0KCIjIxEZGdnqdcMPPvgAS5cuxaRJkyCXyxEWFgZPT88HjuPu7o7o6GhER0ejpKQE+/btg0qlwpIlS/D2229jypQpUCgUCA0NxYgRIx44zpgxY3TFvMLCQqSkpECtVmPRokWIjIyEr68v5HI5lEolnJ2d9TpGzvhGRERERERERNSLFRYWYsuWLVAoFHByckJ4eDhu3bqF1atX62YLio2NZemNusWlS5cg+7/s3XtU1NXeP/D3IMjd4SKCCiaSqKmhISYKD8hFMTHIk5e8ZScVs0Q0zEuULjGvmFJ5IeukPSe19JckKpqiFiKcxLykBqOoHVGQmyAgjAL790dr5nEcLjMjOAjv11qzlrO/+7v3Z+8BZDN79kciwa5du7S6LyYmRnn6SEOnTDQHBw8ehKura72bZ3SdCyJNKd5oOHnyJO7cuYMtW7YAAGbPno1OnTrBy8sLq1evxtWrV/Ucqf59+umniI+Px3fffafxmyX07JBIJJg8eTKOHj2K4uJixMfHQwiB0aNHq53uJ5FI6mxn1KhRiI6OxvTp0yGTyVBTUwMhgWoxvgAAIABJREFUBNavXw9At01D9fXXEGNjY0ilUlRWVqK0tFTneooTN3Q5fcnY2BiWlpaorKys9VTJoqIirdrTdj6acmzUOkybNg1vvvkm3nrrLVy/fl3f4dSpurpaeeJaly5d0KdPH3zzzTdwd3fHvn37kJubix9++AFTpkypd9NbZWUljh49qjy5bcCAAfj2228xbNgwHDlyBDk5OcpTvuvb9Hb//n0kJCRgypQpaN++Pby9vXH06FFMnDgRycnJuHHjBuLi4jBq1KhWuemtrt/zq6ursWXLFgwePBhSqRRGRkbo1KkTXnnlFXzxxRe4ceNGk8RTVlamdqJjampqg/fNnz9f5Z7ly5c3SXwA0K9fP7UY63s0ZSytnYWFhdp8x8TE6DusJxYfH68ypsrKygbv4ZodsLGxwZgxY/Dtt9/izp07iI+Ph7u7O+Li4tC7d2+4uLgo15z1fXjAzs4OU6ZMQUJCAoqKirB3715069YNK1euhKurK3r37o2FCxfi5MmT9f5OrdiUl5CQgNzcXHz55ZewtrZGVFQUnJycMGDAACxduhR//vlnvePixjciIiIiIiIiomfMpUuXsHr1anh5ecHZ2Rnz5s0DAHz11Ve4c+eOMt0M3+yn5ioyMhJCCLi5uek7lHplZWXh1VdfxaJFi+pN3UH0tNX3RkP37t2VKWnOnDmj71CfupSUFCxatAiffPKJ8jQwalmsrKyQkZEBADAyMkJgYKDyzc8DBw6o1DUzM8ODBw+Uz3v06IEvv/wS1dXVSElJgYODA8LDw2FnZ6fcpFVRUaFzbHX1pynFiXUHDx5Uu9a/f39lqkJFvcfHK5fLkZSUBFNTU7VUpZpSpFlVpDxVKCgoQGZmplZt6TIfTTk2ah02btwIR0dHjB8/XuXrrzlITEzEpEmTYGdnB29vb5w4cQJTp07FmTNn8Ndffyk3lylOLKzN3bt3sXv3bkyZMgX29vYIDAzE0aNHMWPGDKSnpytTnAYEBNT7oY2CggJ8++23GDt2LDp06IDQ0FBcu3YNCxcuREZGBi5duoRVq1bBy8vriTb1tmSTJ0/Gu+++i9DQUFy6dAmlpaVITk5G//79ER4ejgEDBjRJvxYWFhBC4OzZs8qy6Ojoeu8pLCxUfmhi4sSJEEIgKiqqSeJT2L17N4QQykdYWBiAv78PHi0fN25ck/T/8OFDvPjii/Dy8mqS9p8VZWVlyq+VkJAQCCEQGRmp56ieXGhoKIQQz9Tpns2NqakpRo0ahbi4OGRnZyM5ORljxozBoUOH4O3tDQcHB+WaUy6X19mOmZmZMlVpYWEhkpOTERAQgH//+9/w9vaGs7Mz5syZg6NHj+Lhw4d1tmNjY4MpU6bghx9+wJ07d7Bnzx706dMHX3zxBV544QX07t0bixcvxl9//aV2Lze+ERERERERERE1c4oTARYuXIgePXqgT58+WLduHbp164affvoJRUVFyk/oP57miYh099FHH2Hw4ME4c+aMRimmiPTB3Nxc+UZDQUGB8o2GrVu3YsCAASpvNFRVVek73CZVXl6OKVOmYPjw4fjggw/0HQ41oZkzZ+LChQuQy+XIy8vDmjVrIISAn5+fSr2XXnoJMpkMN2/eRGpqKq5duwZvb2+0adMGvr6+yM3Nxdq1a1FQUICKigocP35cuTFAF3X1p6mVK1fC2dkZc+fOxYEDB1BaWors7GzMmjULOTk5yo1vinoRERHYv38/SktLIZPJMGHCBOTk5CA2NlaZFlRbK1asgI2NDSIiInDkyBGUlZXh8uXLmDRpUq3pT+ujy3w05dgAwM/PD7a2tkhLS9O5DWrezMzMsGfPHly+fLnBzUBP25IlS3D69GlERUUhKysL58+fx7Jly/DSSy/Ve9/NmzdVTvl+4403cO3aNSxbtgw3b97EpUuXsHTpUri7u9fbzvXr1xEbG4vAwEB07NgRYWFhuHv3Lj755BPcunULJ0+exIIFC9CjR4/GHHaLdPr0aezcuRNvv/02PvjgAzg6OsLExAQuLi745JNP8M477zxxHxYWFg1u2jI1NcVzzz2HxMREpKen11lv/fr1cHJyeuKYnjU1NTUNprxuLJq8XqQ9zuvT0aZNG3h5eWHVqlXIzMzExYsX8f777+PatWsICQmBjY2Ncs1ZUlLSYDuxsbHIzs7GxYsXMXXqVBw9ehSBgYHKzXS7d++u9XRhBTMzM7z22mvYtm0b7ty5g2PHjiEwMBAxMTG1fkAEgoiIiIiIiIiImp379++Lffv2iRkzZggHBwcBQHTr1k2Eh4eL5ORkUVNTo+8QicSVK1cEALFz506d7ndzcxOdO3du5Kgaz/3795X/7ty5s2jTpk2ddZ90LogaW3V1tUhPTxdLliwRL7zwggAgbG1txeTJk8UPP/wgSktL9R1iowsPDxdWVlYiOztb36FQEzp37pwICwsTvXr1EmZmZsLGxkYMGjRIbN26Ve33o4yMDOHt7S3Mzc2Fk5OT2Lhxo/Jafn6+CAsLE05OTsLIyEjY29uLqVOnioULFwoAAoBwd3cXqampyuePPmpTX3+aKigoEBEREcLZ2VkYGRmJjh07ivHjxwuZTFZvPalUKoYPHy6SkpKUdWqL/cMPPxRCCLXykSNHKu/LzMwUoaGhol27dsLU1FR4eHiI/fv3C39/f2X9t99+W+zdu1etnYkTJzY4Hw3d15Rj8/b2FtbW1uLUqVNavzb0bPnss8+EoaGhSE9P13coSh4eHmL+/Pka1c3KyhIbNmwQQ4YMERKJRJiZmYng4GCxfft2cffuXY37vHjxoliyZIlwd3cXAISNjY0YM2aM2L59u7h3756uQ2lVavs9/5tvvhEARExMTK33nDhxQtja2j5Rv+bm5mLIkCF1Xj979qwwNzcXmzdvFgBESEhIrfXu3r0rbGxsxLZt29R+3j5NYWFhAoBITEzUS/9NraHXS5/Onj1b79dIc9bQvIaEhAgAoqKiosG2uGbXzV9//SXi4uJEcHCwMDIyEoaGhmLIkCFiw4YNWq27Hv1/zcDAQJiamorg4GARFxcncnNzNWrD1tZWbNq0Sa1cIkQ9CVWJiIiIiIiIiOipKSoqwv79+7F//34cOnQI5eXl6N+/P4KDgzFu3Dj06tVL3yESqbh69Sq6d++OnTt3Yvz48Vrf369fPxQUFCA7O7sJomtcjo6OyM3NrfPErCedC6Kmdu3aNSQkJGD37t04deoUTExM4O/vj1GjRiE0NBQdOnTQd4hPJDU1Fd7e3vjXv/6FKVOm6DscIiLSs5qaGgwdOhQlJSU4ffo0jIyM9B0SBg4cCF9fX6xZs0btWk1NDc6ePYuEhAR8//33yMjIQPv27TFixAiMGTMGw4YNg7GxcYN9VFdXIzU1Fbt378aPP/6I7OxsdOnSBUFBQQgODkZQUFCzmItnSW2/5ycmJuKVV17B8OHD1VJDNxYLCwv069cPJ0+erPX6uXPn4OXlhcLCQri4uOD27ds4d+4cXnzxRZV6y5Ytw5UrVxAWFgZvb29MnDgR//73v5sk5vrMnDkTcXFxSExMRFBQ0FPvv6k19Hrp07lz59C/f3+EhIQgPj5e3+FopaF5DQ0NxU8//YSKigqYmJjU2xbX7E+uqKgISUlJSEhIQHx8vMrfLceOHYsXXnhBo3YKCgpw8OBB7N69G0eOHEFVVRUGDRqEUaNGYfTo0ejevXut97Vv3x7R0dFqp2oy1SkRERERERERkR799ddfKmlrZsyYgbt37yI6Oho3b95Eeno6li5dyk1v1Cw9//zzEEKo/NFYLpfj448/Rs+ePWFmZqZMibFv3z5UV1dr1G5+fj7Cw8PRtWtXtG3bFnZ2dhg9ejTOnTunU92YmBhIJBJIJBI4Ojri9OnT8Pf3h6WlJczMzDB06FCkpKQ0+lwQNSfdunXDnDlzcPLkSdy5c0eZznH27Nno1KkTvLy8sHr1aly9elXPkWpPLpdj2rRpGDZsGDe9ERERAMDAwABbt26FTCardaNZc3HhwgVMmzYNDg4OGDBgAHbu3IlXX30Vp06dwp07d/Dtt99i1KhR9W56u3//PhISEjBlyhS0b98e3t7eOHr0KCZOnIjk5GTcuHEDcXFxGDVqFDe96aC23/O9vb3h4OCAw4cPY8SIEThx4oRGKTW1WbuUl5cjJSVFuY4xNDSstU1jY2PMnz8fQgh88sknKtfKysrw+eefY/HixXXGVFVVhe+//16ZhtDU1BR9+/ZFbGysypi8vLyUsUgkEkyaNAkAEBAQoFJeXFzc4Dw8Lj4+XqWNzMxMjB07Fra2tsqygoICjWPdv3+/SnuVlZUq/Wmz3iwsLMS8efPg4uICY2NjODo6IiAgANu2bUNFRYXGr9ej7bRt2xbW1tYYMWIEjh8/rtU8PP5Yvny58nV8tPz111/X+nXQZn4ej/XGjRsYN24crKysYGtri+DgYGRlZam1nZGRgdDQUEilUpiZmWHgwIHYv3+/ytfRtGnTtP4+yM3NbbB/rtmfnI2NDcaMGYNvv/0WeXl5OHz4MIYMGYK4uDj07t0bLi4uyjVnfT8T27dvjylTpiAhIQF5eXn47rvv4OjoiBUrVsDV1RXu7u5YtmwZ5HK5ZoFpfO4cERERERERERE1iosXL4pVq1Yp09aYm5sr09YUFxfrOzyiJzJt2jQhlUrFzz//LO7fvy9yc3NFZGSkACCOHz+uUre2VKe3b98Wzz33nLC3txcHDhwQpaWl4uLFi8LHx0eYmJiopCbTpq6iP3Nzc+Hp6SlOnTolysrKxOnTp8WLL74o2rZtK06cOFHnuBpKdUr0rCorKxP79u0TkydPFlKpVAAQL7zwgliyZEmzSg9XnwULFoh27dqJ//73v/oOhYiImpm1a9cKY2NjcenSJX2HUmuq01WrVglzc3OxYsUKcfnyZY3bys/PF9u3bxdjxowR5ubmwsDAQAwZMkSsWrVKZGRkNHboVIvk5GTh5OSkTKvcoUMHMXHiRLFjxw5RXl6uVl/btYumqU6FEOL+/fvC3t5eGBgYqHwdrVq1SowdO1YZL2pJdZqQkCAAiBUrVoiioiKRn58vPvvsM2FgYCAiIyNV6p47d06Ym5sLNzc3UVZWJoQQorKyUrz88ssNpo/UJNWpIm2lj4+POH78uCgvLxdpaWmiTZs2Ij8/X6tYH23v0TSY2rwOOTk5wtnZWTg4OIiEhARx7949kZubK6KjowUAsX79emXd+l4vRTv29vYiISFBlJSUiMzMTDF69GghkUjE1q1btZqH4cOHCwMDA3H16lW1vjw9PcV3332nUqZNqlNtv04VsYaEhCjX2EeOHFGmSn/UlStXhJWVlejcubP4+eeflW0HBAQIOzs7YWxsrBaPpqlOH+0/KSlJtGvXTq1/ajrV1dUiOTlZLFiwQPTo0UMAEHZ2dmLy5Mli3759orKyUqN25HK5OHTokBgzZowAIPLy8lSu15XqlBvfiIiIiIiIiIiaWFVVlfIPQK6urmp/AJLL5foOkajRODs7i8GDB6uVu7q6arTx7c033xQA1P5Yn5OTI4yNjYW7u7tOdRX9ARBnz55VKb9w4YIAINzc3OocFze+UWvw8OFDkZycLMLDw0WnTp0EANG1a1cRHh4ujhw5Ih4+fKjvENXIZDJhZGRU6xsgRM2FYlNEfY8lS5boO0yiFqmqqkoMGDBADBs2TN+h1LnxzdnZWaP7r127JjZs2CACAgKEoaGhMDExEQEBAWLDhg0iJyenKUKmBlRWVort27eLkJAQYWlpqfyZbmtrq7YRTNu1izYb34QQYvXq1QKAmDRpkhBCiPLycmFvby/Onz8vhKh/45uvr69a+5MmTRJGRkaipKREpfyHH34QAMTo0aNFTU2NePPNN8XixYvrjFNBm41vBw8erPW6trHWtvFNm9dh6tSpAoD4/vvv1foMCgrSeOObop3HvyYqKytFp06dhKmpqcjNzVWLu655OHz4sAAgZs2apVJ+8uRJ0blzZ/HgwQOVcm02vmn7daqINSEhQaX89ddfFwBEfn6+skyxmWnPnj0qdfPy8oSZmdkTbXx7vP8JEyao9U9Pz+Mf+DUzM9PqA7/Hjh3TauMbU50SERERERERETWBiooKJCQkICwsDJ07d4a3tzd2796NoKAgJCcnq6Stadu2rb7DJWo0QUFBOHXqFGbMmIG0tDRletPMzEz4+vo2eH98fDwMDAwQHBysUu7g4IDevXvjzJkzyM7O1rqugrm5Ofr166dS1rdvX3Tq1Annz59HTk6OtkMmajEMDQ3h5eWF2NhYZbrtN998E0ePHlWmlJoyZQp2796NsrIyfYcLAFiwYAGef/55TJ8+Xd+hENVJ/H0QRb2PpUuX6jtMohapTZs2+PTTT/Hzzz/j8OHD+g5Ha5cuXcLSpUsxYMAAdOvWDcuWLYO1tTW+/vpr5OXl4ciRI5gzZw4cHBz0HWqrZGxsjClTpiA+Ph5FRUVISkrC+PHjUVhYiEmTJuHs2bPKurqsXbQxa9Ys2NraYufOnbh69Sri4uIwaNAgvPjii/XeFxwcrJJuU8HNzQ0PHz7EpUuXVMrHjBmDDz/8ED/++CO8vLxQWFiI6OhoneOuzcCBAxsl1tpo8zrs3bsXADBixAi1dhITExEREdFgf4+2M3LkSJVyY2Nj+Pv7o6KiotafT3XNw7Bhw9C3b19s27YNhYWFyvK1a9di9uzZT5TSWNevUw8PD5XnTk5OAIDbt28ryw4dOgQAGD58uEpdOzs79OzZU+eYa+u/c+fOav3T09O7d28sWLAAJ0+exI0bN7B+/XoAwLRp09C+fXvlmvPWrVuN0h83vhERERERERERNaLffvsNoaGhsLW1RWhoKC5evIj3338fMpkMWVlZiI2NhZeXFyQSib5DJWoSGzduxLfffotr167B398f7dq1Q1BQkPKP/fWRy+UoKSlBTU0NpFIpJBKJyuP3338HAFy5ckWruo+ysrKqte8OHToAAPLy8p5k+EQthoGBAdzd3bF06VJcunQJly9fxvvvv4/MzEyMGzcODg4OeP3113H+/Hm9xZiWlob4+HisW7cOhoaGeouDiIiaN29vb7z66quYP3++8kMZzdm9e/cwa9YsODo6ok+fPti+fTu8vLxw7Ngx5OXl4YcffsCUKVNgaWmp71DpEYaGhvDz88POnTuxYMECVFdXY8+ePQC0W+foysLCAhEREaiursaSJUsQExODqKioBu8rKSnBxx9/jL59+8La2loZ0/z58wEA9+/fV7snOjoaL7/8Mk6dOoUxY8bAwKBxt52Ym5s3WqyP0mW9aWJi8kTfaw21Y29vDwDIzc1Vu1bXPABAREQE7t+/j02bNgEAZDIZjh07hhkzZjxxrLp8nUqlUpXnig941tTUKNsuLS2FiYkJLCws1O63trbWOe7a+ld8TSr6J/3p0qULZsyYgYSEBOTk5OCrr75Chw4dsHjxYnTp0gWenp745ptvnqgPbnwjIiIiIiIiImpEJ06cwLFjxxAbG4vbt28jJSUF8+fPR/fu3fUdGtFTIZFIMHnyZBw9ehTFxcWIj4+HEAKjR4/Gp59+Wu+9xsbGsLKygqGhIR4+fFjnqThDhw7Vqu6jCgsLIYRQ61ux4U2xAY6IVPXq1QuLFi3Cf/7zH9y8eRNr167FgQMHcOrUKb3FFBkZCR8fn1pP4SB6FvTr10/tTeX6HsuXL9d3yETPrDVr1iAjIwP/+7//q+9QGpSfn4/Nmzfjtddew++//47r169jw4YNGDp0KNq0aaPv8AhASkqKcsNSbRRrkLt37wLQbp2joMuH5WbPng2pVIodO3bAzc0NAwYMaPCeUaNGITo6GtOnT4dMJkNNTQ2EEMoTmmpbO504cQIlJSXo27cvZs2a9dQ+CKFLrI/Sdr0plUpRWVmJ0tLSBmOr6/VqqJ07d+4AgNanNk6cOBH29vb44osvIJfLsW7dOrz55ptPtIFM1zW2pm1bWlqisrKy1pOj6/oAGj802rLY2trizTffxI8//oiCggL8+OOPePDgAbZv3/5E7XLjGxERERERERFRI7O1tcX06dPr/UM4UUtlZWWFjIwMAICRkRECAwMRHx8PiUSCAwcONHj/6NGjUVVVhZSUFLVrq1evRpcuXVBVVaV1XYXKykqcPn1apeyPP/7A7du34ebmho4dO2o8VqLWqnPnznjnnXfqPYWiqe3evRupqamIiYnRWwxEjWH37t0qbyaHhYUB+DuF2qPl48aN03OkRM+2Hj164O2330ZUVFSDp0I1F1OnTkX//v31HQbVQgiBvLw8pKWl1Xo9PT0dAFReP23XLmZmZnjw4IHyeY8ePfDll1/WG5dUKsW8efMglUo1Ou2turoaKSkpcHBwQHh4OOzs7JQbjSoqKmq95/r163j77bfx//7f/8O+fftgamqKkJAQ5OfnN9jfk9Al1tpo8zq89tprAICDBw+q1e3fvz/mzp2rfF7f66Vo5/H1sFwuR1JSEkxNTdXSfzbE2NgYs2bNQl5eHtatW4fvvvsOc+bM0aqNRxkaGiIjI0OnNbamFB9WUaQ8VcjNzYVMJqv1Hl2+D+jZoPjZ4enp+cRtceMbERERERERERERNaqZM2fiwoULkMvlyMvLw5o1ayCEgJ+fX4P3rly5Ei4uLvjnP/+JxMRElJSUoKioCHFxcVi2bBliYmKUKQ21qasglUqxePFipKamory8HOnp6Zg0aRLatm2L2NjYJpkPImpcQghER0dj3LhxcHd313c4RET0jFi6dCnu3r2Lr7/+Wt+hUAsxduxY7NixA7dv34ZcLseNGzcQExODZcuWwd3dHVOmTFHW1Xbt8tJLL0Emk+HmzZtITU3FtWvX4O3t3WBMH3/8MYqLizF48OAG67Zp0wa+vr7Izc3F2rVrUVBQgIqKChw/fhxbtmxRq19WVobQ0FBs2LABL7zwArp27Yo9e/bg9u3beP311/Hw4UMNZ0572sZaF23Xm87Ozpg7dy4OHDiA0tJSZGdnY9asWcjJyVHZ+Fbf66VoJyIiAvv370dpaSlkMhkmTJiAnJwcxMbG6vTByVmzZsHU1BRRUVEICAjA888/r3UbTzI/2lqxYgVsbGwQERGBI0eOoKysDBcvXsRbb71V54l3un4fUCsjiIiIiIiIiIio0axevVp07dpV32EQ6c25c+dEWFiY6NWrlzAzMxM2NjZi0KBBYuvWraKmpkYIIcTatWsFAJXHhx9+qGyjsLBQzJs3T3Tr1k0YGRkJOzs7MWzYMHHkyBG1/rSp6+bmJjp37iwuX74shg8fLiwtLYWpqanw8fERJ0+eVKufkJCgFqfisXXr1kacNaJnk62trdi0adNT7/fQoUMCgDh79uxT75uoqYWFhQkAIjExUd+hELVI77zzjnB2dhZVVVVPvW8PDw8xf/58lbJVq1YJZ2dnlbKrV68KACI9Pf1phkdaqK6uFidPnhSRkZHi5ZdfFp06dRKGhobC0tJSDBgwQKxYsUKUl5er3afN2iUjI0N4e3sLc3Nz4eTkJDZu3Ki8Zm5urrI2GT58eL3x1rae+fzzz4UQQuTn54uwsDDh5OQkjIyMhL29vZg6dapYuHChsq67u7t49913Ve7/448/RH5+vlq70dHRKn1/8803tfZfWlqqrJOamlprncdpGqtCSEiIACAqKip0fh0KCgpERESEcHZ2FkZGRqJjx45i/PjxQiaTafx61daOVCoVw4cPF0lJSVrPw6OmT58uAIhffvml1uuPf63U9/jzzz81np/aYlWs6R8vHzlypPK+zMxMERoaKtq1ayfMzMzE4MGDxS+//CJ8fX2FmZmZWvx1zauu/VPz8+677wofHx+VsmPHjgkAIi8vT6W8rvWnRIgGEh0TEREREREREZHG1qxZg82bN+P69ev6DoWIHtOvXz8UFBQgOztb36EQtQjt27dHdHQ03nnnnafab1BQEKqqqnD06NGn2i/R0zBz5kzExcUhMTERQUFB+g6HqMW5cuUKevbsid27d2P06NFPte+BAwfC19cXa9asUZatXr0acXFxuHbtmrIsKysLzz//PNLT03myKdETGDVqFA4ePAi5XK7zKWXN3TfffIONGzcq0+s+q3r27ImKigr89ddf+g6FnrL33nsPFy9exIkTJ5Rlx48fh5+fH/Ly8mBnZ6csr2v9yVSnRERERERERERERET0TLh06RJ+/vlnldRSRK1FfHw8JBKJ8pGZmYmxY8fC1tZWWRYREaH8t5eXl/LeQ4cOKcvbt2+v1nZ+fj7Cw8PRtWtXtG3bFnZ2dhg9ejTOnTv3NIdI1OS6d++OUaNGYd26dfoOhYgaWZ8+fXDjxg3l81u3bqFLly4tdtMbAGzZsgXz5s3Tdxgayc3NhY2NjVpK3Bs3biArKwt+fn56ioyeddz4RkREREREREREREREz4T169eje/fuGDFihL5DIXrqQkNDIYRASEgIACAsLAyzZs3CzZs3kZaWhjZt2iAqKgpCCJibm6vcGxQUBCFEradH5eTkwMPDAz/88AM2bdqEoqIinDhxAkVFRfD09ERqaupTGR/R0zJv3jycOnUKaWlp+g6FiBrZ2rVrUVZWhn379uHcuXOYOXOmvkNqVF999RVee+01lJWVYcuWLbh79y7Gjh2r77A0dvfuXYSFheHmzZu4f/8+fvvtN4wbNw7t2rXDRx99pO/w6BnFjW9ERERERERERETUosXExEAikeD8+fO4desWJBIJoqKi9B0WEWnp3r172LFjByIiImBgwLc3iBYsWABfX1+YmZnh5ZdfRlVVVa2nuTVk0aJF+Ouvv/Dpp5/ilVdegYWFBXr37o1du3ZBCIHZs2c3QfRE+vM///M/cHd3x+bNm/UdChE1oq+//hqXLl1Cx44d8f7772PFihWIjIzUd1iNLj4+HtbW1ti8eTN27dr1zJxwOuQ3AAAgAElEQVRo5+DggKNHj6K4uBj/8z//A2tra7z66qvo3r07fvvtN3Tr1k3fIdIz6tn4DiAiIiIiIiIiIiLSUWRkZIt8w4Ootfnxxx9RXV2NcePG6TsUomZh4MCBjdJOfHw8DAwMEBwcrFLu4OCA3r1748yZM8jOzoajo2Oj9EfUHEyePBkfffQRtmzZAlNTU32HQ0SN4OWXX8aJEyf0HUaTmjZtGqZNm6bvMHTm7+8Pf39/fYdBLQw/EkVERERERERERERERM3erl27MGLECNjY2Og7FKJm4fF0prqQy+UoKSlBTU0NpFIpJBKJyuP3338HAFy5cuWJ+yJqTsaNG4f79+/j4MGD+g6FiIiIngA3vhEREREREREREZGSIi2oRCJ55k92qa6uxpYtWzB48GBIpVIYGRmhU6dOeOWVV/DFF1/gxo0byrotadxELVF+fj6SkpIwfvx4fYdC9EwwMDDAgwcP1MqLi4tVnhsbG8PKygqGhoZ4+PAhhBC1PoYOHfq0Qid6KhwcHODj44Ndu3bpOxQinbTE9cvp06cxdepUODs7w9TUFDY2NujTpw/+8Y9/YPPmzcjKytJ3iDqp67UqKytT23CempraYHvz589XuWf58uVNGT5Rs8eNb0RERERERERERKQUGRkJIQTc3Nz0HcoTmzx5Mt59912Ehobi0qVLKC0tRXJyMvr374/w8HAMGDBAWbcljZuoJdq9ezfatm2rloqRiGrXsWNH3Lp1S6UsNzcX//3vf9Xqjh49GlVVVUhJSVG7tnr1anTp0gVVVVVNFiuRvowfPx779+9HSUmJvkMh0lpLWr/U1NRg/vz5GDx4MDp06IDExEQUFxfjzz//xPr163Hv3j3MmjULzz///DP5/1Fdr5WFhQWEEDh79qyyLDo6ut62CgsLsWXLFgDAxIkTIYRAVFRUo8dcVlaG7t2783dveiZw4xsRERERERERERG1OKdPn8bOnTvx9ttv44MPPoCjoyNMTEzg4uKCTz75BO+8846+QyQiLezZswevvvoqLCws9B0K0TNh2LBhuH37Nr744guUlZUhKysLc+bMQYcOHdTqrly5Ei4uLvjnP/+JxMRElJSUoKioCHFxcVi2bBliYmJgaGioh1EQNa1//OMfqK6uZrpTIj376KOPEBMTg02bNmHNmjXo2bMnjI2NYW9vj8DAQBw6dAgjRozQd5hNytTUFM899xwSExORnp5eZ73169fDycmpUfq0sLCAl5dXrdeEEKipqUFNTU2j9EXUlLjxjYiIiIiIiIiIiFqcS5cuAQB69OhR6/WxY8c+zXCI6AnI5XKkpqYiKChI36EQNZlt27ZBIpEgLi4OADBixAhIJBKUlZUp66SlpUEikeCnn34C8Peb5BKJpNb2li9fjmnTpmHFihXo0KEDpk6divnz58PBwQGFhYWQSCRYuHAhAKBDhw747bffEBoaivfeew92dnbo2bMnfvzxR/z000/8P5NaLBsbG3h4eOD48eP6DoWo1crIyMCqVavg7u6O6dOn11qnTZs2+Oijj55yZE+XgYGB8v/lulKXFhcXY/PmzViwYEGTx2NpaYmsrCxuDKZnAj+eQURERERERERERC2Ovb09AODIkSN4//331a77+PigoKDgaYdFRDpIS0tDZWUlfHx89B0KUZOZOnUqpk6dWm+dQYMGQQihUXtSqRRbt25VK6/rFBkbGxusW7cO69at06h9opbC19cXe/bs0XcYRK3Wl19+iZqaGowZM6beep6enhr/H/iseuutt7B8+XLs27cPFy5cwIsvvqhy/bPPPsMrr7wCFxcXPUVI1DzxxDciIiIiIiIiIqJWpLCwEPPmzYOLiwuMjY3h6OiIgIAAbNu2DRUVFfXeW1VVhe+//x6BgYFwcHCAqakp+vbti9jYWLUUKHK5HB9//DF69uwJMzMz2NjYYNSoUdi3bx+qq6u1rqctb29vODg44PDhwxgxYgROnDjxRGla8vPzER4ejq5du6Jt27aws7PD6NGjce7cOZ3qxsTEQCKRQCKRwNHREadPn4a/vz8sLS1hZmaGoUOHIiUlRed4iVqSX3/9FU5OTujatau+QyEiohbGx8cHMpkMt2/f1ncoRCpay7rt119/BQC1TV4N0XSM8fHxynWXRCLBjRs3MG7cOFhZWcHW1hbBwcHIyspSa1/T+ddmndgQY2NjzJ8/H0IIfPLJJyrXysrK8Pnnn2Px4sX1tvFo3G3btoW1tTVGjBihcrKlYi1aXl6OlJQU5dwo0po/PmeVlZVa96HrvBPpghvfiIiIiIiIiIiIWonc3Fx4eHhg586diI2NRUFBAc6cOQNfX1+89dZbyvRqdTl06BDGjx8PPz8//Pnnn7h58yZmzJiBefPmqaVbee+99/DZZ5/h888/R2FhIf7880/07NkTISEhSE5O1roeAPj5+cHW1hZpaWkNjtXCwgK7d++Gk5MTDh06hKFDh6Jjx46YNGkSdu7cifv372s8bzk5OfDw8MAPP/yATZs2oaioCCdOnEBRURE8PT2Rmpqqdd3IyEgIIeDm5obi4mLMmTMHy5cvR25uLn799VcUFRXBz88Pv/zyi8ZxErVUv/zyC3x9ffUdBhERtUCDBw+GkZGR2u+dRPrUmtZtik2ntra2mk6PVmMMDQ2FEAIhISEAgIiICERERODWrVv4/vvvcezYMbzxxhsqbWs6/9qsEzU1Y8YM2NvbY8+ePfjzzz+V5Rs3boSfnx969epV572KuHfs2KGM+z//+Q/MzMzg7++Pr776CsD/rUXNzc0xZMgQCCEghEBVVVWtc6ZLH7rMO5GuuPGNiIiIiIiIiIiolVi0aBGuX7+O2NhYBAcHw9LSEvb29oiKikJQUJBGbfj6+mLRokWwtrZG+/btMXv2bEyYMAGxsbG4d++esl5SUhJ69+6NwMBAmJqawt7eHmvXroWrq6tKe5rWA4CamhrlH+U14eXlhStXrmD79u0ICQlBRUUFvvvuO0yYMAFdunTBrl27NGpn0aJF+Ouvv/Dpp5/ilVdegYWFBXr37o1du3ZBCIHZs2frVFehvLwcmzZtgqenJ8zNzTFgwAD8+9//xoMHDzBnzhyNYiRqqR4+fIi0tDSmOSUioiZhYWEBd3d3ftiAmpXWtm4DAIlEonFdbcf4qGnTpinXXQEBARg5ciROnz6NgoICZR1N51+XtV9DTE1NMW/ePNTU1GDFihUAgPv372P9+vX48MMP671XEfeGDRsQHByMdu3awdXVFTt27EDHjh0RHh6OO3fuaB1TY/ShybwT6Yob34iIiIiIiIiIiFqJvXv3AgBGjBihdi0xMRERERH13h8cHKySvkTBzc0NDx8+xKVLl5RlQUFBOHXqFGbMmIG0tDRl+pvMzEyVk5s0rQdA5dPzmjI2NsaUKVMQHx+PoqIiJCUlYfz48SgsLMSkSZNw9uzZBtuIj4+HgYEBgoODVcodHBzQu3dvnDlzBtnZ2VrXVTA3N0e/fv1Uyvr27YtOnTrh/PnzyMnJ0Xi8RC3N1atXUV5eDg8PD32HQkRELZSHhwfOnz+v7zCIlFrTuq1Tp04AoPUGKG3G+KjHf6d0cnICAJV0x5rOvy5rP03MmjULtra22LlzJ65evYq4uDgMGjSowXSwirhHjhypUm5sbAx/f39UVFTg8OHDWsfTGH1oMu9EuuLGNyIiIiIiIiIiolZALpejpKQEJiYmsLS01KmNkpISfPzxx+jbty+sra0hkUggkUgwf/58AFBJH7px40Z8++23uHbtGvz9/dGuXTsEBQUp/1Cubb3GYGhoCD8/P+zcuRMLFixAdXU19uzZU+89inmrqamBVCpVjlnx+P333wEAV65c0aruo6ysrGrtu0OHDgCAvLy8Jx060TMrMzMTEokELi4u+g6FiIhaqO7du6v9fkakL61t3aY41ffChQtNNsZHSaVSledt27YF8PcpdYDm86/r2k8TFhYWiIiIQHV1NZYsWYKYmBhERUXVe09Dcdvb2wP4O1Wprp6kj4bmnehJcOMbERERERERERFRK2BsbAypVIrKykqUlpbq1MaoUaMQHR2N6dOnQyaTKVPYrF+/HgBUUtlIJBJMnjwZR48eRXFxMeLj4yGEwOjRo/Hpp59qXU9bKSkpyj+812bo0KEAgLt379bbjrGxMaysrGBoaIiHDx8qU/Y8/hg6dKhWdR9VWFhYaxogxYY3xQY4otZIJpPB0dER5ubm+g6F9Cw+Pl7lDeXKyspGazsmJkbZrqOjY4P1d+3apaxvYmLSaHHoW0sdF1FDXF1dkZ+fj6KiIn2HQtTq1m1hYWEwNDRs8ANJH3zwAQwMDJCRkaH1GLWh6fzruvbT1OzZsyGVSrFjxw64ublhwIABTxS3Iv2og4ODskzb9LK69EH0NHDjGxERERERERERUSvx2muvAQAOHjyodq1///6YO3dunfdWV1cjJSUFDg4OCA8Ph52dnfIP5RUVFWr1rayslG9KGBkZITAwULlp4cCBA1rX05YQAnl5eUhLS6v1enp6OoC/x92Q0aNHo6qqCikpKWrXVq9ejS5duqCqqkrrugqVlZU4ffq0Stkff/yB27dvw83NDR07dmwwRqKW6sqVK3B1ddV3GNQMhIaGQgiBkJCQRm87MjISQgi4ublpVH/8+PEQQsDf37/RY9Gn+sZVVlaG7t27q6Vza4iu9xE9Td27dwfwd3ptouagNa3bXF1dsWTJEqSnp+Nf//pXrXUyMzMRFxeHsWPHomfPnlqPUVuazr8uaz9NSaVSzJs3D1KptMHT3h6P+/HXQy6XIykpCaamphg+fLiy3MzMDA8ePFA+79GjB7788stG7YPoaeDGNyIiIiIiIiIiolZi5cqVcHZ2xty5c3HgwAGUlpYiOzsbs2bNQk5OTr1voLRp0wa+vr7Izc3F2rVrUVBQgIqKChw/fhxbtmyp9Z6ZM2fiwoULkMvlyMvLw5o1ayCEgJ+fn071/Pz8YGtrW+dmttqMHTsWO3bswO3btyGXy3Hjxg3ExMRg2bJlcHd3x5QpUxpsY+XKlXBxccE///lPJCYmoqSkBEVFRYiLi8OyZcsQExMDQ0NDresqSKVSLF68GKmpqSgvL0d6ejomTZqEtm3bIjY2VuOxErVEV65cUW5IICL9EUKgpqam1pRkFhYW8PLy0vo+ouaia9euMDY2hkwm03coRABa37otKioKCxcuxMyZM7Fw4ULIZDI8ePAAt27dwtdff42hQ4fixRdfxNdff63zGLWh6fzrsvbTxscff4zi4mIMHjxYq7gjIiKwf/9+lJaWQiaTYcKECcjJyUFsbKzKqegvvfQSZDIZbt68idTUVFy7dg3e3t6N2gfRUyGIiIiIiIiIiKjRrF69WnTt2lXfYRDVqaCgQERERAhnZ2dhZGQkOnbsKMaPHy9kMpkQQoi1a9cKACqPDz/8UAghRH5+vggLCxNOTk7CyMhI2Nvbi6lTp4qFCxcq67q7uwshhDh37pwICwsTvXr1EmZmZsLGxkYMGjRIbN26VdTU1Cjj0bSeEEJ4e3sLa2trcerUqQbHWV1dLU6ePCkiIyPFyy+/LDp16iQMDQ2FpaWlGDBggFixYoUoLy9X1q9v3EIIUVhYKObNmye6desmjIyMhJ2dnRg2bJg4cuSIWt/a1HVzcxOdO3cWly9fFsOHDxeWlpbC1NRU+Pj4iJMnTzY4TiJ9srW1FZs2bWrSPp577jmxevXqJu2Dni0hISECgKioqGj0thU/kzXl7+8vjI2NGz0OfdN2XObm5mLIkCFNGBFR03N1dRXLli1r0j48PDzE/PnzVcpWrVolnJ2dVcquXr0qAIj09PQmjYeat9aybnvUb7/9JiZPnqyM29LSUgwaNEjExsYKuVyuUlfTMaamptY5T4+Xjxw5UuP5V9Bk7Vffa2Vubq5SPnz48Hrn6PF2AIjPP/+8zrilUqkYPny4SEpKUmsrIyNDeHt7C3Nzc+Hk5CQ2btwohBBi7969an1MnDhRqz50nXdqfd59913h4+OjUnbs2DEBQOTl5amU17X+lAihY3JjIiIiIiIiIiJSs2bNGmzevBnXr1/XdyhE9Azo168fCgoKkJ2dre9QiLTWvn17REdH45133mmyPmxsbLBq1SrMmDGjyfqgZ0toaCh++uknVFRUwMTEpFHb1vZnckBAAE6ePInKyspGjUPftB2XhYUF+vXrh5MnTzZxZERNx8PDA0OHDsWaNWuarI+BAwfC19dXpY/Vq1cjLi4O165dU5ZlZWXh+eefR3p6Otzd3ZssHiIiIn177733cPHiRZw4cUJZdvz4cfj5+SEvLw92dnbK8rrWn0x1SkREREREREREREREzVJZWRksLCz0HQY1Q7m5uRg3bhysrKxga2uL4OBgZGVlqdUrLCzEvHnz4OLigrZt28La2hojRozA8ePHNe4rIyMDoaGhkEqlMDc3h7e39xNv8no0LmNjYzg6OiIgIADbtm1DRUWFVvHHx8dDIpEoHzdu3NBobjQd1+PtKzbExcTEQCKRoLy8HCkpKcrrirRudd33NMZGpC1LS0uUlpbqOwwiIiLSEje+ERERERERERERERFRs1NZWYmHDx9y4xvVKiIiAhEREbh16xZ2796N5ORkvPHGGyp1cnNz4eHhgR07diA2NhYFBQX4z3/+AzMzM/j7++Orr75qsJ+rV6/C09MT6enp2LNnD+7cuYNNmzYhOjpa5w1Xirh27typjOvMmTPw9fXFW2+9hbi4OK3iDw0NhRACISEhanPz/fff49ixY2pzo824Hm9fITIyEkIImJubY8iQIRBCQAiBqqqqeu9r6rEBgJ+fH2xtbZGWlqb160OtEze+ERERPZu48Y2IiIiIiIiIiIjoKVOcknP+/HncunULEokEUVFR+g6LqFkpKysD8PdmBKLHTZs2DZ6enjA3N4efnx+Cg4Nx+vRpFBQUKOssWrQI169fx4YNGxAcHIx27drB1dUVO3bsQMeOHREeHo47d+7U28/ixYtRXFyM2NhYBAYGwsLCAn379sU333yDnJwcnWJXxBUbG4vg4GBYWlrC3t4eUVFRCAoKeuL4H52bgIAAjBw5Um1ummJcusxBU4wNAGpqapQb8Yg0YWlpqfx/h4iIiJ4d3PhGRERERERERERE9JQpTsl59LF8+XJ9h0XUrCg2IJibm+s5kubp4sWLKikgJRIJ3nvvvRZb/jgPDw+V5507dwYA3L59W1m2d+9eAMDIkSNV6hobG8Pf3x8VFRU4fPhwvfN86NAhAMDw4cNVyjt16gRXV1cNXy1VirhGjBihdi0xMRERERFPFP/jc+Pk5ARAdW6aYlzaaMqxAcCJEydQVFQET09PAK3v+0XT7yP6PzzxjYiI6NlkqO8AiIiIiIiIiIiIiIiIHtemTRsAf5/cROr69OlT52lWLbX8UVKpVOW5gcHfZz0ovl7kcjlKSkpgYmJS66mB9vb2AP5OuVkXuVyO0tJSmJiY1Jpyt0OHDpDJZA3G+nib9cWlab364n98btq2bQtAdW4ae1zaaMqx1aU1fr/wtDvtVFVVKf/fISIiomcHT3wjIiIiIiIiIiIiesyuXbuUJ6SYmJjoOxyiVkmxIYep50gXxsbGkEqlqKysrPUUJ0UaTQcHh3rbsLS0RGVlZa1fh0VFRY0eV2PGX1/bjTkuiUSidf9NNTYiXZWWljK1NhE1Kq4piZ4ObnwjIiIiIiIiIiIiesz48eMhhIC/v7/atbKyMnTv3h3BwcFatanrfUStlWIDAlPPka5ee+01AMCBAwdUyuVyOZKSkmBqaqqW6vNxinSkitSgCgUFBcjMzHyiuA4ePKh2rX///pg7d26jxV+XxhyXmZkZHjx4oHzeo0cPfPnll/Xe05RjI9JFWVkZN74RUaPimpLo6eDGNyIiIiIiIiIiohbEwsICXl5eLba/5kAIgZqamlrTqtU3H/XdR0TqDA0NYWJiwhPfSGcrV66Es7MzIiIisH//fpSWlkImk2HChAnIyclBbGysMq1mXVasWAEbGxtERETgyJEjKCsrw+XLlzFp0qRa04RqE9fcuXNx4MABlJaWIjs7G7NmzUJOTo5y41tjxP80xvXSSy9BJpPh5s2bSE1NxbVr1+Dt7a3RHDTF2ADAz88Ptra2SEtL07kNal144hvR/+GasulxTUnUeLjxjYiIiIiIiIiIiEgLlpaWyMrKqvWknqa4j6g1s7Cw4IlvBABIS0uDRCLBTz/9BAAwNTVFVFQUgL9Tba5evRrA3yemKU5BcXBwwOnTp/HGG28gPDwctra2GDhwIMrLy3H06FFMnz4dABATEwOJRILz58/j1q1bkEgkyrZdXFyQmpoKDw8PvP766+jQoQOmTp2K2bNno2/fvpDL5ZBIJJg2bZrGY1HENW7cOMyePVsZ1927d5GcnIwuXbpoFb8uc6PNuOLj49XanzRpknI8GzZswIsvvohevXph3LhxiI2NRa9eveq9rynHBgBVVVUQQkAIofHrQq1baWmpzptZiYi0xTUlUeMx1HcAREREREREREREREREtbGxsUFhYaG+w6BmYNCgQXVuYqpvc5OtrS3Wr1+P9evX11knMjISkZGRdV53dXXF3r171cpHjhxZT8T10yQuTevpOjfajKu+dnr06IFff/1VrTw0NPSJXxtdx1ZbPET1KSoqgrW1tb7DICIiIi3xxDciIiIiIiIiIqJmTi6X4+OPP0bPnj1hZmYGGxsbjBo1Cvv27UN1dTWA/zutpry8HCkpKZBIJJBIJDA0/L/PvlZVVeH7779HYGAgHBwcYGpqir59+yI2NlYlVYrihBbFIzMzE2PHjoWtra2ybOHChQ32p6nCwkLMmzcPLi4uMDY2hqOjIwICArBt2zZUVFTUWq9t27awtrbGiBEjcPz48Tpjv3HjBsaNGwcrKyvY2toiODgYWVlZajFkZGQgNDQUUqkU5ubm8Pb2xsmTJ9XqPd5+ZWWlRvNf131PY2xEzzIXFxdcvXpV32EQEVELJpfLcfPmTTz//PP6DoWoyXBNqV6Pa0quKamFEERERERERERE1GhWr14tunbtqu8wqIWZNm2akEql4ueffxb3798Xubm5IjIyUgAQx48fV6lrbm4uhgwZUms7CQkJAoBYsWKFKCoqEvn5+eKzzz4TBgYGIjIyUq1+SEiIACB8fHzE8ePHRXl5uUhLSxNt2rQR+fn5DfaniZycHOHs7CwcHBxEQkKCuHfvnsjNzRXR0dECgFi/fr1KPXt7e5GQkCBKSkpEZmamGD16tJBIJGLr1q21xh4SEiJOnTolysrKxJEjR4Spqanw8PBQqXvlyhVhZWUlOnfuLH7++WdRWloqLly4IIYNGya6du0qjI2N65ybiooKlfKG5qO2+5pybEIIMXToUGFjYyNSU1PrjItIF7a2tmLTpk1N2secOXOEp6dnk/ZBRESt2x9//CEAiD/++KNJ+/Hw8BDz589XKVu1apVwdnZWKbt69aoAINLT05s0HmpduKbkmlLXsQnBNSU1nXfffVf4+PiolB07dkwAEHl5eSrlda0/eeIbERERERERERFRM5eUlITevXsjMDAQpqamsLe3x9q1a+Hq6qp1W76+vli0aBGsra3Rvn17zJ49GxMmTEBsbCzu3btX6z0LFiyAr68vzMzM8PLLL6Oqqgrt27d/0mEBABYtWoTr168jNjYWwcHBsLS0hL29PaKiohAUFKRWb8OGDQgODka7du3g6uqKHTt2oGPHjggPD8edO3fU2p82bRo8PT1hbm6OgIAAjBw5EqdPn0ZBQYGyzuLFi1FcXIzY2FgEBgbCwsICffv2xTfffIOcnJxGGacmc9AUYwOAmpoaCCHqTQlH1Fx1794dmZmZ+g6DSCOPnqBS12Pp0qX6DpOIHiOTyWBgYAAXFxd9h0LUZLim5JqSa0pqqbjxjYiIiIiIiIiInikXL15UexP5vffea7HlABAUFIRTp05hxowZSEtLU6aiyczMhK+vr8ZzFxwcrJLmRMHNzQ0PHz7EpUuXar1v4MCB2r9QGtq7dy8AYMSIEWrXEhMTERERoVJv5MiRKnWMjY3h7++PiooKHD58WK0NDw8PledOTk4AgNu3byvLDh06BAAYPny4St1OnTrp9EaQtppybABw4sQJFBUVwdPTE0Dr/B6iZ5erqyuKiopQVFSk71CIGqR4Q7i+Bze+ETU/V65cgZOTE0xNTfUdCj0lze33Va4pnwzXlFxTck3ZummfHJmIiIiIiIiIiEiP+vTpU+enjFtq+caNG+Hp6Ynt27fD398fAODt7Y2wsDC89tprtd5Tm5KSEqxbtw579+5FdnY2iouLVa7fv3+/1vvMzc017kMbcrkcJSUlMDExgaWlpc717O3tAQC5ublq16RSqcrztm3bAvj7E+uKtktLS2FiYgILCwu1+zt06ACZTKb5oLTUlGOrS2v8HqJnl+KNwoyMDAwePFjP0RARUUuUmZn5VDamUPPRGn8f5pqSa0quKZ+snJovnvhGRERERERERETUzEkkEkyePBlHjx5FcXEx4uPjIYTA6NGj8emnn6rVrcuoUaMQHR2N6dOnQyaTKdOVrF+/HoBuf+Ctr7+GGBsbQyqVorKyEqWlpTrXU6RscXBw0CkGS0tLVFZWoqysTO26tqdMaTsfTTk2opagS5cusLe3x6lTp/QdClGjsrCwUDtRpK7HV199pVGbMTExynscHR2beARELUdKSoraqUdELQ3XlFxTck1JLRU3vhERERERERERETVzVlZWyMjIAAAYGRkhMDAQ8fHxkEgkOHDggEpdMzMzPHjwQPm8R48e+PLLL1FdXY2UlBQ4ODggPDwcdnZ2yj+oV1RU6BxbXf1pSnG6wMGDB9Wu9e/fH3PnzlWp9/h45XI5kpKSYGpqqpZWRlOKlDiK9DQKBY7kvhoAACAASURBVAUFyMzM1KotXeajKcdG9KyTSCTw9vbGL7/8ou9QiBpVWVkZzp49CwAICQmpMzWqj4+Pxm1GRkZCCAE3N7emCpuoxcnNzYVMJtPqe43oWcQ1JdeUXFNSS8WNb0RERERERERERM+AmTNn4sKFC5DL5cjLy8OaNWsghICfn59KvZdeegkymQw3b95Eamoqrl27Bm9vb7Rp0wa+vr7Izc3F2rVrUVBQgIqKChw/fhxbtmzROa66+tPUypUr4ezsjLlz5+LAgQMoLS1FdnY2Zs2ahZycHOWbFIp6ERER2L9/P0pLSyGTyTBhwgTk5OQgNjZWmcJFWytWrICNjQ0iIiJw5MgRlJWV4fLly5g0aVKtqWrqo8t8NOXYAMDPzw+2trZIS0vTuQ0iffLx8UFycjKqq6v1HQoREbUwv/zyCwwNDeHp6anvUIiaHNeUXFPqimtKatYEERERERERERE1mtWrV4uuXbvqOwxqYc6dOyfCwsJEr169hJmZmbCxsRGDBg0SW7duFTU1NSp1MzIyhLe3tzA3NxdOTk5i48aNymv5+fkiLCxMODk5CSMjI2Fvby+mTp0qFi5cKAAIAMLd3V2kpqYqnz/6qE19/WmqoKBARERECGdnZ2FkZCQ6duwoxo8fL2QyWb31pFKpGD58uEhKSlLWqS32Dz/8UAgh1MpHjhypvC8zM1OEhoaKdu3aCVNTU+Hh4SH+P3v3HhVlufcN/DuAHJQ4nxRlC6QltE1fdKcBywMgQjOA6CC1gw4WWtvALB9qdZCUdpqaYjsLrb2Dnp6EyTjMGCiYFAiuJ8h2WxQxSQU5g3KQQwLX+0cv84qAAgIj+v2sxVp6zzXX/btu4B7ume99XSqVSnh4eKjbr1q1SiQlJfXq569//estj8etnjeSY3N3dxempqYiNzd30N8bopsxNzcXe/bsGfH9/PLLLwKA+Omnn0Z8X0Sj6cSJEwKA8Pf3H9Z+H374YWFrazusfRLdrV544QXxyCOPjMq+5s6dKzZs2NBj25YtW4S9vX2Pbb/++qsAIPLz80elLro38Jqy73a8puQ1JWnW3/72N7FgwYIe27777jsBQFRXV/fY3t/1p0SIISyyTEREREREREREfXr//ffx8ccf47ffftN0KURERCPKwsICmzdvxgsvvDCi++nq6oKVlRXeeOMN9YwdRHeDn3/+GbNnz4a/vz+Sk5N7PLZ27Vro6Ohg165dg+531qxZqK2tRVlZ2XCVSnTXcnZ2hlQqxdatW0d8X3/5y1+wcOFCvP/+++ptW7duRWxsLEpKStTbzp07h/vvvx/5+flwcXEZ8bqIiIg0Ze3atTh58iSysrLU244ePYrFixejuroalpaW6u39XX9yqVMiIiIiIiIiIiIiIrpjaWlpwdPTE6mpqZouhUgjOjo6kJCQAC8vL9jY2MDAwAB//vOfERMTg66urgH10d7ejrfffhsPPvggxo8fDzMzM8hkMqSmpvZaRrimpgbh4eGYOnUqdHV1YWlpicDAQPz8888jMTwijTl79ixOnTqFJUuWaLoUIiIiGiIG34iIiIiIiIiIiIiI6I62cuVK/PDDD7h06ZKmSyEadikpKZBIJD2+PvroI/Xj6enpCA4OxuLFi3H69GmUlpYiLCwM69evR2Rk5ID2sXbtWuzevRsffvgh6urqcPr0aTz44IPw9/dHdna2ul1FRQXmzp2LxMRE7NmzB/X19cjKykJ9fT3mz5+PvLy8YR8/kaZ89dVXsLKywoIFCzRdChEREQ0Rg29EREREREREREQ07G78AL+vr6ioKE2XSURjhK+vL4yMjJCYmKjpUoiGnb+/P4QQPb7+9re/9WizcOFCvP766zA1NYWFhQVeeuklPPHEE4iJiUFjY+Mt93HkyBE4OzvDy8sLBgYGsLa2xrZt2zB9+vQe7V5//XVcuHABH3zwAXx9fWFoaAhnZ2fs378fQgi89NJLwzp2Ik1KTEzEypUroaOjo+lSiKgPvKYkooFg8I2IiIiIiIiIiIiG3Y0f4Pf1xQ8piGig9PT0EBAQgP3792u6FKJRJ5VKcfTo0V7bH374YVy7dg2FhYW37GPp0qXIzc1FWFgYjh8/rl7e9MyZM1i4cKG6XXJyMrS0tCCVSns838bGBs7OzigoKEBZWdntDYjoDvDvf/8bhYWFCA4O1nQpRNQPXlMS0UAwvk5ERERERERERERERHe84OBgLF26FGfPnsW0adM0XQ7RiPrHP/6h/ndDQwN27NiBpKQklJWV4cqVKz3atrS03LK/jz76CPPnz0dcXBw8PDwAAO7u7li9ejWWLVsGAGhvb0dDQwMAwNjYuN++zp49i8mTJw96TER3kv3798POzg7z58/XdClERER0GzjjGxEREREREREREY2aWbNmDWjJmu6v6OhoTZdMRHcIDw8P2NjY4F//+pemSyEaVTKZDJs3b8bzzz+P4uJidHV1QQiBnTt3AvhjRpxbkUgkCAkJQWZmJq5cuYLk5GQIIRAYGIgPPvgAwB8zK5qYmEBHRwfXrl3rd3adRYsWjeh4iUba77//ji+++AJPPPEEJBKJpsshokHiNSURXY/BNyIiIiIiIiIiIhpVCoWixwfoq1evBgCkpaX12L5y5UoNV0pEdxIdHR28+OKL+OSTT9Dc3KzpcohGRWdnJ44dOwYbGxuEh4fD0tJSHdRpbW0dcD8mJiYoKioCAIwbNw5eXl5ITk6GRCLBwYMH1e0CAwPR0dGBY8eO9epj69atsLOzQ0dHx22Oikiz9u/fj+rqarzwwguaLoWIhojXlETUjcE3IiIiIiIiIiIiIiIaE/72t7/h999/R1xcnKZLIRoV2traWLhwISorK7Ft2zbU1taitbUVR48exSeffDKovtasWYNffvkF7e3tqK6uxvvvvw8hBBYvXqxu895778HR0RHPPvss0tLS0NDQgPr6esTGxmLTpk3Yvn07dHR0hnuYRKNq586dCAoKgp2dnaZLISIiotvEv0yJiIiIiIiIiIho1Pz8888Dbrt///4RrISIxiIzMzM8+eST+OCDD7BmzRpoa2truiSiITE0NMTVq1cBACkpKZBIJLC2tkZlZWWvtgkJCXjzzTfx4Ycf4o033oCZmRl8fHzwxBNPYMuWLfDy8oKLiwuCg4OxYcMG9fMkEgneeOMNREdH4/vvv8fHH3+M4OBgXLhwAfr6+pg+fTr27duHVatWqZ9jZWWF//3f/8W7776LtWvXorS0FCYmJpg9ezZSUlLg6ek58geHaARlZmbi559/xt69ezVdChENEa8pieh6DL4REREREREREREREdGYsX79euzbtw8qlQr+/v6aLodoSAazXK+FhUW/s7u99957Pf7/6quv9tnu4YcfHvAMcWZmZtixYwd27Ngx4BqJxoodO3Zg4cKFmDt3rqZLISIiomHApU6JiIiIiIiIiIjojpWcnAyJRKL+OnPmDIKCgmBubq7etm7dOvW/3dzc1M9NT09Xb7ewsOjVd01NDcLDwzF16lTo6urC0tISgYGBg5pBgIhG3/Tp0+Hr64u///3vEEJouhwiIhojCgoKcOjQIbzyyiuaLoWIRhGvKYnubgy+ERERERERERER0R0rICAAQgj1rE6rV6/Giy++iNLSUhw/fhza2tp48803IYTAhAkTejx36dKlEELAxcWlV78VFRWYO3cuEhMTsWfPHtTX1yMrKwv19fWYP38+8vLyRmV8RDQ07777LvLz85GYmKjpUoiIaIyIjIzEI488gscee0zTpRDRKOI1JdHdjcE3IiIiIiIiIqJhVl5ejscffxwJCQlobGzUdDlEd5XIyEgsXLgQ48ePxyOPPIKOjo4+77y/lddffx0XLlzABx98AF9fXxgaGsLZ2Rn79++HEAIvvfTSCFRPNPZdvnwZX375JeRyOa5cuaKxOmbOnImQkBC8/vrraG9v11gdREQ0NqhUKhw5cgTbt2+HRCLRdDkDsnbtWnzwwQcoKSnRdClEdxVeUxJpVkdHB44ePYqIiAh8/fXXt90fg29ERERERERERMMoNDQU27ZtQ1VVFZ588klYWVnBx8cHsbGxqKio0HR5RGPeX/7yl2HpJzk5GVpaWpBKpT2229jYwNnZGQUFBSgrKxuWfRGNdWVlZfjoo4/g5eUFa2trPPPMM2hoaMDu3buxYsUKjdX17rvvoqqqCnv27NFYDUREdOfr7OzEa6+9huXLl8PV1VXT5dySnZ0dFAoF7r//fkRHR8PR0REzZ87E22+/jZ9++knT5RGNebymJBp9LS0tSEpKwtNPPw0bGxssXrwYR44cwapVqxATE3NbfesMU41ERERERERERIQ/3uAMDw9HeHg46uvrceTIESiVSmzYsAFr1qyBk5MT5HI5goKC4OTkpOlyicacG5eeGYr29nY0NDQAAIyNjfttd/bsWUyePPm290c0FpWUlECpVEKhUCA3NxcGBgZYvHgxPv30U/j5+cHExETTJcLW1hYRERHYvHkznnrqKZiZmWm6JCIiugP985//RHFxMZKSkjRdyoCMGzcOK1aswIoVK9DZ2Ym8vDwoFAp8/vnn2Lx5M+zs7LB06VJIpVJ4e3tDV1dX0yUTjSm8piQaHfX19VCpVFCpVEhLS0NLSwtmz56NtWvXYuXKlZgxY8aw7IczvhERERERERERjRAzMzPI5XLEx8ejuroaGRkZ8PT0RGxsLJydneHo6IiIiAjk5OSgq6tL0+USjXlaWlr4/fffe22/cTlGPT09mJiYQEdHB9euXYMQos+vRYsWjVbpRBrX1dWFgoICREVFwcnJCY6OjoiOjoaDgwMSEhJQXV0NpVKJ0NDQOyL01u21116Djo4O3n77bU2XQveQ/fv3QyKRQCKRQF9fX9PlDJu7dVx0b6uvr8dbb72F1atXY9q0aZouZ9C0tbXh5uaGmJgYXLx4ESdPnsQzzzyDgoIC+Pn5wcbGBkFBQYiPj0djY6OmyyUa83hNSXR7Lly4gL1790Imk8HGxgZhYWG4fPkyoqOjUVpaivz8fERFRQ1b6A1g8I2IiIiIiIiIaFTo6+vD09MTMTExuHTpErKzsyGXy3Ho0CG4u7vDxsYGoaGhUCqVaG9v13S5RGPSxIkTcenSpR7bKisrcfHixV5tAwMD0dHRgWPHjvV6bOvWrbCzs0NHR8eI1Up0J2hra0NmZiYiIiIwZcoUzJkzB/Hx8fDy8kJGRgYqKioQHx8PuVw+LDNjjAQjIyPs3LkTH3/8MX744QdNl0P3iODgYAgh4OHhoelShtXNxtXc3Ixp06b1Ws7tVob6PKLhsm7dOmhpaWHTpk2aLqVfFy9ehJeXFz766KNbLovo7OyMqKgo5Ofn47fffsPGjRtx+fJlrFq1CtbW1vDy8kJMTAwqKipGqXqiuwuvKYkGr7CwEFu3boWbmxvs7e2xfv16AMCnn36qvhE4IiICkyZN6rePrq4u5ObmIjIyEmFhYYPaP4NvRERERERERESjTEtLC25ubtiyZQuKiopw8uRJvPLKKygpKYG/vz/MzMwgk8kQHx+vXjqDiG5tyZIlKC8vxz/+8Q80Nzfj3LlziIiIgJWVVa+27733HhwdHfHss88iLS0NDQ0NqK+vR2xsLDZt2oTt27dDR0dHA6MgGlmXL1+GQqFAaGio+gPyzMxMPP/888jPz0dJSQliYmLg6ek5Zn4H/vrXv8LPzw9PP/00rl69qulyiO5KQgh0dXX1OUuxoaEh3NzcBv08opH27bff4osvvsCePXtgamqq6XL6tGbNGsTFxcHU1BSvvfYa7OzsMHfuXLz77rsoLCy86XOnTp2KiIgIZGRkoLKyErGxsTA1NcWbb76JyZMnY86cOYiKikJRUdEojYZo7OM1JdGtdXZ2IicnB6+99hqmT5+Ohx56CDt27ICDgwNSUlJQX1+vni3cyMio337a29uRlpaG1atXw9bWFq6urjhw4AD8/f2RnZ0NCwuLAdUjEUKI4RocERERERERERHdnosXLyI9PR1KpRKHDh1CV1cX5s2bB7lcjhUrVsDW1lbTJRINm88//xzPPPNMr+1NTU0wNDQEABw/fhzz58/v1aavtzUbGhrw6quv4uDBg7hy5QpcXFywc+dOrFmzBgUFBQCAyMhIbNmyBcAfS1+9++67SE5ORmlpKUxMTDB79mxs2LABnp6ewzlUIo2qrq5Geno6FAoFDh8+jM7OTvVry/LlyzF58mRNl3jbKioq4OzsjFWrVmHbtm2aLofuEZ6ensjJyUFbW5umSxlWgx2XoaEhZs2ahZycnBGujGjgGhsb8dBDD2HBggX44osvNF0OAOAvf/kLFi5ciPfff7/Px9va2pCTkwOlUomvv/4a5eXlsLe3h0wmg0wmw8KFCwcUomltbUVmZiZUKhWSk5NRXV0NBwcHSKVSyOVyuLq6QiKRDPfwiDSC15REo+P615aUlBRUVVUN6bXl6tWr+O6776BQKJCamoqGhgY4OTlBLpdDJpPBxcWl3+daWFhg8+bNeOGFF3psZ/CNiIiIiIiIiOgOdfnyZWRmZkKpVCI5ORlNTU3qN4OCgoLg5OSk6RKJiOgOVVJSAqVSCYVCgdzcXBgYGGDx4sWQy+Xw8/ODiYmJpkscdp999hnCwsLwww8/wNXVVdPl0D2Awbc/MPhGd6KwsDAkJSXh1KlTsLS01HQ5AG4dfLteV1cXTpw4AaVSicTERJw+fRrm5ubw9fWFTCaDr6/vgJYh7+zsRF5eHlQqFQ4cOIBff/0VU6ZMgY+PD6RSKby9vaGrqzscwyMiortMfX09VCoVVCoV0tLS0NLSgtmzZ0MqlWLlypWYMWPGgPqpqalBWlparxuxZDIZli9fjvvvv39A/fQXfONSp0REREREREREdyhTU1PI5XLEx8ejuroaGRkZ8PT0RGxsLJydneHo6IiIiAjk5ORw+SgiontcV1cXCgoKEBUVBScnJzg6OiI6OhoODg5ISEhAdXW1ermZuzH0BgDPPvssPDw88Mwzz6CxsVHT5dAoq6mpQXh4OKZOnQpdXV1YWloiMDAQP//8s7pNcnIyJBKJ+uv8+fNYuXIlTExMYG5uDqlUinPnzvXqu6ioCAEBATA2NsaECRPg7u5+2yGvuro6rF+/Ho6OjtDT08PkyZPh6emJzz//HK2trX2209XVhampKXx8fHD06NFRG9eN/XcH4rZv3w6JRIKrV6/i2LFj6se7Z6Tq73mjMTa6t6WkpODTTz/Fnj177pjQW7cPP/wQMpkMn376Kaqrq/ttp6WlBRcXF0RFReHUqVM4d+4c3nrrLZSUlGDlypWwtLSETCbD3r17b9qPtrY23NzcsGXLFpw9exYnT57Es88+i4KCAvj5+cHGxgZBQUGIj4/naycREeHChQvYu3cvZDIZbGxssHr1aly+fBnR0dEoLS1Ffn4+oqKibhl6KykpQUxMDNzc3GBtbY01a9YA+ON1sLy8HDk5OYiMjLxl6O2nn37C22+/jZkzZ6Kurq7vRoKIiIiIiIiIiMaUzs5OkZ2dLSIjI8UDDzwgAAhLS0sREhIiUlNTRVtbm6ZLJCKiUdDa2ioyMjJEeHi4mDhxogAg7O3tRXh4uMjIyBDXrl3TdImjrrKyUkyaNEn4+fmJrq4uTZdDo6S8vFz86U9/EtbW1uLgwYOiqalJnDx5UixYsEDo6+uL3NzcHu39/f0FAOHv7y9yc3NFc3OzyMjIEAYGBmLu3Lk92p49e1aYmJgIW1tbcfjwYdHU1CR++eUXsWTJEjF16lShp6c36HorKiqEvb29sLGxEUqlUjQ2NorKykqxefNmAUDs3LmzRztra2uhVCpFQ0ODOHPmjAgMDBQSiUTs27dvVMfV3X9ra2uP7RMmTBCurq79jrev543k2IQQYtGiRcLMzEzk5eX1Wxfdnc6fPy/MzMxEWFiYpkvppba2VsTFxQm5XC4MDQ2FlpaWcHFxERs3bhSnT58ecD/V1dUiLi5OSKVSoaurK7S1tYWrq6vYtWuXuHjx4oD7+e2338SuXbuEp6en0NHREfr6+sLT01Ps2rVLlJeXD2WIREQ0Bp08eVJs2bJFuLq6ColEIkxMTIRcLhdxcXGioaFhQH10dnaK/Px8sXHjRjFjxgwBQJibm4uQkBCRmJgompubB9RPR0eH+j3PadOmCQDCyspK/Z5ne3t7r+cw+EZERERERERENMbd+AbV+PHjhVQqFXFxceLKlSuaLo+IiIZRfX29SExMFCEhIcLIyEgAEE5OTmLjxo0iPz9f0+XdEbKysoSOjo46PER3v6eeekoAEF9++WWP7RUVFUJPT0+4uLj02N4dolIqlT22r1ixQgAQNTU16m1yuVwAEF9//XWPtpcuXRJ6enpDCr49/fTTAoBISEjo9djSpUvVP7vd7b766qsebdra2sSkSZOEgYGBqKysHLVxDWfwbSTHJoQQCxYsEKampr1Cj3R3a2trEy4uLmLmzJmipaVF0+XcVEtLi0hNTRVhYWHC2tpaABAODg4iPDxcZGdnDzi83dzcLFJTU2/774LhCuUREdGdbyjhsr60tbWpb8SaNGmSACCmTp066Buxbvc1kUudEhERERERERGNcc7OzoiMjEROTg7Onz+PnTt3AgCee+45mJubw83NDTExMbh06ZKGKyUioqGorq5GfHy8ermZxx9/HCUlJdi0aRNKS0tRWFiIqKgouLi4aLrUO8KCBQuwadMm/Nd//ddtL0d5Jzt58mSPJSAlEgnWrl17z20H/lgOU0tLC1KptMcxsrGxgbOzMwoKClBWVtbrGM6dO7fH/6dMmQIAKC8vV29LT08HAHh7e/doO2nSJEyfPn1I37ukpCQAgI+PT6/H0tLSsG7duh7tHnvssR5t9PT04OHhgdbWVhw6dKhXH5oa12CM5NgAICsrC/X19Zg/fz4A/r5c//tyNwsPD0dxcTESExNhYGCg6XJuysDAADKZDLGxsbh06RKys7Mhl8uRlpYGd3d32NjYIDQ0FEqlEr///nu//UyYMAEymQzx8fGorq5GRkYGPD09sW/fPsyZMwcODg6IiIhAZmYmOjo6+u3H3NwcoaGhSExMRHV1NZKTk+Hi4oKPP/4YM2bMgKOjIyIiIpCTkwMhxEgcEiIiGkGtra1QKpVYvXo1bG1t4e7uDoVCAR8fH2RnZ6OyslJ9zamrq9tvP1evXoVSqURoaCisra3h5eWFzMxMPP/888jPz8dvv/2GmJgYeHp6QkdHp99+6urqEB8fj6CgIFhZWSEgIAAFBQVYs2YNTp8+jXPnzqmXSpVIJDcdW/97ISIiIiIiIiKiMcfOzg5hYWEICwvD5cuXkZmZCaVSibfeegvr1q2Dk5MT5HI5goKC4OTkpOlyiYioHyUlJVAqlVAoFMjNzYWBgQEWL16Mffv2wc/PDyYmJpou8Y722muvITc3F48//jh++uknWFpaarqkYffQQw/1Gz64l7a3t7ejoaEBAGBsbNzn8wDg7NmzmDx5co9tN7bv/pCvq6tL3XdTUxP09fVhaGjYq08rKysUFxf3u8++dNerr6+P++67b8jtrK2tAQCVlZW9HtPEuAZjJMfWH/6+3P3++7//G/v27cOBAwfwwAMPaLqcQdHW1oabmxvc3NywZcsWFBYWQqVSQalUwt/fHyYmJvD09IRUKkVAQACMjIz67EdPTw+enp7w9PTEzp07ceLECSiVSiQmJmL37t0wNzeHr68vZDIZfH19MWHChD776Q7lyWQy7NmzB3l5eVCpVPjmm2+we/duTJkyBT4+PpBKpfD29r5pQIKIiDSnrq4OBw8ehEqlQlpaGlpaWjB79mysWbMGK1euxIwZMwbUT01NDdLS0qBQKHD48GF0dnZi3rx5eOeddxAYGKi+EeFWzp8/j5SUFKhUKmRlZUFHRwdubm6Ijo5GUFAQJk6cOKRxMvhGRERERERERHSXMjU1hVwuh1wuR1tbG3JycqBUKhEbG4t33nkHDg4OkEqlkMvlePTRR6GlxcUBiIg0paurS/0BdUJCAoqKimBhYQEfHx9ERETc9ANq6k0ikSAuLg5z5sxBQEAAMjMz7/jZf2ho9PT0YGJigubmZrS2tt50Zomh9H3fffehqakJzc3NvUJi9fX1Q+rT2NgYDQ0NaGpq6jf8dqt2VVVVAP6Y1W4oNQznuG41C0df+x+psdG9KTc3F2FhYVi/fj2WLVum6XJum7Ozs3pW7+tDAs899xxWr14NNzc39XXcpEmT+uxDS0sLLi4ucHFxQVRUVI9A/cqVK6Gvrw8PDw/IZDIEBATAysqqz376CuUpFAqoVCrs27dvwKE8IiIaHRcuXEBycjJUKhW+//579Xk8Ojr6pq8bN7rxRqzu140PP/zwpq8bN7r+deOnn35Sv2589tlnw/a6wXcziYiIiIiIiIjuAfr6+vD09FQveZqfn4+QkBAcOnSo11I67e3tmi6XiOie0NbWhszMTERERGDy5MmYM2cO4uPjsWTJEmRkZKCiogLx8fGQy+UMvQ2BmZkZDh48iKKiIqxcuRKdnZ2aLolGSGBgIDo6OnDs2LFej23duhV2dnY3XeLvZrqXI+1eGrRbbW0tzpw5M6Q+u4M53377ba/HZs+ejZdffrlHu4MHD/Zo097ejiNHjsDAwKDXUqUDNZzjGj9+fI+lGB944AHs3bv3ps8ZybHRveXcuXNYtmwZPDw8sHXrVk2XM+ymTp2KiIgI9d8FsbGxMDU1xZtvvokpU6Zgzpw5iIqKwunTp2/aT/eSpzk5OaiqqsInn3wCAHjppZcwadIkuLm5ISYmBqWlpTftx9nZGVFRUcjPz0dJSQk2btyIy5cvY9WqVeol72JiYlBRUTFsx4CIiG6usLAQW7duhZubG+zt7fHOO+/A1NQUn376KaqqqpCRkYGIiIibht66urpQUFCAJcHQyAAAIABJREFUqKgoODk5wdHREZs3b4aDgwMSEhJQU1MDpVKJsLCwm4beOjs7kZOTg9deew3Tp0/HQw89hH/+859wcXFBSkoKKisrkZiYiNDQ0GELSzP4RkRERERERER0j+m++z8qKgpFRUU4efIkXnnlFZSUlMDf3x9mZmaQyWSIj49XLx1GRETD4/Lly1AoFAgNDVV/QJyZmYmwsDD1h8gxMTHw9PQc1pmr7lUzZsxAcnIyDh8+jA0bNmi6HBoh7733HhwdHfHss88iLS0NDQ0NqK+vR2xsLDZt2oTt27cP+ffp73//O8zMzLBu3TpkZGSgubkZp06dwpNPPtnnMqEDrdfe3h4vv/wyDh48iKamJpSVleHFF19ERUWFOvjW3W7dunVQqVRoampCcXExnnjiCVRUVCAmJka9LKgmx/V//s//QXFxMUpLS5GXl4eSkhK4u7sP6BiMxNgAYPHixTA3N8fx48eH3Afd+Wpra+Hj4wM7Ozvs378f2trami5pRJmbmyM0NBSJiYmorq5GcnIyXFxc8Mknn6hDCt3htpstdWtpaam+6am+vh5JSUlwcHDAxo0bYWdnpw63FRQU3LSe60N5lZWVPUJ53YH+7mtOIiIaPn2Fyz744AM4ODgMKlzW3t6uvhGrO0wdHx8PLy8v9bl9IDditba2QqlUYvXq1Zg0aRLc3d2hUCjg4+OD7OxsXLhwAbGxsZDJZCOzPLYgIiIiIiIiIiL6fy5cuCBiY2OFVCoV48aNE9ra2sLV1VXs2rVLlJWVabo8IqIxqaqqSsTFxQmpVCp0dXV7nFtLS0s1Xd49ISEhQWhpaYldu3ZpuhQaIXV1dWL9+vXCwcFBjBs3TlhaWoolS5aIjIwMdZu8vDwBoMfXG2+8IYQQvbY/9thj6uedOXNGBAQECCMjI2FgYCDmzp0rVCqV8PDwULdftWrVoOqtra0V69atE/b29mLcuHFi4sSJIjg4WBQXF9+0nbGxsfD29hZHjhwZtXElJSX16uevf/2rup+ioiLh7u4uJkyYIKZMmSI++ugjIYS45fNGcmzu7u7C1NRU5ObmDur7QmNHS0uLmD9/vnBwcBCVlZWaLkejOjo6RHZ2toiMjBTTpk0TAISVlZUICQkRqampor29fUD9tLW1iYyMDBEeHi4mTZokAIipU6eK8PBwkZGRIa5duzagflpaWkRqaqoICwsT1tbWAoBwcHAQ4eHhIjs7W3R1dd3OcImI7knDdW5tbm4WqampIiQkRBgZGQkAwsnJSWzcuFHk5+cPuJ7a2loRFxcn5HK5MDQ0FFpaWsLFxUVs3LhRnD59eqjDHBKJEDeJexMRERERERER0T3r8uXLyMzMhFKpRHJyMpqamuDk5AS5XA6ZTAYXFxdNl0hEdMcqKSmBUqmEQqFAbm4uDAwMsHjxYsjlcvj5+cHExETTJd5z3n//fbz++uvYv38/5HK5psshIqIhunbtGgIDA3H8+HHk5uZi2rRpmi7pjlJYWAiVSgWlUonc3FyYmJjA09MTUqkUAQEBA1parqurCydOnIBSqURiYiJOnz4Nc3Nz+Pr6QiaTwdfXd0DLsHd2diIvLw8qlQrffPMNzp49iylTpsDHxwdSqRTe3t4jM/sPEdFdoK6uDgcPHoRKpUJaWhpaWlowe/ZsSKVSBAcH48EHHxxQPzU1NUhLS4NCocDhw4fR2dmJefPmQS6XIzAwEFOmTBlQP+fPn0dKSgpUKhWysrKgo6MDNzc3SKVSBAUFYeLEibcz3CFj8I2IiIiIiIiIiG6pra0NOTk56hBHRUUFHBwcIJVKIZfL8eijj0JLS0vTZRIRacz1HxAnJCSgqKgIFhYW8PHxGdQHxDSyIiIi8PHHH2P//v0IDAzUdDlERDRI165dQ3BwMDIyMnD48GHMmzdP0yXd0S5cuIDk5GSoVCp8//330NbWVocU5HI5Jk2aNKB+bgz06+vrw8PDAzKZDAEBAbCyshpQP8MRyiMiuptdHy678bw9mHDZcJ63FQoFVCoVCgoKYGpqesedtxl8IyIiIiIiIiKiQbk+3LF//36cOXNGHe6Qy+VYsmQJ9PT0NF0mEdGI6ysUbG9vD5lMBplMhoULF0JHR0fTZdJ1hBAIDw9HbGwsEhMTERAQoOmSiIhogDo7OxESEoKUlBQcPHgQCxcu1HRJY8rNZg5auXIlZsyYMaB+RmLmoNsJdxARjXWcqfP2MPhGRERERERERES35cY36K5fzs/f3x/GxsaaLpGIaNhcvwx0SkoKGhsbuQz0GCOEwEsvvYS9e/cy/EbDSiKR3LLNxo0bERUVNfLFEN1lOjs7ERoaqp69bNGiRZouaUxrbW1FZmYmVCoVUlJSUFVV1WNGb1dX1wGd065evYrvvvsOCoUCqampaGhoGNLfRcO1nB8R0VjQV7jMysoK3t7ekMvlAw6Xtbe3Izs7G0qlEl9//TXKy8uHdCPW9a8JycnJqK6uHtJrgqYw+EZERERERERERMPm4sWLSE9Ph1Kp7HX3/4oVK2Bra6vpEomIBq26uhrp6el9zmyyfPlyTJ48WdMl0iAJIbB27Vp8+umnSExMhL+/v6ZLIiKifnR2duKpp55CUlISQ28jYLgCGB0dHTh+/DgUCoU6gDF16lT4+fkNOYBxO6E8IqI7yUgEjm/nRqy7KXDM4BsREREREREREY2I62dFSk5ORlNTE2dFIqIxo6SkRL2E6Y2zWfr5+cHExETTJdJtEkJgzZo1+PzzzxEXF4fg4GBNl0RERDdoa2vDE088gUOHDnF501Fy44zexsbG8PLyGvKSewqFAqdOneqx5J6Pjw8MDQ1v2c9whfKIiDRhuMJlN1tiejA3Yl2/xHRWVhZ0dHTuiiWmGXwjIiIiIiIiIqIR19bWhpycHPUHHxUVFT3ubH300UehpaWl6TKJ6B52/Qe0CQkJKCoqgoWFBXx8fCCXy7FkyRLo6elpukwaZkIIvPrqq9i1axd27NiBdevWabqke8qvv/6KadOm4auvvkJwcDC2b9+ODRs2AABsbW1RVlZ2W/0nJCTgvffew5kzZ9DW1gYA+M9//oOHHnrotmunkZGcnIxly5ap/9/a2gp9ff0R3ef+/fvx+OOPAwD09PTUPytA759RGl2XL1+Gv78/CgsLkZqaCldXV02XdM+5cOECDh06BKVSiUOHDkFbW1sdkpDL5Zg0adKA+rnxhgJ9fX14eHhAJpMhICAAVlZWA+rnxlCeiYkJPD09BxXKIyIaSdeHy77//vse583BhMuG60aswsJCKBQKqFQqFBQUwNTU9K47bzL4RkREREREREREo+r6cMn+/ftx5swZhkuISCP6CuXa29tDJpMNakkuGvtiYmKwfv16rF27Fjt37mQYe5T0FyqaNWsWamtrbyv4duzYMbi7u+PVV1/F22+/jaqqKixcuBBpaWkMvo0BAQEBSElJGZXgWzdPT0/k5OQw+HaHKC8vh6+vr3qWm5kzZ2q6pHtefX09VCpVnzMXrVy5EjNmzBhQP/3NXCSTybB8+XLcf//9A+rnZuGSwYTyiIhu13CEcq9/rywxMRGnT59Wv1cmk8ng6+uLCRMm3LKf62fKPHDgAH799VdMmTIFPj4+kEqld+VMmQy+ERERERERERGRRt34BuH1d7H6+/vD2NhY0yUS0V3k+mWYU1JS0NjYyGWYCQBw4MABPPnkk1i+fDn++c9/3nUfCN2JRjL4tm7dOsTExKCsrAy2trY9HjM0NMSsWbOQk5Mz5P5pZDH4dm87deoUli5dCiMjI6SlpWHKlCmaLolu0NraiszMTKhUKqSkpKCqqqrHjN6urq6QSCS37Ofq1av47rvvoFAokJqaioaGhiH9XTZcywkSEQ1EX8swDyVcdv2NWF9//TXKy8uHdCPW9efk5ORkVFdXw8nJCTKZDFKpdMDn5LGKwTciIiIiIiIiIrpjXLx4Eenp6VAqlT3u/pfL5VixYkWvD66JiAaiuroa6enpvWYWkcvlWL58OSZPnqzpEukOkZmZicDAQMybNw+JiYkDXkKIhmYkg2/Lly/HN99802dwisG3Ox+Db/euo0ePYvny5Zg5cyaSk5N5Hh4Drg+AJCUlobi4GFZWVvD29oZcLh9wAKSjowPHjx+HQqHAgQMHcOnSJUydOhV+fn5DDoDcTiiPiOh6w3VuuXLlCjIyMm77RiwGfv8/Bt+IiIiIiIiIiOiOdP2sTMnJyWhqauKsTEQ0YCUlJeolTG+cTdLPz48fpFO/Tpw4AZlMhvHjxyM5ORlOTk6aLumuNZLBt5sFpxh8u/Mx+HZv2r17N1555RUsX74cn3/++ah972l43Tij9/jx47Fo0SLI5fIhLfmnUChw6tQpmJubw9fXFzKZDD4+PjA0NLxlP33NyjSUUB4R3ZuGK1w2XDdiXb/Ec1ZWFnR0dNRLPAcFBWHixIm3M9wxS0vTBRAREREREREREfXF1NQUcrkc8fHxqK6uRkZGBjw9PbF3717MmTMHjo6OiIiIQE5ODrq6ujRdLhFpWFdXFwoKChAVFYUZM2bA0dER0dHRcHBwQEpKCurr66FUKhEaGsrQG93U7NmzceLECdja2uKRRx7BgQMHNF3SXev++++HEGLAgaKamhqEh4dj6tSp0NXVhaWlJQIDA/Hzzz+r2yQnJ0MikSAlJQUAYGBgAIlEgnnz5mH79u2QSCS4evUqjh07BolEAolEcssZhLqfJ5FIMHnyZPz444/w8PDAfffdpw50HDt2rNfz6urqsH79ejg6OkJXVxempqbw8fHB0aNHe7Rrb2/H22+/jQcffBDjx4+HmZkZZDIZUlNT0dnZOehj0J/uY9P9debMGQQFBcHc3Fy9rba2dlD76ejoQEJCAry8vGBjYwMDAwP8+c9/RkxMTJ9/n11/TPT09DB58mR4enri888/R2tra6/2lZWVWLlyJUxMTGBubg6pVIpz5871ajeY41JUVISAgAAYGxtjwoQJcHd37zcEOdifURqa9vZ2rFq1CuvWrcMrr7yCr776iqG3MczZ2RmRkZHIycnBb7/9hg8++AAA8Nxzz8Ha2hpeXl6IiYlBeXl5v31oaWnBxcUFUVFRKCwsxLlz5/DWW2+hpKQEwcHBsLKygkwmw969e1FdXd1vP9ra2nBzc8OWLVtQXFyMkydPYv369SgpKYG/vz9sbGwQFBSE+Ph4NDY2DvuxIKKx5/z584iJiVH/bbN69WpcvnwZ0dHRKCsrQ35+PqKiom4ZeispKUFMTAzc3NxgY2ODF154AQCwb98+1NbWIicnBxEREbcMvRUWFiIqKgpz5syBvb093nnnHZiamuKzzz5DVVUVMjIyEBERcc+G3gAAgoiIiIiIiIiIaAzp7OwU+fn5YuPGjeLBBx8UAISFhYUICQkRqampoq2tTdMlEtEoaW1tFRkZGSI8PFxMnDhRABD29vYiPDxcZGRkiGvXrmm6RBrDrl27JiIjI4VEIhGRkZGis7NT0yXdMx5++GFha2vbY1t5ebn405/+JKytrcXBgwdFU1OTOHnypFiwYIHQ19cXubm5Pdr7+/sLAKK1tbVX/xMmTBCurq5DqmvChAli/vz5Ijc3VzQ3N4sff/xRzJw5U+jq6oqsrCx124qKCmFvby+sra2FUqkUDQ0N4syZMyIwMFBIJBKxb98+ddvnnntOGBsbi8OHD4uWlhZRWVkpXn31VQFAHD16dMjHoD/dx2bBggXi6NGj4urVq+L48eNCW1tb1NTUDGo/SqVSABB///vfRX19vaipqRG7d+8WWlpa4tVXX+2x3+5jYmNjI5RKpWhsbBSVlZVi8+bNAoDYuXNnrxr9/f3Vx/rIkSPCyMhIzJ07t0e/g6n37NmzwsTERNja2orDhw+LpqYm8csvv4glS5aIqVOnCj09vQEdQxo+ZWVl4pFHHhFGRkYiOTlZ0+XQCKqrqxNxcXFCLpcLQ0NDoaWlJVxcXMTGjRvFqVOnBtxPdXW1iIuLE1KpVOjp6QltbW3h6uoqtmzZIoqLiwfcz/nz58WuXbuEp6enGDdunNDX1xeenp5i165d4tKlS0MZIhGNUSdPnhQbN24ULi4uQiKRCFNTUyGXy0VcXJxoaGgYUB/Xv1c1Y8aMHu9VJSYmiubm5gH109HRIbKzs0VkZKS4//77BQBhZ2cnwsLCRGpqqmhvb7+dod6VGHwjIiIiIiIiIqIx7eTJk2LLli3C1dVVSCQSMX78eCGVSkVcXJy4cuWKpssjomFWX18vEhMTRUhIiDAyMhIAhJOTk9i4caPIz8/XdHl0F4qNjRW6urpCJpPxdWWU9BV8e+qppwQA8eWXX/bYXlFRIfT09ISLi0uP7SMVfAMgTpw40WP7L7/8IgCIhx9+WL3t6aefFgDEV1991aNtW1ubmDRpkjAwMBCVlZVCCCHs7e3Fo48+2mt/06dP7xF8G+wx6E/3sfn222/7fHww+1EqlWLhwoW9+njyySfFuHHjenxY3H1MEhISerVfunRpn8E3pVLZo90TTzwhAIiampoh1SuXywUA8fXXX/doe+nSJaGnp8fg2yjLzs4WNjY2wsnJaVCBJRr7WlpaRGpqqggLCxPW1tYCgHBwcBDh4eEiOztbdHV1Daifq1evitTUVBESEiKMjY2H/HfhcIXyiGhsuD5cNm3aNAFATJkyZdDhsutvxJo0adKQb8S6/pxoZWWlPpdFRkYO6px4r5IIIcSoTC1HREREREREREQ0wi5evIj09HQolUocPnwYnZ2dmDdvHuRyOVasWAFbW1tNl0hEQ1BaWoq0tLQ+f7eXL19+y+VhiG7XsWPHsGLFChgYGOB//ud/MG/ePE2XdFebNWsWamtrUVZWpt5mYmKCpqYmXL58GUZGRj3au7i44KeffkJpaan6fBAQEICUlBS0trb2WjLR0NAQs2bN6nd5y5vV9euvv6K5ubnXY7a2tigvL0d5eTkmTpwIExMTNDQ0oLGxEffdd1+PtqGhofjiiy8QFxeH0NBQvPjii/j444/x/PPP49lnn8XcuXOhra3dax+DPQb96T42tbW1MDc3H5H9bN++HRs2bEBubi7mz5+v7re/Y9JfjZWVlbC2tlZv/6//+i9s27YN//73vzFz5sxB12tkZISmpiY0NTXB0NCwR9uZM2eiuLgYbW1tN62Nbl9XVxfee+89REVF4bHHHsMXX3xxy58Junt1dnYiLy8PKpUKSUlJKC4uhqWlJZYuXQq5XA5vb2/o6uresp+Ojg4cP34cCoUCBw4cwKVLlzB16lT4+flBJpNh4cKFt1zaGgBaW1uRmZkJlUqFlJQUVFVVwcHBAVKpFHK5HK6urpBIJMMxdCIaRdf/bicnJ6O6unpIv9uXL19GZmYmlEolUlJS0NjYCCcnJ8jlcshkMri4uAyonrq6Ohw8eBAqlQrffvstWltbMXv2bEilUjz++ON44IEHbnfI94xbn9mJiIiIiIiIiIjGCDs7O4SFhSEsLKzHm5Fvv/021q1bN6Q3I4lIM0pKSqBUKqFQKJCbmwsDAwMsXrwY+/btg5+fH0xMTDRdIt1DXF1d8csvv+CZZ56Bu7s73njjDbz11lt9hpNo+LW3t6OhoQEAYGxs3G+7s2fPjngQtr9zj5WVFcrLy1FdXQ0zMzM0NDRAX1+/zzBPd5CrsrISAPDRRx9h/vz5iIuLg4eHBwDA3d0dq1evxrJlywCMzDGYMGFCr22D3U9DQwN27NiBpKQklJWV4cqVKz3atbS09Oi3v2PSnxtr0NLSAvBHcGqw9VpaWqKpqQn6+vq9Qm/AH9/D4uLiAddGQ1NVVYWnnnoKWVlZiI6OxoYNG9TfV7o3aWtrw83NDW5ubtiyZQsKCwuhUqmgVCrh7++P8ePHY9GiRZDL5QgICOgVcO2mo6Oj7icmJgaFhYVQKBRQKBTYvXs3zM3N4evrC5lMBh8fnz7PAwBgYGAAmUwGmUyGPXv2qEN533zzDXbv3g0rKyt4e3sPKpRHRJpxfbgsLS0NLS0tmD17Nl544QUEBwfjwQcfHFA/1dXVSE9Ph0Kh6HEj1qZNmwZ1I9b58+eRkpIClUqFrKws9Xnr3XffRVBQECZOnHg7w71nMfhGRERERERERER3JVNTU8jlcsjlcrS1tSEnJwdKpRJ79+7FO++80+PO3kcffZQfuBFpWFdXF06cOAGlUomEhAQUFRXBwsICPj4+iIyMxJIlS6Cnp6fpMukeZmlpCaVSid27dyMyMhI//PADvvjiC84mOgr09PRgYmKC5uZmtLa2DmjGnpu5nZl66urqIITo1Ud1dTWAP8JTenp6MDY2RkNDA5qamnoFvaqqqgAANjY26npCQkIQEhKCa9euISsrC9u3b0dgYCB27NiB9evXD/sx6M9g9yOTyZCdnY2YmBg8/vjjsLCwgEQiwa5du/Dyyy+je+GpWx2T0ar3vvvuQ1NTE5qbm3uFXurr64elJupfSkoKVq1aBQsLC+Tl5WH27NmaLonuQM7OznB2dkZkZCQuXLiAQ4cOQalU4rnnnkNYWBjc3d3V13GTJk26ZT9RUVE9bqgIDg6Gnp4ePDw8IJPJ4O/v32NmyevdKpRnbGwMLy8vSKXSm4byiGj09Bcui46OHlS4bLhuxOoO4apUKhQUFMDU1BSenp747LPPsGzZMs54Ogz4bh4REREREREREd319PX14enpiZiYGJSVlSE/Px8hISE4fPgw3N3dYW1tjdDQUCiVSrS3t2u6XKJ7RltbGzIzMxEREYHJkydjzpw5iI+Px5IlS5CRkYGKigrEx8dDJpMx9EZ3BIlEgoiICOTm5uLSpUuYNWsWlEqlpsu6JwQGBqKjowPHjh3r9djWrVthZ2eHjo6OAfU1fvx4/P777+r/P/DAA9i7d++AntvW1oYff/yxx7b//Oc/KC8vx8MPP6z+MLV7praDBw/2aNve3o4jR47AwMAA3t7eAP6YRa6oqAgAMG7cOHh5eSE5ORkSiaTH84fzGNzMQPfT2dmJY8eOwcbGBuHh4bC0tFQHAltbW3s9t/uYfPvtt70emz17Nl5++eURrRcAfHx8AADp6ek92tXW1uLMmTND2j/dWltbGyIiIrBs2TL4+voiPz+foTcakD/96U8ICwuDUqlEZWUl9u7dC1NTU7z55puYMmUK5syZg6ioKJw+ffqm/Tg4OCAiIgI5OTmorKzEJ598AgAIDw+Hra0t3NzcsHXrVpw9e/am/XQH8nJycvDbb79h69ataG1txXPPPQdra2t4eXkhJiYG5eXlw3YMiOjWCgsLERUVhTlz5sDe3h7vvPMOTE1N8dlnn6GqqgoZGRmIiIi4aeitq6sLBQUFiIqKwowZM+Do6Ijo6Gg4ODggISEB1dXVUCqVCA0NvWnorbOzEzk5OYiIiICdnR0eeugh/Otf/4KLiwtSU1NRWVmJxMREhIaGMvQ2XAQREREREREREdE97Ny5c2LXrl3C1dVVSCQSMX78eCGVSkVcXJy4cuWKpssjuuvU19eLxMREERISIoyMjAQA4eTkJDZu3Cjy8/M1XR7RgLW0tIjw8HABQMjlclFXV6fpku4aDz/8sLC1te2xraqqSjg6OgoHBwfx7bffiitXroi6ujrxySefiPHjx4uEhIQe7f39/QUA0dra2qv/pUuXCmNjY3Hx4kWRm5srdHR0xKlTpwZUl7GxsfDw8BC5ubmiublZ/Pjjj2LmzJlCV1dXZGVlqdtWVFQIe3t7YW1tLZRKpWhsbBRnzpwRgYGBQiKRiL1796rbGhsbiwULFoh///vfoq2tTVRVVYmoqCgBQERHRw/5GPTnZsdmsPtZvHixACDef/99UVNTI1paWsR3330n7OzsBACRkZHR65hMnDhRqFQq0djYKEpLS8ULL7wgrK2txYULF25ZY2RkpAAgTpw4MaR6f/31V2FmZiZsbW3F4cOHRVNTkygsLBTe3t7CyspK6OnpDegY0sDl5eWJGTNmCCMjI/Hll19quhy6S7S0tIjU1FQRFhYmrK2tBQDh4OAgwsPDRXZ2tujq6hpQP1evXhWpqakiJCREGBsb9/q7dKD91NXVibi4OCGXy4WhoaHQ0tISLi4uYuPGjQN6fSGiweno6BDZ2dkiMjJS3H///QKAsLOzE2FhYSI1NVW0t7cPqJ/W1laRkZEhwsPDxcSJEwUAYW9vL8LDw0VGRoa4du3agPq5/pxkZWWlPpdERkYO6pxEQ8PgGxERERERERER0f9z8eJFERsbK6RSqdDV1RXa2trC1dVV7Nq1S5SVlWm6PKIx62a/W6WlpZouj+i2HDhwQNjY2AhbW1uRmpqq6XLGtG3btgkAPb7eeOMN9eN1dXVi/fr1wsHBQYwbN05YWlqKJUuW9AhXJSUl9eoDgMjLy1O3KSoqEu7u7mLChAliypQp4qOPPhpQfd2BvFOnTglvb29x3333CQMDA7FgwQKRk5PTq31tba1Yt26dsLe3F+PGjRPGxsbC29tbHDlypEe7n3/+WaxevVrMmDFDjB8/XpiZmYl58+aJffv29fqgdCDHoD95eXl9Hpu+DHQ/NTU1YvXq1WLKlCli3LhxwtraWjz99NPitddeU/fv4uLS7zGZOHGiCA4OFsXFxf3W2P0zcOP2xx57bEjH5cyZMyIgIEAYGRkJAwMDMXfuXKFSqYSHh4e671WrVt3yeNLNXb16Vaxbt05oaWmJpUuX9gg2Eg2n6wMw06dPFwCEpaWlCAkJGVQApruf8PBwYWtrKwCIqVOnqgMwv//++4D6Ga5QHhH1NFzhsuG6Eau2tlYdeJ0wYUKPwGtRUdFQh0lDIBFCiBGZSo6IiIiIiIiIiGgMu3z5MjIzM6FUKpGSkoLGxkY4OTlBLpdDJpPBxcVF0yUS3dFKSkqgVCqhUCiQm5sLAwMDLF68GHK5HH5+fjddHoZorLly5QoiIyOxd+9eyOUfmpBkAAAgAElEQVRy7NmzBxYWFpoui4bZrFmzUFtbi7KyMk2XQnRHy8nJwapVq1BVVYX3338fzz//vHoZXKKRVlhYCJVKBaVSidzcXIwfPx6LFi2CXC5HQEAAjIyMBtyPQqGAQqHAqVOnYG5uDl9fX8hkMvj4+MDQ0PCWfXR2diIvLw8qlQpJSUkoLi6GlZUVvL29IZfL4e3tDV1d3dsdMtFdq66uDgcPHoRKpUJaWhpaWlowe/ZsSKVSBAcH48EHHxxQP9XV1UhPT4dCocDhw4fR2dmJefPmQS6XY/ny5Zg8efKA+jl//jxSUlKgUqmQlZUFHR0duLm5QSqVIigo6KZLqdLIYfCNiIiIiIiIiIjoFtra2pCTk6MO8VRUVMDBwQFSqRRyuRyPPvootLS0NF0mkUZ1dXXhxIkTUCqVSEhIQFFRESwsLODj4wO5XI4lS5ZAT09P02USjaj09HSEhYWhvb0d27ZtQ2hoqKZLomHE4BvRzbW0tGDTpk3Ytm0bfHx88Mknnww4TEA0Ei5cuIBDhw5BqVTi0KFD0NLSgru7u/o6btKkSQPq5/obOvLy8qCnpwcPDw/IZDL4+/vD2tp6QP0MVyiP6G42XOGy4boRqzsEq1KpUFBQAFNTU3h6ekIqlWLZsmW47777bme4NAwYfCMiIiIiIiIiIhoEhnuI/r++QqH29vaQyWSQyWRYuHAhdHR0NF0m0ahqbGzEW2+9hX/84x9YtGgRPvzwQ8yYMUPTZdEwYPCNqH9KpRJr165FU1MTtmzZgrCwME2XRNRDfX09VCoVVCoV0tPTcfXqVfXMUStXrhzwa3VNTQ3S0tKgUCiQkZGBjo4OzJs3DzKZDIGBgZg2bdqA+rkxlKetra0O9wwmlEd0NxiOcNlwvVfTPVOjQqFAUlISSktLYWdnh6VLl0IqlWLp0qUYN27ccAybhgmDb0RERERERERERLfhP//5D/4ve3ceHXV9Nu7/CgmEnbAFQYyABAGpsllBAsiiEMhAEEe0irb2cRdR24p1xbY+LrUq/rS2qNVipcWIJGSQxVBBNhc2FdzY4WFVdghLtt8flnylgkQl+WS5Xpyco5PPzLmmJXNM5s79zsjIID09ncWLF1OrVi2Sk5Pp378/NWrUKNJj5EflU6nAjXEqO/bs2cPUqVOZNm0a2Rdn07pqa4Y3H05qaqoDPtJ/zJ49m1tuuYUVK1bw61//mrvvvpvq1asHnaUf4PHHH+c3v/nNUbfdc889/OEPfwioSCo9li1bxogRI3jnnXe45pprePjhhz3qWaXegQMHyMrKIhKJMHnyZLZs2XLURu9u3boV6Xje7OxsZs6cSVpaGpMnT2b37t20bduWUChESkpKkR/nq6++IjMzk4yMDGbMmMGhQ4fo2rUrgwcPplmzZifhGUulT15eHvPmzSMjI6NwuGzw4MGkpqbSo0ePIv0C1cn6Raxvviakp6ezbdu2H/S1rGA4+CZJkiRJkiSdJOvXrycjI4OMjAxmz55Nbm7uie9UF3gdmAQ8U8yBgh7AIOBvwCcBt5RhVapU4YILLiA1NZWpP5/Km9Xe5G7u5n7uJwY3vElH5Obm8uyzz/LAAw9Qs2ZN/vd//9fjTyWVC/v37+ePf/wjDz/8MO3ateOZZ56ha9euQWdJ39uR7U6RSIRJkybxxRdf0LBhQ/r37084HKZfv35UqVKlyI+TlpbGxIkT2bhxI82aNWPQoEGEQiF69uxZpC1R2dnZTJ8+vfCox+3bt5+MpymVSmeffXbhsFvHjh2LdJ+dO3eSlZVVOCy6Z88e2rZtSzgcJhQK0alTpyI9zvbt25kyZQqRSIQ333yTAwcO0LVrV0KhEKmpqZx55pk/5qmpBDn4JkmSJEmSJAVkNatJIYXd7GYyk+lE0X5Aqx9uMIOZxjSe4Alu5uagc8qNcYzjJm6iLW15lVdJpGhHPEkVxdatWxk1ahTjxo2jb9++PP3007Ru3TroLEn63goKCnjllVcYNWoUubm5PPzww1xzzTVUquT2YpUPy5cvJxKJkJmZyfz586levTq9evUiHA6TmppK7dq1i/w4aWlppKWl8cknn1C/fn0GDBhAKBQiOTmZmjVrFvMzkcqPDRs2MHXqVDIzM5kxYwZ5eXl06dKFcDjM0KFDadq0aZEeZ82aNUyePJlIJMKsWbOIiYkpPGJ42LBhnHLKKcX8TFQcHHyTJEmSJEmSArCABaSSSmMak0kmp3Fa0EkVwrVcSxppXM3VjGFM0Dnlymd8xhVcwQpW8DiPcx3XBZ0klToLFy7k5ptvZvHixVxzzTWMHj2axo0bB50lSUWSlZXFqFGjWLp0KVdccQVPPPGEx5qqXFu3bh3Tp08nMzOT6dOnU6lSJbp37154JGqTJk2K9DirV68uPIpxwYIFxMbG0qdPH0KhEIMHD6ZRo0bF/EyksuebXzfz58+nWrVq9O7dm3A4zKBBg4iLiyvS4xwZQo1EIixatIi6devSt29fUlJSGDJkCLVq1SrmZ6Li5uCbJEmSJEmSVMImMIGf83OSSeYVXqEGNYJOqjDu4R7+wl84l3OZxrSgc8qdHHJ4iIf4Pb9nCEMYy1jqUS/oLKlUyc/PZ+LEiYwaNYqtW7cyYsQIfvvb31KnTp2g0yTpmJYvX86DDz5IWloaffv25fHHH+ecc84JOksqUTt27GDmzJlkZmaSnp7O/v376dChQ+GmqDZt2hTpcb766ivefPNN0tLSeOutt8jNzaVLly6EQiEuvvhiEhPdnKyKKT8/nyVLlpCZmcmECRP47LPPaNCgAcnJyYTDYS666CJiY2NP+DjfPHZ40qRJbNiwgYSEBPr3709KSgr9+/cv0rHDKjscfJMkSZIkSZJKSAEFPMiD/I7fMYIRPMmTVMJjoUrSUzzFAzxAPeqxhjVB55Rb/+bfXMVVVKIS4xjHBVwQdJJU6hw+fJiXX36Ze++9l/z8fH7zm99w2223FekNPUkqCRs2bOAPf/gDL774Ih07duTRRx+lV69eQWdJgTtw4ABZWVlEIhEmT57Mli1baNGiReEmuG7duhEVFXXCx8nOzmbmzJmkpaUxefJkdu/eTdu2bQmFQqSkpBT5caSy6uDBg8ydO7dws9vmzZsLv5ZCoRAXXHABMTExJ3ycb35Npqens23bNr+WKhAH3yRJkiRJkqQScIhD/A//w7/4F2MYw03cFHRShfQqr3I1V1NAAfvYRzWqBZ1Ubu1iFzdyIxOYwAhG8Ef+SBWqBJ0llTo7duzg4Ycf5plnnqFJkyY8+OCDXH755URHRwedJqmC2rJlC48++ijPPfccCQkJPPTQQ1xyySUODUjHcGS7VCQSYdKkSXzxxRc0bNiQ/v37Ew6H6devH1WqnPi/gQ8fPszbb79Neno6kydPZtOmTSVQLwUvKiqKc889lyFDhjB48OAib0/cvn07U6ZMIRKJ8Oabb3LgwAG6du1KKBQiNTWVM888s5jLVVo4+CZJkiRJkiQVs+1s52IuZglLmMAEkkkOOqnCeou3uIiLAPiYj2lHu4CLyr9xjONmbqY1rXmVV2lFq6CTpFJp/fr13H///bz66qs0b96cu+++myuvvLJIWy4k6WTYuHEjjz32GM8//zxxcXHcc889XHfddR4JJ30Py5cvJxKJkJmZyfz586levTq9evUiHA4zePDgIh1tnp+fzwcffMD69etLoFgKTqVKlejatStNmjQp0vVr1qxh8uTJRCIRZs2aRUxMDElJSYVHDp9yyinFXKzSyME3SZIkSZIkqRitYAUDGUgeeUSI0Iai/fayiseHfEh72hNNNBOYwFCGBp1UIaxhDVdwBUtZysM8zEhGBp0klVpr167lySef5K9//SunnHIKt99+O9dffz1Vq1YNOk1SObV+/Xr+9Kc/8fzzz1O7dm1uv/12br31VqpVczOu9GOsW7eO6dOnk5mZyfTp06lUqRLdu3cvPBK1qMM+UkW2fPly0tLSiEQiLFq0iHr16tGnTx9SUlIYMmQItWrVCjpRAXPwTZIkSZIkSSomWWQRJkxrWpNBBvHEB51U4W1mM01owimcwq3cym/5bdBJFUYuufzhP38GMYjneZ761A86Syq11q1bxxNPPMHYsWOJj4/njjvucABO0knl64xUcnbs2MHMmTPJzMwkPT2d/fv306FDh8JNVUU93lEq744cH5yWlsakSZPYsGEDCQkJ9O/fn5SUFPr37+8mUh3FwTdJkiRJkiSpGLzAC9zETaSSyt/5O9VwY0ZpkEsuscTyE35Ce9rzMi8HnVThvM3bXMVV5JDDS7zk0b/SCWzYsIHHH3+8cBPTDTfcwIgRI6hf38FRST/MkiVLePLJJ/nXv/7Fqaeeym233cYNN9xAbGxs0GlShXDgwAGysrKIRCJMnjyZLVu20KJFi8JNcN26dSMqKiroTKnEZGdnM3PmTNLS0sjMzGTXrl20bduWUChESkqKXxP6Tg6+SZIkSZIkSSdRAQU8yIP8jt9xJ3fyMA8ThT+gLU3qU5+zOZtDHGI+84POqZB2s5ubuIl/8k9GMILHeIxYfLNd+i4bN27k6aefZuzYseTk5HD11Vdz2223kZiYGHSapDIgPz+fyZMn88QTTzBnzhw6duzI7bffzmWXXUZMTEzQeVKFlZeXx5w5c8jIyCA9PZ21a9dy6qmn0qVLFypVqhR0nlTsdu3axZw5c8jJySEpKYnBgweTmppK8+bNg05TGeHgmyRJkiRJknSS7Gc/V3IlU5nK8zzPcIYHnaRjaEMbWtCCd3mX7WwPOqdCG8c4buZmmtGM8YznJ/wk6CSp1Nu3bx/jx4/niSeeYMWKFQwYMICRI0fSt2/foNMklUIHDx7ktdde4+GHH+bzzz+nT58+3HrrraSkpLg9RyqFli5dSkZGBsuXLw86RSoRsbGx9O7dm1AoRIMGDYLOURnk4JskSZIkSZJ0EmxiE4MZzBrW8AZv0IMeQSfpOHrSkzjimMxkvuRLGuAP14O0lrVcyZUsZjEP8zC3cqtbEqUiyMvLIz09nSeeeIL58+fTuXNnbr75ZoYNG0a1ah6vLVV0q1atYuzYsbzwwgscPHiQq666ittuu40zzzwz6DRJkqSTxt2YkiRJkiRJ0o/0ER/Rla7sYhfzme/QWylXj3qF//wFXwRYIoBmNGMWs7iTO/kVvyKZZLawJegsqdSLjo5m6NChzJs3j3fffZeWLVty/fXXc+qpp3Lbbbfx6aefBp0oqYTl5OTwxhtvcNFFF9GqVSvGjx/PHXfcwbp163juueccepMkSeWOg2+SJEmSJEnSjzCNaXSnO4kk8gEf0IpWQSfpBOpSl8McpjrV+ZzPg84REEMMoxnNXOayghWcwzm8yZtBZ0llxnnnncc///lPtmzZwgMPPEAkEqFt27Z07tyZsWPHcuDAgaATJRWjTZs28eijj9KyZUvC4TAFBQX861//Ys2aNdxzzz0eHSdJksotB98kSZIkSZKkH2gMY0ghhUu4hKlMJY64oJNUBHWpyy520ZKWbnwrZbrQhSUs4SIuIoUUrud6DuDAjlRUdevWZeTIkXzxxRdMmzaNhIQEbr75Zk4//XTuvPNOPvnkk6ATJZ0khw8fJj09nVAoREJCAk899RRXXnklq1at4q233iIcDhMTExN0piRJUrFy8E2SJEmSJEn6nvLIYwQjuJ3buZd7eZEXqUzloLNURHHEsZOdtKKVG99KodrU5hVeYQITeI3XOJdz+YiPgs6SypRKlSrRr18/3njjDdatW8eIESN47bXXOOuss+jcuTNPP/00X375ZdCZkn6A999/n1tuuYUmTZowdOhQDh48yL/+9S/Wr1/PQw89RLNmzYJOlCRJKjEOvkmSJEmSJEnfw172MpjBvMALjGc8oxkddJK+p7rUZSc7OZMz3fhWioUJs5Sl1KUu53EeYxhDAQVBZ0llTpMmTbjvvvtYvXo1c+bMoVOnTtx33300btyYCy+8kHHjxpGdnR10pqTvsHHjRsaMGUP79u0577zzmDlzJrfccgsrV67krbfe4pJLLqFyZX8JQ5IkVTxRBQUF/qRAkiRJkiRJKoI1rCGFFHayk8lMpjOdg07SD/Aqr3IN1/A8z3Md17Gf/UQTHXSWjiOXXP7En7iP++hFL17mZRrTOOgsqUzLzs4mPT2dV155hbfeeovatWsTDocZNmwYPXv2JDra10QpaNu3byc9PZ3x48cza9Ys6tWrx+WXX87w4cM599xzg86TJEkqFRx8kyRJkiRJkorgXd4llVTiiSdChAQSgk7SD/QmbzKQgcxiFhdwAatYRQtaBJ2lE3iP97iSK9nDHl7kRVJICTpJKhc2bdrE+PHjefXVV1m6dCkNGzZkyJAhXHLJJfTq1YuYmJigE6UK48svv2TSpEm8/vrrvP3221SuXJkBAwYwfPhwkpOTqVKlStCJkiRJpYqDb5IkSZIkSdIJvM7rXMVV9KAHr/EatakddJJ+hAUs4HzO5xM+oS1tmcpU+tM/6CwVwR728Bt+w/M8z7Vcy5M8SXWqB50llRtr164lIyODtLQ05s+fT1xcHCkpKYTDYfr16+fQjVQMtm/fzpQpU0hLS2P69OlER0fTt29fwuEwqamp1K7tf3dKkiQdj4NvkiRJkiRJ0ncYwxju4A7+h//hWZ4lBjfflHWf8iltacvHfExvenMP9zCSkUFn6XtII43ruZ7GNOZVXqU97YNOksqd1atX8/rrr5OWlsbChQupV68eAwcOJCUlhX79+lGnTp2gE6Uy69NPPyUSiRCJRJg3bx5Vq1Zl4MCBXHLJJQwcOJDq1R3qliRJKgoH3yRJkiRJkqRjOMxhruVaXuVVnuRJRjAi6CSdJFvYQmMa8w7vcDd3czZn8yzPBp2l72k96xnOcN7nfUYzmt/wGypRKegsqVxau3Ytr7/+euGQTlRUFElJSQwcOJBQKESrVq2CTpRKtcOHDzN79mwikQhTpkxh1apVNGjQgOTkZFJTU0lOTqZatWpBZ0qSJJU5Dr5JkiRJkiRJ/2UHOxjKUBaykH/yT1JICTpJJ9EhDlGVqkxmMhlksJa1ZJEVdJZ+gDzyeJzHuY/76ElP/s7faUKToLOkcm3nzp1MmzaNSCTCtGnT2LFjB4mJiaSkpDBw4ECSkpKIjY0NOlMK3ObNm5k2bRpTpkxhxowZ7N27l7PPPrtwc+J5551HdHR00JmSJEllmoNvkiRJkiRJ0jesZCUppLCPfWSSSQc6BJ2kYlCd6vyFv7CFLTzDM6xnfdBJ+hE+4AOu4Ap2sYsXeIFBDAo6SaoQ8vLyWLp0KZmZmUQiERYvXkzVqlXp1q0bffv2pVu3bnTp0oWYGI8JV/m3f/9+FixYQFZWFllZWSxevJjY2FiSkpLo27cvQ4YMcTuiJEnSSebgmyRJkiRJkvQf85hHKqmcwRmkk84pnBJ0kopJE5pwF3eRQAIXczF72ENNagadpR9hL3v5Nb9mLGMZznCe4zlqUCPoLKlCWb9+PVlZWcycOZOZM2eydetW6tWrR69evejTpw99+vRx8EflxqFDh1iwYAEzZ84kKyuLhQsXkp+fzznnnEOfPn3o27cv3bt3p3r16kGnSpIklVsOvkmSJEmSJEnAS7zEDdxAiBDjGEd1fJOyPGtFK37OzxnCENrSliUsoT3tg87SSTCRiVzHdcQTz3jGu7VRCkhBQQHLli0rHAqaPXs2+/bto2nTpvTo0YNu3bqRlJREu3btqFSpUtC50gnt3buXBQsWMG/ePObOncu7775LdnY2Z5xxRuFgZ+/evWnQoEHQqZIkSRWGg2+SJEmSJEmq0Aoo4MH//LmVW3mSJ6mEb8CXdx3owAAG8AAPUIMa/IN/MIxhQWfpJNnABoYznPnM527u5n7u9+taClhOTg7vvfceb7/9NvPmzWPBggXs2bOHOnXq0K1bN84//3y6d+/OueeeS7Vq1YLOldi0aRNz585l3rx5zJkzh48++oi8vDzOOOMMunXrRo8ePejduzfNmzcPOlWSJKnCcvBNkiRJkiRJFdZBDnIN1zCRiYxlLFdzddBJKiFJJNGZzjzFUySSyFVcxX3cF3SWTqICCniap7mTO+lOd/7O3zmVU4POkvQfeXl5fPzxx8yZM4f58+czZ84cNm7cSJUqVejYsSPnnnsunTt3pnPnzpx55plER0cHnaxybO/evSxZsoSFCxeycOFC3n33XdasWUNMTAznnHMOSUlJhVsKGzduHHSuJEmS/sPBN0mSJEmSJFVIW9jCIAaxilW8zuv0olfQSSpB/ehHAgk8z/MMZCD1qMcrvBJ0lorBQhZyBVewjW08x3NcxmVBJ0k6jrVr1zJ37lzmz5/PwoUL+eijjzh06BA1a9akQ4cOdO7cmU6dOtG5c2datWpFVFRU0Mkqg/bv38/SpUtZuHAhixYtYuHChXz++efk5+cTHx9Pp06d+OlPf0pSUhJdunShZs2aQSdLkiTpOBx8kyRJkiRJUoWzjGWkkEIMMUSI0JrWQSephF3MxVSlKuMZzx3cwVzm8j7vB52lYnKAA9zFXTzN0wxnOH/mz9TEQQaptMvJyeHjjz8u3MK1cOFCli1bRk5ODrVr1+acc86hXbt2nH322bRr14527doRFxf39Z0PH4YqVYJ9AgpUQUEBa9asYdmyZSxbtoyPPvqIZcuW8dlnn5GXl0e9evUKtwoeGahMSEgIOluSJEnfg4NvkiRJkiRJqlBmMINLuZR2tGMSk2hIw6CTFIDhDGcPe8ggg7/wF+7iLnaxK+gsFbNJTOJarqUBDRjPeDrSMegkSd/ToUOH+PDDD1m0aBEffvghH3/8McuXL2f37t0AtGzalGeBd1NTaXHeeZx11lm0atWKGjVqBBuuYrV582Y+/fTTo4bcPvnkE/bu3QtAs2bNCocjO3bsSOfOnWnevHnA1ZIkSfqxHHyTJEmSJElShTGWsdzMzVzCJbzES1SlatBJCsgN3MAKVjCTmbzN2/SmN5vZzCmcEnSaitkWtvALfkEWWdzDPdzHfUQTHXSWpB9p06ZNrH3rLdqMGsXBw4cJt23L4sWLOXDgAAB169alRYsWtG3blrPOOosWLVrQokUL2rRpQ/Xq1QOuV1Hs3LmT1atXH/WxfPlyPv74Y/bs2QNAXFwcZ511FmeddVbh/9ft27enQYMGAddLkiSpODj4JkmSJEmSpHIvjzzu4R4e4zHu535GMzroJAXsV/yKeczjXd5lIxtpSlNmM5se9Ag6TSWggAKe5mnu5E660Y1xjKMpTYPOkvRjRCLws5/B3r1w443w5z+Tk5PDypUr+fzzz1mxYsVRHxs3bgQgOjqa008/nZYtW5KQkEBCQgKnn346p59+OgkJCTRt2pTKlSsH/OQqhj179rB+/XrWrl3L+vXrWbduHevXr2fNmjWsWLGCHTt2ABAbG0uLFi1o1aoViYmJhR+tW7emcePGAT8LSZIklaSYoAMkSZIkSZKk4rSPffyMnzGDGfyDf/AzfhZ0kkqBGtRgP/sBaEITalKTz/ncwbcKIoooRjKSPvThZ/yMdrTjOZ7jci4POk3S95WXB/fdB488AlFRX9+WlARA5cqVadOmDW3atPnW3fbv33/UINyqVatYu3Yts2fPZv369Rw6dAiASpUq0aRJk8JhuFNPPZUmTZrQsGFDGjduTKNGjWjUqJEbxb7D4cOH2bZtG5s3b2br1q1s27aNTZs2sXXrVtatW1c44LZr1/87crx+/fqFg4hdunRh+PDhhQNuCQkJREe7qVOSJEkOvkmSJEmSJKkc28hGBjGI9awniyySSAo6SaXENwffooiiJS1ZycqAq1TS2tGO93iPu7iLK7iCqUzlz/yZmtQMOk1SUXz1FQwbBrNmQUHB1x8A3buf8K41atSgffv2tG/f/pif37x5M+vXrz9q89jatWuZOXMmW7Zs4csvvyQnJ6fw+sqVKxMfH88pp5zCKaecQnx8PPXq1SMuLo66dese9fHN26pUqXIy/pcoMXv37mXXrl3s3LnzWx9Hbt+xYwebNm1i27ZtbN26le3btx/1GDVq1CgcGmzWrBkDBw48attes2bNqFGjRkDPUJIkSWWJR51KkiRJkiSpXFrKUkKEiCOOTDJpRrOgk1SKPMMz/J7fs5WtAFzKpeSSyxu8EXCZgpJOOtdyLbWoxSu8Qje6BZ0k6bssWgSDB8O2bfCNATROPRX+7/9KJGHbtm18+eWXbNmyhS1btnxrq9l/D4R9c1DuiBo1alCtWjVq165N1apVC/+5cuXK1KlTh9jYWKpXr07NmjULj1w9cts3Heu2I3bu3Pmt23bt2sWRtwj37dtHTk5OYeO+ffvIzs7m0KFD7N69m5ycHPbs2cPevXvJzc391mPVrFnzWwN+Rwbb4uPjadKkCfHx8TRq1IjGjRsft1OSJEn6vtz4JkmSJEmSpHLnDd5gOMPpRjfSSKMOdYJOUilTgxrsY1/hv7ekJREiARYpaKmk0pWuXMM1XMAF3MM93Md9RONxelKpM24cXHst5OfDNwexYmKgT58Sy4iPjyc+Pp6zzjqrSNfv27fvqEG4Ix8HDhxgz549HDx4sPCfc3Jy2L17N7t372bLli1HDZ3t37+fw4cPH/XYx7rtiFq1ahETc/Rbgt8cpKtevTqxsbHExcVRrVo14uPjj7qtcuXK1KpVi1q1ah1za92Rx5EkSZJKmoNvkiRJkiRJKlfGMIY7uINf8kue5Vkq45ux+raa1OQAB8gnn0pUIpFEVrKy8N9VMTWiEREiPM3TjGIUM5jBP/gHLWgRdJokgIMH4aab4KWXjv35ggLo0aNkm76HmjVrUrNmTU477bSgUyRJkqRywZ/gSJIkSZIkqVzIJZebuIlf8Sv+l/9lLGMdetNxVaEKBRSQw9fHziWSyAEOsIlNAZcpaFFEMZKRLGIR+9lPR79EX9YAACAASURBVDryKq8GnSVp/Xro2hVeeeX41+TlQffuJdckSZIkKVAOvkmSJEmSJKnM28lO+tGPV3iFN3iDUYwKOkmlXBWqABQOvrWkJQArWBFYk0qXsziL93iPq7ma4QznUi5lF7uCzpIqpkgE2rWD5cuPPtr0v9WvD4mJJdclSZIkKVAOvkmSJEmSJKlMW81qutGNz/iMWcxiEIOCTlIZcGQb4GEOA3AKp1CLWg6+6ShVqcoYxjCNacxlLh3owFzmBp0lVSx5eTBpEuzbB/n5x78uOhp69oSoqJJrkyRJkhQoB98kSZIkSZJUZi1gAV3pShWq8C7v0olOQSepjDgy+HZk4xt8vfVtJSuDSlIpdhEXsZSltKMdvejFXdx11N8dScUoOhpefBFmzYKEBIiJOfZ1lSrBBReUZJkkSZKkgDn4JkmSJEmSpDJpAhPoTW+60Y35zOc0Tgs6SWXIfx91CpBIohvfdFzxxDOZyTzLs/x//H90pzurWBV0llRx9Ojx9VGnd9zx9Va3/x6Ay8mB7t2DaZMkSZIUCAffJEmSJEmSVKYUUMBoRnM5l3Md1/E6r1Od6kFnqYw51sY3B990IlFEcR3X8QEfcIhDdKQjr/BK0FlSxVGtGrRq9fXgW4sWX2+DO6JGDfjJT4JrkyRJklTiHHyTJEmSJElSmXGIQ1zFVTzEQzzDM4xhDJX8EZd+gCODb4c5XHhbS1qyilXkkx9UlsqItrRlAQu4kRv5OT/nUi5lJzuDzpLKvy1b4De/+Xrr27JlMHo0VK789SBcUtLRg3CSJEmSyj1/KihJkiRJkqQyYTvbuZALySCDyUzmJm4KOkll2PGOOj3IQTayMagslSFVqcojPMI0pjGPeXSgA+/wTtBZUvl2881Qp87/G3i791746CPo0gV69Qq6TpIkSVIJc/BNkiRJkiRJpd4KVtCVrmxkI+/xHskkB52kMu54R50CHneq7+VCLmQpSzmbs+lNb+7irqP+Xkk6SSZOhEmTYOzYr481PaJ1a5g7F66/Prg2SZIkSYFw8E2SJEmSJEmlWhZZ/JSf0oAGLGABbWgTdJLKgWMddRpPPHWo4+CbvreGNGQyk/kbf+MZniGJJFayMugsqfzYvRtGjoRf/hIuvPDbn69UCeLiSr5LkiRJUqAcfJMkSZIkSVKp9QIvMIABXMiFzGQm8cQHnaRy4lgb3wBa0tKBJf1gV3EVH/ABOeTQkY6MZWzQSVL5cMcdkJcHjz0WdIkkSZKkUsTBN0mSJEmSJJU6BRQwmtFcx3XcwR1MYALVqBZ0lsqRKlQBjj345sY3/RhtaMN7vMcd3MGN3EiYMDvYEXSWVHbNmgUvvQTPPgt16wZdI0mSJKkUcfBNkiRJkiRJpcp+9jOEITzCI/ydv/MIjxBFVNBZKmeOt/EtkUQH3/SjVaYyoxnNDGawgAW0pz2zmR10llT2ZGfDtdfCxRd//SFJkiRJ3+DgmyRJkiRJkkqNTWyiJz2Zy1xmMIPhDA86SeXUkcG3wxw+6vZEElnFKvLICyJL5Uwf+rCUpXSkI73oxUhGfuvvnKTvcP/98OWXMGZM0CWSJEmSSiEH3yRJkiRJklQqfMRHdKUre9jDfObTgx5BJ6kcK6AA4FvbBFvSkkMc4v/4vyCyVA41oAHppPMyL/MiL5JEEl/wRdBZUum3dOnXA29PPAGnnhp0jSRJkqRSyME3SZIkSZIkBW4a0+hOdxJJ5H3epxWtgk5SOXdk8K3Sf/2INJFEAFayssSbVL5dxVUsZCF55NGe9ozBDVbSceXmwjXXQFIS/OIXQddIkiRJKqUcfJMkSZIkSVKgxjCGFFK4hEuYylTiiAs6SRXA8Ta+NaQhdanLClYEkaVyrjWteY/3uJM7uYM7GMpQtrM96Cyp9HnkEfj8c3j+eYiKOvH1kiRJkiokB98kSZIkSZIUiDzyuIVbuJ3buZd7eZEXqUzloLNUQeSTD3x78A3gDM5w8E3FJoYYRjOat3iL93mfdrRjGtOCzpJKj88/h4cegt/9Dlq2DLpGkiRJUinm4JskSZIkSZJK3F72MpjBvMzLvMEbjGZ00EmqYI531Cl8fdypR52quPWmN8tYRi96MYABjGQkhzkcdJYUrPx8+J//gdatYeTIoGskSZIklXIOvkmSJEmSJKlErWENXejCYhYzi1mkkhp0kiqg79r41pKWbnxTiahDHcYznpd5mb/xN87nfD7n86CzpOA89xy8+y787W8QExN0jSRJkqRSzsE3SZIkSZIklZh3eZeudCWaaN7lXTrTOegkVVAn2vi2mtXkkVfSWaqgruIqPuIjYomlAx0Yw5igk6SSt2kT3HMPjBoFHToEXSNJkiSpDHDwTZIkSZIkSSXidV6nN71pT3vmMpcEEoJOUgV2ZPDtWBvfEknkEIfYwIaSzlIF1pzmzGY2d3Inv+JXDGEIX/FV0FlSybnxRmjUCO69N+gSSZIkSWWEg2+SJEmSJEkqdmMYwzCGMZzhRIhQm9pBJ6mC+66jThNJBPC4U5W4GGIYzWjmMIeP+Ih2tGMqU4POkorf+PEQicALL0DVqkHXSJIkSSojHHyTJEmSJElSsTnMYa7man7Fr3iKp/grfyWGmKCzpO886rQ+9alLXQffFJiudGUxi+lLXwYykJGM5BCHgs6Sisf27XD77XDDDdC9e9A1kiRJksoQB98kSZIkSZJULHawg3704w3eIJ10RjAi6CSp0HdtfANoSUtWsrIkk6Sj1KEO/+AfTGAC4xhHJzrxER8FnSWdfCNHQkwMPPRQ0CWSJEmSyhgH3yRJkiRJknTSrWQl53M+K1nJHOaQQkrQSdJRvmvjG3x93Kkb31QahAmzhCXEEcd5nMcYxhT+/ZXKvKlT4dVX4c9/hri4oGskSZIklTEOvkmSJEmSJOmkmsc8utKVOOJYyELa0z7oJOlbjgwOHW/jm4NvKk2a0YxZzGIUo/gVvyKZZDazOegs6cfZvx9uvhl+9jMYPDjoGkmSJEllkINvkiRJkiRJOmle4iV605ue9OTf/JtGNAo6STqmohx1uoY15JFXklnSccUQw2hGM5e5rGQl7WnPFKYEnSX9cHfdBXv2wJNPBl0iSZIkqYxy8E2SJEmSJEk/WgEFjGY013ANN3ADr/Ea1akedJZ0XIc4BEAsscf8fCKJHOYw61lfklnSCXWhC4tZTD/6ESLE9VxPNtlBZ0nfz3vvwXPPwZgxEB8fdI0kSZKkMsrBN0mSJEmSJP0oBznIFVzBwzzMy7zMGMZQyR87qZQ7yEEAqlL1mJ9vRSsAjztVqVSb2oxjHBOYQBppnMu5fMiHQWdJRXP4MPzyl3DRRXDFFUHXSJIkSSrD/AmkJEmSJEmSfrAtbKEHPZj+nz9Xc3XQSVKRHBl8q0a1Y36+LnWpRz0H31SqhQmzhCXUpz5d6MKjPFp4jK9Uav3hD7B2LTz7bNAlkiRJkso4B98kSZIkSZL0gyxjGV3owg52MI95XMAFQSdJRXaAA8DxN77B18edrmRlSSVJP8jpnM7bvM1oRnMf99Gf/mxiU9BZ0rF9/DE8+ig88gg0bx50jSRJkqQyzsE3SZIkSZIkfcuRoaDjmcEMkkiiKU1ZwAJa07qEyqST40Qb3wBa0tKNbyoToolmFKOYy1zWsIb2tCeTzKCzpKPl58P110OHDnDjjUHXSJIkSSoHHHyTJEmSJEnSt4xkJE/z9DE/N5axDGQgySSTRRYNaVjCddKPd2Tw7UQb3xx8U1nyU37KYhYzhCEMYhBXcRXZZAedJX3tqadg0SJ48UWIjg66RpIkSVI54OCbJEmSJEmSjrKIRbzAC9zO7UxhSuHteeRxF3dxAzdwD/fwT/75nUNDUml2kINEEUUssce9JpFE1rCGXHJLsEz6cWpRi7/yV9JIYwpT6ExnlrDkuNevY53b4VT81q6FBx6Ae++Fs84KukaSJElSOeHgmyRJkiRJkgoVUMBN3EQ00RRQQJgwH/Ih+9jHEIbwFE/xD/7BaEYHnSr9KAc4QCyxRBF13Gta0IIccvg//q8Ey6ST4xIuYQlLiCeernTlUR4ln/yjrskjj8u5nCu5ko1sDKhUFcL110Pz5jBqVNAlkiRJksoRB98kSZIkSZJU6B/8gw/4gFxyKaCAwxymD304n/NZwAKyyOJn/CzoTOlHO8hBqlHtO685gzMAWMWqkkiSTroEEvg3/+ZRHuV+7qcf/djEpsLPP8IjvMd7ZJPNFVzxrcE46aR46SXIyoK//AWqVAm6RpIkSVI54uCbJEmSJEmSANjHPn7Nr4/agJVHHrvZzRrW8A7vkERSgIXSyXOQgyc8qrchDalNbVazuoSqpJOvEpUYyUjmMpd1rOMcziGDDBaykAd4gHzyySWXOczhKZ4KOlflzZYt8Otfw8iRcP75QddIkiRJKmccfJMkSZIkSRIAf+AP7GDHtzb+5JLLQQ5yB3eQR15AddLJVZTBN/j6uFM3vqk8OJdzWcQiUkghlVT60e+oQed88rmLu/iQDwOsVLkzYgTUqgW/+13QJZIkSZLKIQffJEmSJEmSxCpW8QRPkEvuMT+fSy4zmMFv+W0Jl0nF4wAHTnjUKXw9+ObGN5UXtajFS7xET3qyhz3fes0voIAwYQ5wIKBClSuRCEycCGPHQs2aQddIkiRJKoccfJMkSZIkSRK3cusJr8knnz/yR57n+RIokorXIQ4VaePbGZzhxjeVK2/wBrOZfcxB51xyWcMaRjEqgDKVK3v2wI03wtVXw0UXBV0jSZIkqZxy8E2SJEmSJKmCm8Y03uRNcsg57jUxxBBFFPWox1rWfus4VKms8ahTVUQb2cgv+MVRR5z+t1xyeYZnmMKUEixTufPrX0NuLvzpT0GXSJIkSSrHYoIOkCRJkiRJUnAOc5ibuZlooskj71ufjyGGPPLoTndu5EZSSaUylQMolU6u/eynBjVOeN0ZnMFudrODHdSjXgmUScUjn3wu4zL2spcCCr7z2iii+Dk/51M+pQENSqhQ5cbs2fDCC/Daa1DP101JkiRJxceNb5IkSZIkSRXY0zzNOtYdNfRWhSoAnM7p3MM9rGUt/+bfhAk79KZyYyc7qUvdE17XghYAbn1TmbeZzbSmNQ1pCHz9Wl/pOG8R5JPPbnZzDdeUZKLKg0OH4IYbYOBAuOSSoGskSZIklXMOvkmSJEmSJFVQW9nKAzxAHnlEEUUlKhFLLMMYxju8wxrWMJrRJJAQdKp00u1kJ3HEnfC60zmdylR28E1l3qmcyvM8z1a2sopVPMZjdKc70UQTRdS3BptzyCFChBd4IaBilUn33w+bNsFzzwVdIkmSJKkCiCooKPjuneaSJEmSJKlIvvrqK+bOnUtOTk7QKVKR/PncPzOr2SwAmu9qzoWrLqTbhm5Uy6l2zOurVKlC9+7dqeexZSoHzuVcetObR3n0hNeewRn8kl9yN3eXQJlUsnawg+lMZ8p//uxiF1WowmEOA1CVqnzERySSyLJly/j0008DLlZpVXvDBi66804WX3MNqy+8MOicH6Rhw4YkJSURExMTdIokSZKkInDwTZIkSZKkH2HNmjWkp6eTkZHB3LlzycvLO/GdpNLgp0AmMB54EVhWtLvFxMTQs2dPBg8ezODBg0lIcBucyqZEErmGa/gtvz3htRdxEQkkuPlK5V4++bzP+7zJm2SQwcd8TAEFNNrYiJp9a7LqMzcf6vgqARcDE4Gy/MZTvXr1GDhwIKmpqfTr148aNWoEnSRJkiTpOPyVFUmSJEmSvqfly5cTiUTIzMxk/vz51KlThwsvvJC//e1vpKamUrt27aATpRP6jM9oQQuq3FYFbivafbKzs5k5cyZpaWncd9993HrrrbRt25ZwOEwoFKJjx45ERUUVb7h0kuxiV5GOOgVoQQs+5/NiLpKCV4lKtD/Ynn1z97E7czdbZ29la8et7AvvI/HRRP5S/S9ccMEFbsNSubV27VoyMjKIRCIMGzaMmJgYkpKSSElJ4dJLL6Vx48ZBJ0qSJEn6Bje+SZIkSZJ0Anl5eSxYsIBIJMKkSZP44osviI+Pp1+/foTDYfr160eVKlWCzpRK1JGvi7S0NCZOnMjGjRtp1qwZgwYNIhQK0bNnTypXrhx0pnRcVajC3/k7l3P5Ca99jMd4hmdYz/oSKJNK3s6dO8nKyiIzM5OMjAz27Nlz1GBzp06dyCefSlQKOlUqMdu3b2fKlClEIhGmTp1KdnY2HTp0ICUlhcsuu4zWrVsHnShJkiRVeA6+SZIkSZJ0DAcOHCArK4tIJEJGRgZbt26lRYsWpKSkEA6H6datm5utpG9Yvnw5aWlppKWl8cknn1C/fn0GDBhAKBQiOTmZmjVrBp0oFdrHPmpRizd5k2SST3j9RCZyKZeSTTaxxJZAoVT8tm3bxrRp00hLS2PGjBnk5eXRpUsXwuEwQ4cOpWnTpkEnSqXGN783SE9PZ9u2bbRt25ZQKERKSorfG0iSJEkBcfBNkiRJkqT/2LFjB5FI5JhbHYYNG0abNm2CTpTKhNWrV5OZmUlaWhoLFiwgNjaWPn36EAqFGDx4MI0aNQo6URXcBjaQQAILWEAXupzw+qUspQMd+IzPOJMzS6BQKh7ffH2eP38+1apVo3fv3oTDYQYNGkRcXNGO/5Uqsm9ug544cSIrV64kISGB/v37k5KS4jZoSZIkqQQ5+CZJkiRJqtDWrVvH9OnTyczMZPr06URHR5OUlFS42a1JkyZBJ0pl2pdffsnUqVNJS0vjrbfeIjc3ly5duhAKhbj44otJTEwMOlEV0Md8zNmczad8SmtOfFTdXvZSm9pMYQoDGFAChdLJkZ+fz5IlS8jMzGTChAl89tlnNGjQgOTkZMLhMBdddBGxsW4xlH6MI1tvI5EIixYtom7duvTt25eUlBRSU1OpXbt20ImSJElSueXgmyRJkiSpwlm+fDmRSITMzEzmz59PnTp1uPDCC31zSipm2dnZzJw5k7S0NCZPnszu3bs9JkyBmMMcetCDzWzmFE4p0n0a0pD7uZ8RjCjmOunHOXjwIHPnzi3c7LZ582aaN29OKBQiFApxwQUXEBMTE3SmVC6tXbuWjIwMIpEIs2bNIiYmpvCXai699FIaN24cdKIkSZJUrjj4JkmSJEkq9755HNGkSZP44osviI+Pp1+/foTDYY8jkgJw5OsyLS2NiRMnsnHjRpo1a8agQYMIhUL07NmTypUrB52pciqTTAYxiAMcoCpVi3SfLnShK115kieLuU76/nbu3ElWVhaZmZlkZGSwZ88e2rZtSzgcJhQK0alTp6ATpQpn+/btTJkyhUgkwtSpU8nOzqZDhw6kpKRw2WWX0br1iTeOSpIkSfpuDr5JkiRJksqlAwcOkJWVRSQSISMjg61bt9KiRYvCI0zdLCWVLkeOCUtLS+OTTz6hfv36DBgwgFAoRHJyMjVr1gw6UeXIOMZxHddxkINFvs8VXME+9pFBRjGWSUW3bds2pk2bRlpaGjNmzCAvL48uXboQDocZOnQoTZs2DTpR0n9883uT9PR0tm3b5vcmkiRJ0kng4JskSZIkqdzYsWMHkUjkmFsVhg0bRps2bYJOlFQEq1evLjyib8GCBcTGxtKnTx9CoRCDBw+mUaNGQSeqjHuap3mYh9nM5iLf5z7uYxKTWMayYiyTvts3Xx/nz59PtWrV6N27N+FwmEGDBhEXFxd0oqQT+OY26jfeeIMVK1Zw2mmnkZycTEpKituoJUmSpO/BwTdJkiRJUpm2bt06pk+fTmZmJtOnTyc6OpqkpKTC7QlNmjQJOlHSj/Dll18ydepU0tLSeOutt8jNzaVLly6EQiEuvvhiEhMTg05UGfR7fs94xvMpnxb5Pi/xEjdzM/vZTxRu5VHJyM/PZ8mSJWRmZjJhwgQ+++wzGjRoQHJyMuFwmIsuuojY2NigMyX9CEe23kYiERYtWkTdunXp27cvKSkppKamUrt27aATJUmSpFLLwTdJkiRJUpmzfPlyIpEImZmZzJ8/n7i4ON8ckiqA7OxsZs6cSVpaGpMnT2b37t20bduWUChESkqKx4SpyG7hFj7mY2Yzu8j3eYd36ElPNrKRJjhUreJz8OBB5s6dW7jZbfPmzTRv3pxQKEQoFOKCCy4gJiYm6ExJxWDt2rVkZGQQiUSYNWsWMTExhb/Uc+mll9K4ceOgEyVJkqRSxcE3SZIkSVKpd6zjgOLj4+nXrx/hcNjjgKQK6MjrQlpaGhMnTmTjxo00a9aMQYMGEQqF6NmzJ5UrVw46U6XUUIYSQwwTmFDk+2xkI01pyhzmkERSMdapItq5cydZWVlkZmaSkZHBnj17aNu2LeFwmFAoRKdOnYJOlFTCtm/fzpQpU4hEIkydOpXs7Gw6dOhASkoKl112Ga1btw46UZIkSQqcg2+SJEmSpFLpwIEDZGVlEYlEyMjIYOvWrbRo0aLwCFM3O0n6piPHhKWlpfHJJ59Qv359BgwYQCgUIjk5mZo1awadqFKkG904l3N5iqeKfJ8CCqhBDZ7jOa7m6mKsU0WxYcMGpk6dSmZmJjNmzCAvL48uXboQDocZOnQoTZs2DTpRUinxze+N0tPT2bZtm98bSZIkSTj4JkmSJEkqRXbs2EEkEjnmVoNhw4bRpk2boBMllQGrV68uPCJwwYIFxMbG0qdPH0KhEIMHD6ZRo0ZBJypgLWjBdVzHXdz1ve7XlraECfMgDxZTmcq7b74+zZ8/n2rVqtG7d2/C4TCDBg0iLi4u6ERJpdyxtmGfdtppJCcnk5KS4jZsSZIkVSgOvkmSJEmSArVu3TrS/3/27j2u6irR+/hny03kqqiAigGO5iVTUzo66kjgjXFvQQt1HGs6TanTq5R67MmaOd3sqTRPRk1W1pxpmmmSaBLcKI2Cl1HBMlMr81KapQYGoohySWQ9f3TYE4HKRmAjfN+99usVv70u399vb/gt3Iu10tLIyMhg8+bNuLm5MWrUKMfqBd26dXN1RBG5ihUUFJCZmUlqairr16+nsrKS4cOHY7PZmDp1Kr1793Z1RHEBH3xYznKnV26zYSOAAP7G35oombQ2VVVV7Nq1C7vdTkpKCvv376dz587ExcWRmJjI+PHj8fLycnVMEbmKVa96m5GRwccff0xgYCBjx47FarWSkJCAv7+/qyOKiIiIiDQZTXwTERERERGRZrd3714yMjKw2+3k5OTowxkRaRalpaVkZ2eTmprK6tWrKS4upn///thsNqxWq7YJayNOc5qOdOR93mcCE5yqm0QSH/IhOeQ0UTppDcrLy9m6datjZbe8vDwiIiKw2WzYbDaio6Nxd3d3dUwRaYWOHDlCeno6GRkZbNq0CXd3d8cfFU2bNo3Q0FBXRxQRERERaVSa+CYiIiIiIiJNrq7teLp27cqECRNITEzUdjwi0uyqfy6lpqbyj3/8g+PHjxMeHs7kyZOx2WyMGTMGDw8PV8eUJrCf/fSjH3vYw/Vc71TdF3iB/8f/4wQnmiidXK1OnTpFVlYWdrud9PR0zpw5Q//+/UlMTMRmszF06FBXRxSRNubkyZOsWbOGjIwMMjMzKS0tZciQIVitVmbMmEHfvn1dHVFERERE5Ipp4puIiIiIiIg0ibKyMrKyssjIyCA9PZ0TJ04QGRnp2MJUKyuJSEtSvU1Yamoqn3/+OUFBQfzyl7/EZrMRFxeHr6+vqyNKI9nIRmKI4Tu+owtdnKqbQQY2bJzhDH74NVFCuVocPXqUzMxM7HY769at48KFCwwfPpzExERuvvlmevTo4eqIIiKAfjcTERERkdZLE99ERERERESk0WhVARFpDQ4fPuzYojA3NxcvLy9iY2Ox2WzEx8cTHBzs6ohyBf7O3/kNv6GCCtrRzqm6+9hHf/o3aLU4aR1+/PMhJycHb29vYmJiSExMZPLkyQQGBro6oojIJdW1GndYWBhxcXFYrVatxi0iIiIiVxVNfBMREREREZEr8vXXX5OWlkZGRgabN2/Gzc2NUaNGOVYP6Natm6sjiog0WGFhIWvXriU1NZX169dTWVnJ8OHDsdlsTJ06ld69e7s6ojjpuf/97xjHnK5bTjk++PAu7zKFKU2QTlqaqqoqdu3ahd1uJyUlhf3799O5c2fi4uJITExk/PjxeHl5uTqmiEiDVa96m5GRwccff0xgYCBjx47FarWSkJCAv7+/qyOKiIiIiFyUJr6JiIiIiIiI0/bu3UtGRgZ2u52cnBx9OCIibUJpaSnZ2dmkpqayevVqiouL6d+/PzabDavVqm3CrhIP8ACb2MQOdjSofhhhzGc+C1jQyMmkpSgvL2fr1q2Old3y8vKIiIjAZrNhs9mIjo7G3d3d1TFFRBrdkSNHSE9Pr/OPmqZNm0ZoaKirI4qIiIiI1KCJbyIiIiIiInJZdW2H07VrVyZMmEBiYqK2wxGRNqf652Jqair/+Mc/OH78ONdccw3x8fHYbDbGjBmDh4eHq2NKHW7lVk5zGjv2BtUfwxgGMIDlLG/kZOJKp06dIisrC7vdTnp6OmfOnKF///4kJiZis9kYOnSoqyOKiDSrkydPsmbNGjIyMsjMzKS0tJQhQ4ZgtVqZMWMGffv2dXVEERERERFNfBMREREREZG6lZWVkZWVRUZGBunp6Zw4cYLIyEjHFqZa2UhE5N9+vE3Yzp07CQoK4pe//CU2m424uDh8fX1dHVH+11jGEkkkK1jRoPp3cAfHOc4/+WcjJ5PmdvToUTIzM7Hb7axbt44LFy4wfPhwEhMTufnmm+nRo4erI4qItAj63VBEREREWipNfBMREREREREH/VW/iMiVO3z4sGOLxNzcXLy8vIiNjcVmsxEfH09wcLCrI7ZpAxjALdzC4zzeoPpP8iR/4S98wReNnEyaw4+/P3NycvD29iYmJobExEQmT55MYGCgqyOKiLRoda0GHhYWRlxcHFarVauBoFFUYQAAIABJREFUi4iIiEiz0sQ3ERERERGRNu7IkSOkp6eTkZHB5s2bcXNzY9SoUY6/3u/WrZurI4qIXLUKCwtZu3YtqamprF+/nsrKSoYPH47NZmPq1Kn07t3b1RHbnCCCWMQi7ubuBtV/m7e5jdsoowx33Bs5nTS2qqoqdu3ahd1uJyUlhf3799O5c2fi4uJITExk/PjxeHl5uTqmiMhVa+/evWRkZGC328nJySEwMJCxY8ditVpJSEjA39/f1RFFREREpBXTxDcREREREZE2SB9OiIg0v9LSUrKzs0lNTWX16tUUFxfTv39/bDYbVqtV24Q1gzOcIYAA1rCGX/LLBrXxAR8wnOEc5jARRDRyQmkM5eXlbN261bGyW15eHhEREdhsNmw2G9HR0bi7a9KiiEhju9QfVU2bNo3Q0FBXRxQRERGRVkYT30RERERERNqAuraj6dq1KxMmTCAxMVHb0YiINLPqn8upqan84x//4Pjx41xzzTXEx8djs9kYM2YMHh4ero7Z6uxiFzdwA/vZz7Vc26A2CimkC13IIotYYhs5oTTUqVOnyMrKwm63k56ezpkzZ+jfvz+JiYnYbDaGDh3q6ogiIm3KyZMnWbNmDRkZGWRmZlJaWsqQIUOwWq3MmDGDvn37ujqiiIiIiLQCmvgmIiIiIiLSSpWVlZGVlUVGRgbp6emcOHGCyMhIxxamWllIRKTl2Lt3L6mpqWRkZLBz5046derEpEmTsNlsxMXF4evr6+qIrcK7vMt0pnOOc7SnfYPbCSSQJSxhNrMbMZ046+jRo2RmZmK321m3bh0XLlxg+PDhJCYmcvPNN9OjRw9XRxQREfS7qYiIiIg0HU18ExERERERaUX0V/UiIle/w4cPO7ZozM3NxcvLi9jYWGw2G/Hx8QQHB7s64lVrCUv4I3/kG765onZu4AbGM55neKaRkkl9/fj7IycnB29vb2JiYkhMTGTy5MkEBga6OqKIiFxCXauRh4WFERcXh9Vq1WrkIiIiIuIUTXwTERERERG5yh05coT09HQyMjLYvHkzbm5ujBo1CqvVyrRp0wgNDXV1RBERaaDCwkLWrl1Lamoq69evp7KykuHDh2Oz2Zg6dSq9e/d2dcSryu/4HfvYxyY2XVE7t3ALFiykkto4weSiqqqq2LVrF3a7nZSUFPbv30/nzp2Ji4sjMTGR8ePH4+Xl5eqYIiLSQHv37iUjIwO73U5OTg6BgYGMHTsWq9VKQkIC/v7+ro4oIiIiIi1YO1cHEBEREREREeft3buXxYsXM2rUKCIjI3n88cfp2LEjr7/+OidOnGD9+vXMnz9fk96k2X355ZdYLBZWrlzpOObr64vFYqn1aNeuHV26dCEhIYEdO3a4MPWl1XVOIs2lc+fO3HbbbdjtdoqKili1ahWRkZE8/fTT9OnThwEDBrBw4UK2bt2K/r718g5xiEgir7idXvTiEIcaIZHUpby8nKysLObPn0+PHj0YNmwYf/3rXxk/fjzr168nLy+PN998E5vNpklvLchP75dLly513PMbY9vZlJQUBg8ejLe3t6Pdzz777IrblaaTlpZWY+xXXl7e5H2uXLnS0V/79jW3tNaYrmUaMGAADz74IFu3buXw4cM8+uijnDp1ijvvvJPg4GDGjRtHcnIyeXl5ro4qIiIiIi2QJr6JiIiIiIhcBS5cuMDWrVtZuHAhffr04brrruO5554jMjKS9PR08vPzeeedd7jtttv0F/HS4pw9e5Zdu3YBEB8fjzEGYwynTp1ixYoV5ObmMnLkSLKyspxut3fv3lit1qaILdLidOjQAZvNxptvvsnJkyfZsmULY8eO5W9/+xujR48mIiKCOXPmYLfbOX/+vKvjtkiHOdwoE9/CCecIR648kDicOnWK1NRUbrvtNsdEh6ysLGbPns1HH33EoUOHSE5OZuzYsbi7u7s6rtTDggULMMYwaNCgK25r27Zt/OpXv2L8+PEUFBTw5ZdfNspkOmlaCQkJGGOIj49vtj5nzJiBMYbY2Nhm61MaT3h4OPPnz3dMcn711Vfp2LEjf/jDHxwToR977DH279/v6qgiIiIi0kLoXwhERERERERaqLKyMrKyssjIyCA9PZ0TJ04QGRmJ1Wrlf/7nfxg5ciQWi8XVMUUaLCAggClTplBaWsqsWbNISkpyauUWYwxVVVVUVVVdcRZfX18GDx7M1q1br7gtkeZQva31qFGjSE5OZu/evaSmppKRkcGKFSvo1KkTkyZNwmazERcXh6+vr6sju9wFLvAN3zTaxLdTnKKYYgIIaIR0bdPRo0fJzMzEbrezbt06Lly4wPDhw3niiSe4+eabNbFJHFJTUzHGMH/+fHx9ffH19eXo0aOA7uEirVVQUBC33XYbt912W43fjV955RUef/xxx+/GiYmJ+t1YREREpA3TxDcREREREZEW5OTJk6xZs4aMjAwyMzMpLS1lyJAhzJ07lxkzZtC3b19XRxRpdDfddBPwwxa+p0+fJjAwsF71/Pz8OHRIWw2KwA/bhA0YMIDHHnuMw4cPY7fbSU1NZcaMGXh5eREbG4vNZiM+Pp7g4GBXx3WJb/iG85xvlIlvEUQAcIQjDOLKV7NqS378/szJycHb25uYmBhee+01Jk+eXO97gLQt1ZPcgoKCXJxERFzB29sbm82GzWZj+fLl5ObmkpGRwXvvvccLL7xA165dmTBhAomJiUyYMAFPT09XRxYRERGRZqKJbyIiIiIiIi525MgR0tPTycjIYPPmzY5VfJ588kmmTZtGaGioqyOKNCljjOP/tVKDyJWLjIxk/vz5zJ8/n8LCQtauXUtqairz5s3j7rvvZvjw4dhsNqZMmUKfPn1cHbfZHOYwAL3odcVtXcM1WLBo4ls9VFVVsWvXLux2OykpKezfv5/OnTsTFxfHgw8+yPjx4/Hy8nJ1TGnhLly44OoIItJC/HjV22eeeYa9e/eSkZGB3W4nPj6ewMBAxo4di9VqJSEhAX9/f1dHFhEREZEm1M7VAURERERERNqivXv38thjjzFs2DAiIyN5/PHH6dixI6+//jonTpxg/fr1zJ8/X5Pe5Krzs5/9DGMMM2bMqHedTZs2AT+sWBUQEEBaWhoWi8XxOHDgANOmTSMoKMhx7PXXX69Rpry8HKBW3SNHjjB9+nQCAwMJCgrCarXWWCVu6dKlWCwWzp07x7Zt2xz13N3//beCDTknkZaic+fO3HbbbdjtdoqKili1ahWRkZE8/fTTXHvttQwYMICFCxeydevWGpNQW6NDHMIXX7rQ5Yrb8sabYIL5iq8aIVnrU15eTlZWFvPnz6dHjx4MGzaMv/71r4wfP54tW7Zw4sQJ3nzzTWw2mya9tSLO3i8LCgqYN28e4eHheHp60qVLF6ZOncru3bsdZarv6+np6cAPqz5ZLBaGDx9er3t4XarrWSwWevTowY4dO4iNjcXPz48OHTpw0003sW3btlr1Tp48yf3330+vXr3w9PSkY8eOxMXFsXHjxhrlKioqeOSRR+jbty8dOnSgU6dO2Gw2Vq9eXWsCX32uwcXUZ7xUWFjoVD+VlZWkpKQwbtw4QkJC8Pb2ZuDAgSQnJ9e5tfyPr4mXlxc9evRg7NixvPHGG5SVldUqn5+ff8lxWUOuy/79+0lISCAgIAAfHx9Gjx590W1vNaZrnQYMGMCDDz7I1q1bOXz4MI8++iinTp3izjvvJDg4mHHjxpGcnMy3337r6qgiIiIi0hSMiIiIiIiINLnKykqzZcsW8+CDD5revXsbwISFhZnZs2eb1atXm4qKCldHFGlSu3btMoCJj493HCsuLjbvvfee6dq1q/Hw8DDr16+vUSc+Pt4AZsyYMWbjxo3m3LlzZvv27cbNzc0UFBTUKFNWVlZn3fj4eJOTk2POnj1r1q9fb7y9vU1UVFStfD4+PmbkyJFNcOYiLVP1fWnevHmme/fuBjDXXHON4770/fffuzpio1toFppBZlCjtTfcDDdJJqnR2rvaFRUVmXfeecfceuutxt/f3wCmf//+5tFHHzUfffSRq+OJCw0aNMh07969xrFvv/3WXHPNNSY4ONisWbPGlJSUmM8++8yMGTPGtG/f3uTk5NQof7H7vTENv4cPGjTI+Pj4mBEjRjjGCjt27DDXX3+98fT0NJs2bXKUzcvLMxERESY4ONjY7XZTXFxsDhw4YKZOnWosFot57bXXHGXvvPNOExAQYNatW2dKS0tNfn6+WbBggQHMxo0bG3wNLuZy4yVn+rHb7QYwTz31lCkqKjIFBQXmhRdeMO3atTMLFiyo0W/1NQkJCTF2u92cOXPG5Ofnm0WLFhnALFu2rFbGH4/LsrOzjb+/f61xmTN5v/jiCxMYGGi6d+9u1q1bZ0pKSswnn3xixo8fb8LDw42Xl1e9rqG0ToWFheYvf/mLSUxMNL6+vqZdu3Zm6NCh5tFHHzX79u1zdTwRERERaSSa+CYiIiIiItJESktLzerVq83s2bNNcHCwAUxkZKSZN2+e2bJli6mqqnJ1RJFmUz3x7ccPi8VigoKCzOTJk82HH35Yq071h6Rr1669aLuXm/hmt9trHL/lllsM4Jg4V00T36St++yzz8yjjz5qhg4dagDTqVMnc+utt5p33nnHlJSUuDpeo5hmppkpZkqjtfcr8yuTYBIarb2r0ddff21effVVY7Vajaenp3FzczMjR440zz//vDl69Kir40kLUdfEt9/85jcGMG+99VaN43l5ecbLy8sMHTq0xvGmmvgGmF27dtU4/sknnxjADBr074myt99+uwHM22+/XaNseXm56datm/H29jb5+fnGGGMiIiLMz3/+81r99enTp8bEN2evwcVcbrzkTD92u91ER0fXamPWrFnGw8PDFBcXO45VX5OUlJRa5SdOnFjnxLefjstmzpxZa1zmTN7ExEQDmHfffbdG2ePHjxsvLy9NfBMH/W4uIiIi0nppq1MREREREZFGdPLkSd58802mTZtG165dSUhIYOfOncydO5d9+/Zx6NAhkpOTGTVqFBaLxdVxRZpdfHw85oc/xKOqqorCwkLS09OJioq6aJ0bb7yxwf39tN2wsDAAbXUk8hMDBgzgscce46OPPuLQoUM88sgjHD58mBkzZtC1a1dsNhsrVqzgxIkTro7aYIc4RCSRjdZeOOFtcqvTvXv3snjxYkaNGkV4eDj33XcfAK+99hqFhYVs3brVscWpyMWkpaXRrl07rFZrjeMhISEMGDCAnTt3cuzYsSbP4ePjw+DBg2scGzhwIN26dWPPnj3k5eUBsGrVKgAmTZpUo6yXlxexsbGUlZXxz3/+E4CJEyeSk5PD7Nmz2b59u2N70wMHDhAdHe2o29jX4GLjJWf6sVqttbZuBRg0aBDnz59n7969jmPV1yQuLq5W+czMTJKSkmod/+m4rHv37kDNcZkzed9//30AJkyYUKNst27d6NOnT63+pe3y9vbGZrPx6quvcvz4cbZs2UJiYiKZmZmMHj2akJAQx9bw33//vavjioiIiIgTNPFNRERERESkEWzevJlf/OIXBAcHM2fOHMrKyli2bBl5eXl89NFHPPbYY/Tt29fVMUWuSj4+Pg2uGxAQUONrT09PAKqqqq4ok0hrFhkZyfz589m6dSvHjh1j2bJlVFZWMm/ePHr06EFMTAwffPCBq2M67TCHG3Xi2zVc06Ymvi1ZsoRevXpx3XXXkZyczHXXXcfatWspKirCbrdz2223ERgY6OqYchWoqKiguLiYqqoqAgICsFgsNR4ff/wxAF988UWTZ7nYe7Zr164AfPfdd4687du3x8/Pr1bZ4OBgAPLz8wF46aWXePPNNzl8+DCxsbH4+/szceJEx0QxaJprUNd4ydl+iouLeeSRRxg4cCAdO3Z0lHvggQcAKC0trdHuxa7Jxfx0XNau3Q8fUVWPy5zJW1FRQUlJCe3bt8fX17dWX9WvochPubm5MWrUKJ555hkOHjzIzp07mTNnDnv27GHy5MmEhIQwa9YsysrKXB1VREREROpBE99EREREREQawQcffMCnn35KSkoKhYWF2O127rzzTn3gInKV0AqMInULDQ1lzpw5ZGZm8t133/G3v/2N7du3OyYfXC3yyOMUp+hHv0ZrM4IIznCGU5xqtDZbsnfffZeePXuSk5PDsWPHeOWVV5g4cSJeXl6ujiZXGS8vLwIDA3F3d+f8+fOOlWB/+rjpppvq1d6V3MNPnjyJMabW8e+++w74YfKUl5cXAQEBlJeXU1JSUqts9UqYISEhjjy33norWVlZnD59mrS0NIwxTJ06leeeew5o/GtwMc72Y7PZWLRoEXfddRcHDx6kqqoKYwzLli0DcFyry12T5sjr5eWFn58f5eXlnD17tlZbRUVFjZZLWrcbbriBJ554gj179nDo0CF+85vf8NZbb3Hu3DlXRxMRERGRetDENxERERERkUYSGBjIzTfffEWrU4mIa3To0KHGtkbXXnstK1ascGEikZbH39+f6dOn06FDB1dHcdrnfA5Af/o3WpvhhANwhCON1mZLFxUVxYgRIxyrNIk01NSpU6msrGTbtm21nlu8eDE9e/aksrKyXm1dyT28vLycHTt21Dj26aef8u233zJo0CBCQ0MBmDJlCgBr1qypUbaiooLs7Gy8vb0d220GBgayf/9+ADw8PBg3bhxpaWlYLJYa9RvzGlxKffu5cOEC27ZtIyQkhHnz5tGlSxfHpMK6Vr6qviZr166t9dyQIUMc2yA3VV749zar1VueVissLOTAgQMN6l/atsjISGw2m6tjiIiIiIgT9C8UIiIiIiIiItLm3XDDDRw8eJCjR4+Sm5vL4cOHGT16tKtjiUgj+ZzPCSKIYIIbrc1ruIZ2tGtTE99EGsvTTz9Nr169uOOOO8jMzKS4uJiioiJeffVVnnjiCZYuXYq7u3u92rqSe3hAQAAPP/wwubm5nDt3jo8++ohZs2bh6elJcnJyjbwREREkJSWRkZFBSUkJBw8eZObMmeTl5ZGcnOzY8hRg7ty5fPLJJ1RUVPDdd9+xZMkSjDHExMQ0yTW4lPr24+bmRnR0NPn5+Tz77LMUFhZSVlbGxo0beeWVV+psNyIigvvuu481a9ZQUlLCsWPHuPvuu8nLy2vwxDdnrstTTz1Fp06dSEpKYv369Zw9e5bPP/+cWbNm1bn9qYiIiIiItD6a+CYiIiIiIiIiTcrX15chQ4YAkJ6ejsVioW/fvhctv337diwWC+np6QB4e3vX2saseuWUH5eZNWtWnXX/8Ic/AD9sPbZ48WLgh5VIrFaro73nn3+e66+/nn79+jF9+nSSk5Pp16/xtkQUEdfax75GXe0NwAsvQgjhK75q1HZFWoulS5disVjYs2cPx48fx2KxOO7JXbt25cMPPyQhIYF77rmHLl260LdvX9577z3S09OZNm0aUPf93mKxsH37dkc/V3IP9/X15cUXX+Txxx8nNDSUX/ziF3Ts2JENGzYwZswYR7mQkBB27NjBr371K+bNm0dQUBA33ngj586dIysri7vuustRdvPmzfTt25cZM2bQqVMn+vXrx/vvv89rr73Gww8/7ChX32twMfUZLznbT0pKCnPmzOHFF1+kW7duRERE8OabbzJz5kwAxo0bx7Bhw2pck+nTp3Pvvfc6rsmpU6fYsmULPXv2bNC4zJm8vXr1Ijc3l6ioKG655Ra6du3K7bffzr333svAgQOpqKjAYrFw5513Xu6tICIiIiIiVymLMca4OoSIiIiIiMjVbsmSJbz88st89ZU+/BYRkdatc+fOLFq0iN/97neujlJv0UTTl768Qu1Vi67ESEYyjGEkk3z5wle5G2+8kejoaJYsWeLqKCKNYvDgwRQWFnLs2DFXRxGRFmTDhg3ExsZSUFBA586dXR1HRERERC5DK76JiIiIiIiIiIhIq/Y5n9OPxl/FMYIIbXUqIiIiIiIiIuIimvgmIiIiIiIiIiIirVYhhRRQ0CQT38IJ11anIiIiIiIiIiIuoolvIiIiIiIiIiIi0mp9yqcADGRgo7cdTrhWfBO5yixduhSLxcKePXs4fvw4FouFP/zhD66OJSIiIiIiIg2giW8iIiIiIiIiIiLSau1mN13pSiihjd52OOGUUMJJTjZ62yLSNBYsWIAxpsbjySefdHUsERERERERaQBNfBMREREREREREZFWaw97GMzgJmk7nHAArfomIiIiIiIiIuICmvgmIiIiIiIiIg7V239ZLBZ69Ojh6jgN5uvr6ziPHz/atWtHly5dSEhIYMeOHa6OKSLNYDe7GcSgJmm7Jz1pRztNfJOrWmu49589e7bO+350dLSro9XL7t27mT17Ntdeey2+vr74+vrSp08fxo8fzzPPPMOuXbswxjRphku9Dy42rrJYLLRv357rr7+el156qckzOiMtLa1GzvLy8ibvc+XKlTWui4iIiIiIND1NfBMRERERERERh+rtvwYNappJIs3l7Nmz7Nq1C4D4+HjHVmanTp1ixYoV5ObmMnLkSLKyspxut3fv3lit1qaILSKN7Dzn2ce+Jpv45okn3ejGV3zVJO2LNIfWcO/39fV13OuDg4Nxc3PDGMOmTZucbqs57/VVVVU8+OCDDBs2DC8vL1JSUigoKODYsWO89dZbhIWF8dBDD3HDDTewc+fOJs1yqffBxcZVFRUVbN++HX9/f+655x4efPDBJs3ojISEBIwxxMfHN1ufM2bMwBhDbGxss/UpIiIiItLWaeKbiIiIiIiIiLQZAQEBTJkyheeee47z58+TlJTkVH1jDFVVVVRVVV1xFl9fX0aNGnXF7YjIxX3O53zP90221SlABBF8zddN1r6INK/mvNf/13/9F0uWLOGPf/wjL774IoMHD8bb25vAwECioqL405/+1KImk/2Up6cngwcP5u2336Zdu3YsW7aMoqIiV8cSEREREZE2RBPfRERERERERKTNuemmmwDYu3cvp0+frnc9Pz8/Dh06xNq1a5sqmog0oj3swQsv+tCnyfoIJ1wrvom0Is11r9+3bx/PPPMMQ4cOZe7cuRctt3Dhwha/bWZYWBihoaFUVlayZ88eV8cREREREZE2xN3VAUREREREREREmpsxxvH/FovFhUlEpCntZjfXcR0eeDRZH+GE8zEfN1n7ItI6rVixgqqqKhITEy9ZLjAwkLKysmZK1XDVY6uWPklPRERERERaF634JiIiIiIiItKGnDx5kvvvv59evXrh5eVFjx49GDt2LG+88cZlP1StrKwkJSWFcePGERISgre3NwMHDiQ5ObnWdmAVFRU88sgj9O3blw4dOtCpUydsNhurV6/mwoULTpdrbJs2bQJgwIABBAQEkJaWhsVicTwOHDjAtGnTCAoKchx7/fXXa5QpLy8HqFX3yJEjTJ8+ncDAQIKCgrBarRw6dMjR99KlS7FYLJw7d45t27Y56rm76+8TRRrbh3xIFFFN2kc44RzhSJP2IXIldO//wY+vg6enJx07diQuLo6NGzc6yvz0nt6U9/p//etfAAwaNKjJzgecew0b6ptvviEvLw9/f38GDBhQ47mCggLmzZtHeHg4np6edOnShalTp7J79+4ryuns+zo/P/+Sr5mzeQH2799PQkICAQEB+Pj4MHr0aLZu3ers5RMRERERkSugiW8iIiIiIiIibUR+fj5RUVG8/fbbJCcnU1hYyM6dO4mOjuY///M/efXVVy9Z//3332fGjBnExMSwb98+jh49yuzZs7n//vt58MEHa5S95557eOGFF3jxxRc5efIk+/bto2/fvsTHx7NlyxanywHExMQQFBTE9u3bG3wNzpw5w6pVq7j//vvx8PDg+eefByAhIQFjDPHx8QDMmTOHu+++m6NHj7J9+3bc3Nxqlan20+NJSUkkJSVx/PhxUlJS2LBhA7/61a8c5RcsWIAxBh8fH0aOHIkxBmMMlZWVDT4vEantAhfYze5mmfh2jnMUUNCk/Yg0hO79Na/D3//+d8d1+OCDD+jQoQOxsbG8/vrrQO17erWmuNfn5eUB0KlTpyY7H3DuNXTW+fPn2b17NzNnzsTDw4M//vGP+Pv71zjHqKgo3nnnHZYvX05RURGbNm2iqKiIESNGkJub26CcDXlf//g1S01NZcuWLTVeM2fzfvnll4wYMYKPPvqId999lxMnTrB8+XIWLVpU54Q6ERERERFpIkZERERERESu2OLFi014eLirY4hc0u23324Ak5KSUuu5iRMnmmXLljm+HjRokOnevXuNMna73URHR9eqO2vWLOPh4WGKi4sdxyIiIszPf/7zWmX79OljNm7c6HQ5Y4wZM2aM6dixo8nJybnoOf7Yrl27DFDjYbFYTFBQkJk8ebL58MMPa9WJj483gFm7du1F260uU1ZWVudxu91e4/gtt9xiAFNQUFDjuI+Pjxk5cmS9zkWkJQkKCjLLly93dYzL2mV2GQzmU/Npk/ZzyBwyGMyHpvbPlNYkKirKPPDAA66OIU5qa/d+Y4wJDg42bm5uNY5VX4e33367xvHy8nLTrVs34+3tbfLz8x3Hm+NeHxISYgDzwQcf1Pn8oEGDaoxh4uPjG3Q+zryG1f3+9H1gTN3jqurHlClTzJdfflmrzm9+8xsDmLfeeqvG8by8POPl5WWGDh3qOOZMTmfe1xd7zWbOnFnrNXMmb2JiogHMu+++W6Ps8ePHjZeXl/Hy8qqVTa4O2dnZdX4/i4iIiEjLpBXfRERERERERNqIVatWARAXF1fruczMTJKSki5Z32q11to+C37Youv8+fPs3bvXcWzixInk5OQwe/Zstm/f7ti67MCBA0RHRztdDqix4oYz4uPjHSutVFVVUVhYSHp6OlFRF18F6sYbb3Sqjx/7abthYWEAfPvttw1uU0Sct4MddKADfenbpP30pCfuuPMVXzVpPyIN0Vbv/T9VfR1Qf4ZVAAAgAElEQVQmTZpU47iXlxexsbGUlZXxz3/+s97tNca9vnv37gAUFhbW+fzu3bsxxrBjx45azzlzPs68hvXx43HVsWPHmD59OqtWrWLFihW1yqalpdGuXTusVmuN4yEhIQwYMICdO3dy7Ngxp3M25H3909es+vr/+DVzJu/7778PwIQJE2qU7datG3369KnVv4iIiIiINA1NfBMRERERERFpAyoqKiguLqZ9+/b4+fk1qI3i4mIeeeQRBg4cSMeOHbFYLFgsFh544AEASktLHWVfeukl3nzzTQ4fPkxsbCz+/v5MnDjR8UGls+Wam4+PT4PrBgQE1Pja09MTgKqqqivKJCLO2cEOhjEMd9ybtB933OlOd45wpEn7EXGW7v0/uNx1CA4OBn7YPrO+GuNe/4tf/AKAjz/+uN51wPnzceY1dFb37t1544036NWrF88++ywfffRRrZxVVVUEBAQ4+q1+VJ/3F1984VTOhr6vf/qatWv3w8dj1a+ZM3krKiooKSmhffv2+Pr61uqra9eu9c4lIiIiIiJXRhPfRERERERERNoALy8vAgICKC8vp6SkpEFt2Gw2Fi1axF133cXBgwepqqrCGMOyZcsAMMY4ylosFm699VaysrI4ffo0aWlpGGOYOnUqzz33nNPlWiOLxeLqCCKt2od8SBQXX9mxMYUTztd83Sx9idSX7v0/uNx1OHHiBPDDql6N7VL3+rvuuot27dqxcuXKGtfxcpw9H2dew4Zo3749Tz31FMYYFi5cWCNnYGAg7u7unD9/3rFK3E8fN910k1M5G+N9XRdn8np5eeHn50d5eTlnz56t1VZRUVGj5RIRERERkUvTxDcRERERERGRNmLKlCkArF27ttZzQ4YM4b777rto3QsXLrBt2zZCQkKYN28eXbp0cXyYW1ZWVqt8YGAg+/fvB8DDw4Nx48aRlpaGxWJhzZo1TpdrjTp06MD333/v+Praa6+tc5swEXFeKaXsZS/DGNYs/YUTrq1OpUXSvf8H1dfhp+1XVFSQnZ2Nt7d3rS0rG8Ol7vX9+vVj4cKF7N27lyVLlly0jeqtYH+svufj7GvYUImJiQwZMoTs7GzWr1/vOD516lQqKyvZtm1brTqLFy+mZ8+eVFZWOp3zSt7Xl1LfvPDvbVartzytVlhYyIEDBxrUv4iIiIiIOE8T30RERERERETaiKeffpqIiAjuu+8+1qxZQ0lJCceOHePuu+8mLy/vkh8Surm5ER0dTX5+Ps8++yyFhYWUlZWxceNGXnnllTrrzJ07l08++YSKigq+++47lixZgjGGmJiYBpWLiYkhKCiI7du3X/nFaAFuuOEGDh48yNGjR8nNzeXw4cOMHj3a1bFEWoUP+ZBKKvk5P2+W/sIJ11an0iLp3l/zOiQlJZGRkUFJSQkHDx5k5syZ5OXlkZyc7NgitDFd7l6/aNEiHnjgAR566CF++9vfsnPnTkpLSykrK+PTTz/lqaeeIj4+Hjc3N4YN+/dE3vqeT0New4awWCw8+eSTACxcuNCxOtvTTz9Nr169uOOOO8jMzKS4uJiioiJeffVVnnjiCZYuXYq7u7vTOa/kfX0p9c0L8NRTT9GpUyeSkpJYv349Z8+e5fPPP2fWrFl1bn8qIiIiIiJNxIiIiIiIiMgVW7x4sQkPD3d1DJHLKiwsNElJSSYiIsJ4eHiY0NBQM2PGDHPw4EFjjDHPPvusAWo8fv/73xtjjCkoKDBz5swxYWFhxsPDwwQHB5vbb7/dLFy40FF26NChxhhjdu/ebebMmWP69etnOnToYDp16mSGDx9uXnvtNVNVVeXIU99yxhgzevRo07FjR5OTk3PZ8/Tx8al1Htdee+1Fy+fm5tYq/9N/Nlm1alWt53/961/XWbf6mv30+KRJkxzt7d+/34wePdr4+PiYsLAw89JLL132vERagqCgILN8+XJXx7ikRWaR6W66N1t/fzZ/Nt7G21SZqssXvkpFRUWZBx54wNUxpAHayr2/WteuXY2Hh8dlr0NAQICZMGGCyc7OdpRx1b1+586d5o477jC9evUy3t7extPT04SEhJiYmBjz5JNPmsOHDzfofIyp/2t4qfdBXeOq6dOn18o0atQox/MjR440xhhz8uRJc//995vIyEjj4eFhunTpYsaPH2/Wr1/foJwXO/+fvq8b+prVN68xxhw4cMAkJCQYf39/4+3tbaKiokxGRoaJjY11tP3b3/62ztdcWq7s7GwDmIKCAldHEREREZF6sBjzv396IyIiIiIiIg22ZMkSXn75Zb76StuciYhI69a5c2cWLVrE7373O1dHuag44ggkkLd5u1n628QmbuIm8sknmMZfNaoluPHGG4mOjr7klowiLYGfnx/t27enoKDA1VFE5Cq0YcMGYmNjKSgooHPnzq6OIyIiIiKXoa1ORUREREREREREpNWooortbGckI5utz3DCAbTdqUgzmzt3Lv/3//5fx9cnTpzg7NmzXH/99S5MJSIiIiIiIs1FE99ERERERERERESk1fiMzzjN6Wad+BZGGB548BVa+VWkuaWkpHDw4EFOnjzJww8/DPwwIU5ERERERERaP3dXBxARERERERERERFpLNvYhh9+XE/zrfjkhhs96KEV30Sa2aOPPgrg2JawT58+/PnPfyYxMdHFyURERERERKQ5aOKbiIiIiIiIiIiItBo55DCc4bjh1qz9hhPO13zdrH2KtHWhoaG88sorro4hIiIiIiIiLqKtTkVERERERERERKTV2MxmRjO62fsNJ1xbnYqIiIiIiIiINCNNfBMRERERERER+V8rV67EYrFgsVho3769q+OIiJMOcpCjHCWGmGbvO5xwbXUqIi2axjkiIiIiItLaaOKbiIiIiIiIiMj/mjFjBsYYYmNjaz139uxZevfujdVqdarNhtYTEedtYAM++BBFVLP3Xb3VqcE0e98iIvWhcY6IiIiIiLQ2mvgmIiIiIiIi0gr4+voyatSoVttfS2CMoaqqiqqqqlrPXep6XKqeiDSujWzkF/wCTzybve9wwimnnHzym71vkdZO45ymp3GOiIiIiIhcjdxdHUBERERERERE5Grg5+fHoUOHmq2eiDjHYNjMZv4P/8cl/UcQAcARjhBKqEsyiIg0lMY5IiIiIiJyNdKKbyIiIiIiIiIiInLV+5RPOcEJYohxSf/d6Y4nnnzFVy7pX0RERERERESkrdHENxEREREREZEWqqKigkceeYS+ffvSoUMHOnXqhM1mY/Xq1Vy4cAGApUuXYrFYOHfuHNu2bcNisWCxWHB3//ci75WVlaSkpDBu3DhCQkLw9vZm4MCBJCcn19iWKi0tzVHfYrFw4MABpk2bRlBQkOPYwoULL9tffZ08eZL777+fXr164eXlRY8ePRg7dixvvPEGZWVldZbz9PSkY8eOxMXFsXHjxotmP3LkCNOnTycwMJCgoCCsVmudq5Hs37+fhIQEAgIC8PHxYfTo0WzdurVWuZ+2X15eXq/rf7F6zXFuIm3NBjYQSCCDGeyS/tvRjjDCOMIRl/QvcrXROKd2OY1zNM4REREREREnGREREREREbliixcvNuHh4a6OIa3MnXfeaQICAsy6detMaWmpyc/PNwsWLDCA2bhxY42yPj4+ZuTIkXW2Y7fbDWCeeuopU1RUZAoKCswLL7xg2rVrZxYsWFCrfHx8vAHMmDFjzMaNG825c+fM9u3bjZubmykoKLhsf/WRl5dnIiIiTEhIiLHb7ebMmTMmPz/fLFq0yABm2bJlNcoFBwcbu91uiouLzYEDB8zUqVONxWIxr732Wp3Z4+PjTU5Ojjl79qxZv3698fb2NlFRUTXKfvHFFyYwMNB0797drFu3zpSUlJhPPvnEjB8/3oSHhxsvL6+LXpuysrIaxy93Peqq15TnZowxN910k+nUqZPJzc29aC6RhggKCjLLly93dYxarMZqppgpLs0Qa2LNXeYul2ZoKlFRUeaBBx5wdQxpRTTO0TinoedmjMY50nSys7MN4Ph5ICIiIiItm1Z8ExEREREREWmhsrOzGTBgAOPGjcPb25vg4GCeffZZ+vTp43Rb0dHRPPTQQ3Ts2JHOnTtz7733MnPmTJKTkzlz5kyddR588EGio6Pp0KED//Ef/0FlZSWdO3e+0tMC4KGHHuKrr74iOTkZq9WKn58fwcHB/OEPf2DixIm1yj3//PNYrVb8/f3p06cPf//73wkNDWXevHmcOHGiVvt33nknI0aMwMfHh7FjxzJp0iR27NhBYWGho8zDDz/M6dOnSU5OZty4cfj6+jJw4ED+/Oc/k5eX1yjnWZ9r0BTnBlBVVYUxBmNMk5+LiKtVUMEmNjGRiZcv3ITCCdeKbyL1pHGOxjka54iIiIiIyJXSxDcRERERERG5Knz22Wc1tkGyWCzcc889rfY4wMSJE8nJyWH27Nls377dse3XgQMHiI6Orve1s1qtNbaUqjZo0CDOnz/P3r1766x34403Ov9C1dOqVasAiIuLq/VcZmYmSUlJNcpNmjSpRhkvLy9iY2MpKyvjn//8Z602oqKianwdFhYGwLfffus49v777wMwYcKEGmW7devWoA/dndWU5wawadMmioqKGDFiBNA2v4ek7fgX/+IsZ5nAhMsXbkI96ck3fOPSDHJ1amk/QzXOuTIa52ico3GOiIiIiEjzcHd1ABEREREREZH6uO666y66okNrPf7SSy8xYsQI/vKXvxAbGwvA6NGjmTNnDlOmTKmzTl2Ki4v57//+b1atWsWxY8c4ffp0jedLS0vrrOfj41PvPpxRUVFBcXEx7du3x8/Pr8HlgoODAcjPz6/1XEBAQI2vPT09gR9WB6luu6SkhPbt2+Pr61urfteuXTl48GD9T8pJTXluF9MWv4ek7cgkkwEM4BqucWmOMMI4ylGXZpCrU1v8Ga1xjsY5Gudc2XEREREREdGKbyIiIiIiIiItlsVi4dZbbyUrK4vTp0+TlpaGMYapU6fy3HPP1Sp7MTabjUWLFnHXXXdx8OBBx9ZQy5YtAxr2Ydql+rscLy8vAgICKC8vp6SkpMHlqrfHCgkJaVAGPz8/ysvLOXv2bK3ni4qKnGrP2evRlOcm0hZlkkkctVdWam496UkppZzkpKujiLR4GudonKNxjoiIiIiIXClNfBMRERERERFpoQIDA9m/fz8AHh4ejBs3jrS0NCwWC2vWrKlRtkOHDnz//feOr6+99lpWrFjBhQsX2LZtGyEhIcybN48uXbo4PrwsKytrcLaL9Vdf1Su5rF27ttZzQ4YM4b777qtR7qfnW1FRQXZ2Nt7e3rW28Kqv6u3HqrcCq1ZYWMiBAwecaqsh16Mpz02kLTnCEfazv0VMfAvjhy35tN2pyOVpnKNxjsY5IiIiIiJypTTxTURERERERKQFmzt3Lp988gkVFRV89913LFmyBGMMMTExNcrdcMMNHDx4kKNHj5Kbm8vhw4cZPXo0bm5uREdHk5+fz7PPPkthYSFlZWVs3LiRV155pcG5LtZffT399NNERERw3333sWbNGkpKSjh27Bh33303eXl5jg+Eq8slJSWRkZFBSUkJBw8eZObMmeTl5ZGcnOzYLstZTz31FJ06dSIpKYn169dz9uxZPv/8c2bNmlXntmCX0pDr0ZTnBhATE0NQUBDbt29vcBsiV4NMMvHBh5GMdHUUetITCxZtdypSTxrnaJzTUBrniIiIiIgIAEZERERERESu2OLFi014eLirY0grs3v3bjNnzhzTr18/06FDB9OpUyczfPhw89prr5mqqqoaZffv329Gjx5tfHx8TFhYmHnppZcczxUUFJg5c+aYsLAw4+HhYYKDg83tt99uFi5caAADmKFDh5rc3FzH1z9+1OVS/dVXYWGhSUpKMhEREcbDw8OEhoaaGTNmmIMHD16yXEBAgJkwYYLJzs52lKkr++9//3tjjKl1fNKkSY56Bw4cMAkJCcbf3994e3ubqKgok5GRYWJjYx3lf/vb35pVq1bVaufXv/71Za/H5eo15bmNHj3adOzY0eTk5Dj92ohcSlBQkFm+fLmrYzjYjM3Em3hXx3DoYrqYF82Lro7R6KKioswDDzzg6hjSimicU3c5jXM0zhHXys7ONoApKChwdRQRERERqQeLMcZc4dw5ERERERGRNm/JkiW8/PLLfPXVV66OIiIi0qQ6d+7MokWL+N3vfufqKJzlLF3pyku8xH/yn66OA8BQhjKWsSxmsaujNKobb7yR6OholixZ4uooIiIiTWbDhg3ExsZSUFBA586dXR1HRERERC5DW52KiIiIiIiIiIjIVel93ud7vseK1dVRHHrSU1udioiIiIiIiIg0A018ExERERERERERkavSKlYxmtF0oYuroziEEcY3fOPqGCIiIiIiIiIirZ4mvomIiIiIiIhIo7FYLJd9PPbYY66OKSKtwHnOk0kmCSS4OkoNYYRpxTeRVkrjHBERERERkZbF3dUBRERERERERKT1MMa4OoKItBEb2MApTjGZya6OUkNPenKc41RSibv++VWkVdE4R0REREREpGXRim8iIiIiIiIiIiJy1UkjjRu4gQgiXB2lhjDCuMAF8shzdRQRERERERERkVZNE99ERERERERExClffvklFouFlStXOlVv6dKljm3AevTo0UTpGs/atWvp06cP7u4XX7GpoddCRK5MFVWsZnWL2+YUfljxDdB2pyJXKY1z/k3jHBERERERaek08U1EREREREREmsWCBQswxjBo0CBXR7mkQ4cOMXnyZB566CFOnDjh6jgiUod/8S++5Vtu5mZXR6kllFA88OAbvnF1FBFpRhrniIiIiIiIND9NfBMRERERERER+ZH/+q//4uc//zk7d+7Ez8/P1XFEpA4rWclgBtOf/q6OUosbboQSqhXfRKRF0jhHRERERERak4uvYS0iIiIiIiIi0gb96U9/wtvb29UxROQiKqlkFau4j/tcHeWietJTE99EpEXSOEdERERERFoTrfgmIiIiIiIiIvIj+jBYpGVbz3oKKGA6010d5aLCCNNWpyLSImmcIyIiIiIirYkmvomIiIiIiIiIU372s59hjGHGjBmOYxUVFTzyyCP07duXDh060KlTJ2w2G6tXr+bChQv1aregoIB58+YRHh6Op6cnXbp0YerUqezevbtBZZcuXYrFYsFisdCjRw927NhBbGwsfn5+dOjQgZtuuolt27Y1+rUQkaa1kpX8B/9BBBGujnJRYYRpxTeRq5TGOZe+FiIiIiIiIi2JJr6JiIiIiIiIyBW75557eOGFF3jxxRc5efIk+/bto2/fvsTHx7Nly5bL1s/LyyMqKop33nmH5cuXU1RUxKZNmygqKmLEiBHk5uY6XXbBggUYYxg0aBCnT59m/vz5PPnkk+Tn5/Ovf/2LoqIiYmJi2Lx5c5NdFxFpXOWUk046M2jZkzC04ptI66JxjoiIiIiISMukiW8iIiIiIiKN5OjRo0yYMIGXX36Z48ePuzqOSLPKzs5mwIABjBs3Dm9vb4KDg3n22Wfp06dPveo/9NBDfP311zz33HP88pe/xNfXlwEDBrBy5UqMMdx7770NKlvt3LlzLF++nBEjRuDj48OwYcP429/+xvfff8/8+fMb7TqItFbffPMNL774IrGxsRQVFbksx1rWUkIJiSS6LEN99KQnhRRSSqmrozSqP/3pT9xxxx2kp6dTVlbm6jgizUbjHJHWraqqiu3bt7Nw4ULmzp3r6jgiIiIi4gSLMca4OoSIiIiIiMjV7vTp02RkZJCWlsb7779PaWkpUVFRJCQkkJCQQL9+/VwdUaRJ3X333bz88svcdddd3HHHHURFReHm5lZn2cGDB1NYWMixY8ccxwIDAykpKeHUqVP4+/vXKD906FA+/vhjjh49So8ePZwqW93fl19+ydmzZ2tl6d69O99++y3ffvstoaGhtZ7v0aMH+fn5VFZWOn1NRK52n3zyCenp6aSlpfHxxx/j7+9PXFwcCQkJTJo0CT8/v2bPFE885zhHFlnN3rczdrGLG7iBAxygD/WbGNPSffHFF7z33nukpaXx4Ycf0r59eyZMmEB8fDxWq5WgoCBXRxRpMhrniLQ+33//PRs2bCAtLY3Vq1eTl5dHZGQk8fHxJCQkMHr0aCwWi6tjioiIiMhlaMU3ERERERGRRhAYGMisWbN49913KSwsZN26dQwfPpwXX3yR/8/evUZXXR54+79CiFFAQY6RoCQoVOJ6nmppawSsCAgJ7l/CaVMPgFYrdtqZsdP+bWfaTh9rbTu2th3bVR1ppyp4ALZgyG8XIiGVqQjOGlNq23BoFRQDIqAkoDSUJPxfTGWh4oHjnexcH1bfkECuYN3suL+576KiIgYNGsQtt9zC8uXLfWFJGelnP/sZc+bMYePGjYwZM4YzzjiDkpISHn/88Q/8tfv27aOxsZHW1la6d+9OVlbW2/7329/+Fvjf0cWRvO+hevTocdiP3bdvXwC2b99+LJ++lBFaW1upra3ltttuY+jQoXz0ox/lJz/5CRdccAGVlZVs376defPmcdVVVwUZvW1nO0tZymf4zEn/2EfqHM4ByKjrTgcPHsxXv/pVVq9ezauvvsq9997L/v37ufnmm+nXrx8jR47kzjvv5E9/+lPoVOm483mOlBn27t1LHMfMnDmTvn37UlpaylNPPcXMmTN56qmneP755/nRj37Epz71KUdvkiRJ7YQnvkmSJEnSCdTa2sqaNWuI45j58+ezfv16evfuTWlpKclkknHjxpGbmxs6Uzqu9u/fz4oVK7jrrrtYtmwZP/zhD/nSl7508O2HOwnlzDPP5I033uAvf/kLnTt3ft/f/0je962Pt2HDBvbu3fuuF7A8CUUdXVNTEytXriSOY1Kp1MHTThKJBMlkkuHDh9OpU9v43tkf8kNu53Ze4RW60CV0zgfqRjd+yk/bxVDvWOzdu5eamhpSqRSVlZU0NjZSVFREFEUkEglGjBjheEAZxec5UvuyY8cOli5dSiqVorq6mubmZoqLi4miiMmTJzN48ODQiZIkSToGbeO/WkmSJElShurUqRPDhg3jtttuY926dbzwwgt84xvfYOPGjZSXl9OzZ0+iKGLOnDk0NDSEzpWOWo8ePVi/fj0AOTk5XHHFFVRUVJCVlcWvfvWrD/z1kydPprm5maeffvpdb7vzzjs555xzDr4oeyTv+5ampib+53/+520/94c//IGtW7fy0Y9+9LAvBkuZateuXaRSqYOnnVxxxRUsX76cWbNm8eyzz/LCCy9w9913M3LkyDYzegOYwxyu4qp2MXoDGMCAjDrx7b106dLl4HOZ1157jaeeeoqxY8fy0EMPcemll1JYWMjNN99MHMfs378/dK50VHyeI7UvGzduPPhcJi8vj8997nMA/OQnP2HLli2sXLmSr371q47eJEmSMkDb+S9XkiRJktQBvHXl6cqVK3nppZf48Y9/DMBNN91E7969GTlyJHfffffbToiQ2ovPfe5z/P73v2ffvn1s376d73//+xw4cIDRo0d/4K/93ve+x7nnnssNN9zA0qVLaWxs5PXXX+e+++7j9ttv56677jp46smRvO9bunfvzte+9jVWr17Nm2++ybPPPsv06dM55ZRTuPvuu0/In4fUlmzevJnZs2cTRRF5eXlcffXVbNy4kW9/+9vU19dTV1fHbbfdxrBhw0KnHtb/8D/8nt+3q9PTzuEcXubl0BknVXZ29tuey/zxj3/k+uuvp7a2lrKyMvLy8pg5cyapVIo33ngjdK50RHyeI7Vtbz2XueCCCzj33HP59re/zaBBg5g3bx7bt28njmNmzZpFv379QqdKkiTpOPKqU0mSJElqA3bt2sXy5cuJ45jFixeze/duioqKSCaTRFHUZocI0luee+457r33Xn7zm9/w0ksvceqppzJkyBBuvPFGbrzxRrKysrjrrru49dZb3/brvv71r3PHHXcA8Prrr/Od73yHiooKXn75ZXr06MFFF13ErbfeytixY9/2647kfd+6cqy6upp/+qd/YtWqVTQ3N/PJT36S73znO4wYMeJt759Op4mi6LCf589//nM++9nPHusfl3RS1NXVkU6nieOYVatWcdpppzF69GiSySTl5eV07949dOKH9gW+wHKWs571ZNE+rs28kRupp54neCJ0SpuwcePGg1fqrl69mtzcXMaMGUMURZSXlztEUJvm8xyp7WlpaWH16tWkUikWLlzIli1bGDhwIOXl5URRxGWXXUZOTk7oTEmSJJ1gDt8kSZIkqY1pampi5cqVB18cfuWVVygsLCSKIqIoYtSoUe865UHSe3vrBWFPUlSma21tZc2aNcRxzLx589iwYQO9e/emtLSUZDLJuHHjyM3NDZ15xJpooj/9+erffrQXt3Eb85nPOtaFTmlzdu7cyZIlS0ilUlRXV9Pc3ExxcTFRFDFp0iSGDBkSOlFqN3yeo45k79691NTUkEqlqKyspLGxkaKiIqIoIpFIMGLECLKy2sdAXpIkSceHwzdJkiRJasMOHTHMnz+f9evXZ8SIQTqZfEFYmexwY+lBgwaRSCRIJpMMHz6cTp06hc48Jg/yIDdxE5vZTB55oXM+tF/yS/6Bf+BN3gyd0qYdOmKI45iGhgZHDNIR8HmOMt2OHTtYunTpYcfSkydPZvDgwaETJUmSFJDDN0mSJElqRw69Juyd19aVlZXRo0eP0IlSm+MLwso0h16PXVFRwZ49ezL6euyLuZhCCpnHvNApR6SaasYxjtd4jZ70DJ3TLrzXtXXjx48nkUhQUlLitXXSO/g8R5nI67ElSZL0YTl8kyRJkqR26uWXX2bp0qXEccyyZctoaWmhuLiYZDLJlClTGDBgQOhEKai77rqLW2+99W0/9/Wvf5077rgjUJF09DZv3kxVVdVhH/OnTp1Kfn5+6Idx1LkAACAASURBVMQT4nf8jou4iBWs4DIuC51zRDawgfM5nzWs4UIuDJ3TLtXV1ZFKpUin09TW1tKzZ0+uvPJKoiiitLSUbt26hU6UgvF5jjLNW4/5qVSKtWvX0qtXLyZMmOBjviRJkt6XwzdJkiRJygCHnv6zePFidu/endGn/0hSR1BXV0c6nSaO43ed8lleXk737t1DJ55wn+WzrGIVddSRRfu67nIve+lKVyqpJCIKndPuefqPJGWWw53yWVBQQFlZGVEUcdlll3nKpyRJkj6QwzdJkiRJyjBNTU2sXLny4IvDr7zyCoWFhURRRBRFjBo1is6dO4fOlCS9Q2trK2vWrCGOY+bNm8eGDRvo3bs3paWlJJNJxo0bR25ubujMk6aBBgYwgDu5ky/whdA5R6U3vfkW32q3/W3Vzp07WbJkCalUiurqapqbmykuLiaKIiZNmsSQIUNCJ0qSDmPv3r3U1NSQSqWorKyksbGRoqIioigikUgwYsQIsrLa19BdkiRJYTl8kyRJkqQMduiIYv78+axfv75Djygkqa053Fh50KBBJBIJkskkw4cPp1OnTqEzg/h3/p1/5V+pp57utM/T7T7GxxjHOP6NfwudkrEOHVHEcUxDQ4MjCklqQ3bs2MHSpUsPO1aePHkygwcPDp0oSZKkdszhmyRJkiR1IIdeE/bOa/PKysro0aNH6ERJyniHXk9dUVHBnj17vJ76HQ5wgKEMZRSj+A/+I3TOUSunnG5042EeDp3SIRx6bd6iRYuor69n4MCBjB8/nkQiQUlJidfmSdJJ4PXUkiRJOlkcvkmSJElSB7V9+3aqqqpIpVIsW7aMlpYWiouLSSaTTJkyhQEDBoROlKSMsXnzZqqqqojj+F2PuVOnTiU/Pz90YpsSE1NOOX/gD1zABaFzjto/8A/8jt/xFE+FTumQ6urqSKVSpNNpamtr6dmzJ1deeSVRFFFaWkq3bt1CJ0pSxnjrMTeVSrF27Vp69erFhAkTfMyVJEnSCeXwTZIkSZL0ttOHFi9ezO7duz19SJKOUV1dHel0mjiO33XKZnl5Od27t8/rO0+Gy7iMbnTjV/wqdMox+T7f5x7u4UVeDJ3S4b11+lA6nWbFihXk5OQcPH2orKyMvLy80ImS1K4cesrmwoUL2bJlCwUFBZSVlRFFEZdddpmnbEqSJOmEc/gmSZIkSXqbpqYmVq5cefBqmldeeYXCwkKiKCKKIkaNGkXnzp1DZ0pSm9Pa2sqaNWuI45h58+axYcMGevfuTWlpKclkknHjxpGbmxs6s817lmf5BJ+ghhpGMzp0zjF5lEeZyUyaaCKb7NA5+pudO3eyZMkSUqkU1dXVNDc3U1xcTBRFTJo0iSFDhoROlKQ2ae/evdTU1JBKpaisrKSxsZGioiKiKCKRSDBixAiysrJCZ0qSJKkDcfgmSZIkSXpPh4445s+fz/r16x1xSNIhDjcWHjRoEIlEgmQyyfDhw+nUqVPozHblKq5iPetZwxqyaN8vnq9kJZdyKS/zMgPwCvG26NARRxzHNDQ0OOKQpEPs2LGDpUuXHnYsPHnyZAYPHhw6UZIkSR2YwzdJkiRJ0of21jVhqVTqXdf2lZWV0aNHj9CJknTCHXo9dEVFBXv27PF66OPkRV5kMIN5kAe5hmtC5xyzzWxmIANZxSou4ZLQOfoAh17bt2jRIurr6xk4cCDjx48nkUhQUlLitX2SOoRDv+5bvXo1ubm5B6+HLi8vp1+/fqETJUmSJMDhmyRJkiTpKG3fvp2qqipSqRTLli2jpaWF4uJikskkU6ZMYcAAT7aRlDk2b95MVVUVcRy/6zFv6tSp5Ofnh07MCF/kiyxkIRvZSA7tf2DUTDOncRoP8RCf5tOhc3SE6urqSKVSpNNpamtr6dmzJ1deeSVRFFFSUsLpp58eOlGSjpu3HvNSqRRr166lV69eTJgwgSiKKC0tpVu3bqETJUmSpHdx+CZJkiRJOmaHnn60ePFidu/e7elHktq9uro60uk0cRy/65TL8vJyunfvHjoxo7zGaxRSyG3cxpf4Uuic4+ZszuYWbuH/4/8LnaJjsGnTJiorK0mn06xYsYKcnJyDpx+VlZWRl5cXOlGSjsihp1wuXLiQLVu2UFBQQFlZGVEUcdlll3nKpSRJkto8h2+SJEmSpOOqqamJlStXHrwa55VXXqGwsJAoioiiiFGjRtG5c+fQmZL0Lq2traxZs4Y4jpk3bx4bNmygd+/elJaWkkwmGTduHLm5uaEzM9a/8q/cy71sYhOnkzknaY1gBB/n49zN3aFTdJzs3LmTJUuWkEqlqK6uprm5meLiYqIoYtKkSQwZMiR0oiQd1t69e6mpqSGVSlFZWUljY+PbvmHpYx/7GFlZWaEzJUmSpA/N4ZskSZIk6YQ5dEQyf/581q9ff3BEEkUREyZMoGvXrqEzJXVghxvrDho0iEQiQTKZZPjw4XTq1Cl0ZsZrpJECCriVW/kaXwudc1xdxVXsYx+P83joFJ0Ah45I4jimoaGBoqIioigikUgwYsQIRySSgtqxYwdLly497Fh38uTJDB48OHSiJEmSdNQcvkmSJEmSTpqNGzceHJe889rAsrIyevToETpRUgdw6PXMFRUV7Nmz5+BpJ9OmTaOoqCh0YodzG7dxN3eziU30ILP+LvgKX+HX/JpneTZ0ik6wQ68NXLRoEfX19QwcOJDx48eTSCQoKSnx2kBJJ8WhX3etXr2a3Nzcg9czl5eX069fv9CJkiRJ0nHh8E2SJEmSFMT27dupqqoilUqxbNkyWlpaKC4uJplMMmXKFAYMGBA6UVIG2bx5M1VVVcRxzBNPPEFra+vBx5ypU6eSn58fOrHD2s1uCijgi3yRb/LN0DnH3U/5Kd/m22xne+gUnWR1dXWkUinS6TS1tbX07NmTMWPGkEgkmDRpEqefnjlX+koK763HnFQqxdq1a+nVqxcTJkwgiiJKS0vp1q1b6ERJkiTpuHP4JkmSJEkK7tDTlxYvXszu3bsPnr4URRHDhg0LnSipHaqrqyOdThPH8btOmSwvL6d79+6hEwXcwR3cxV1sYhNncmbonOOuggomM5k3eZPTOC10jgLZtGkTlZWVpNNpVqxYQU5OzsHTl8rKysjLywudKKmdaW5u5plnniGVSrFw4UK2bNlCQUEBZWVlRFHEqFGj6Ny5c+hMSZIk6YRy+CZJkiRJalOamppYuXIlcRzz2GOPsXXrVgoLC4miyBdwJL2v1tZW1qxZQxzHzJs3jw0bNtCnTx9KSkpIJpOMGzeO3Nzc0Jk6xB72UEghn+fz3M7toXNOiN/yW4YxjA1sYAhDQueoDdi5cydLliwhlUpRXV1Nc3MzxcXFRFHEpEmTGDLE/59IOry9e/dSU1NDKpWisrKSxsbGt33D0Mc+9jGysrJCZ0qSJEknjcM3SZIkSVKbdeiIZcGCBaxbt47evXtTWlpKFEVMmDCBrl27hs6UFNChY9kFCxawbds2Bg0aRCKRIJlMMnz4cDp16hQ6U+/hdm7nR/yIjWykJz1D55wQO9hBX/qynOWMYUzoHLUxh45Y4jimoaGBoqIioigikUgwYsQIRyxSB7djxw6WLl162LHs5MmTGTx4cOhESZIkKRiHb5IkSZKkdmPjxo3EcUwqlXrXtYVlZWX06NEjdKKkk+DQ65ErKirYs2fPwdNOpk2bRlFRUehEfQg72MF5nMdX+Apf5+uhc06YAxygK125h3u4nutD56gNa2lpYfXq1aRSKRYtWkR9fT0DBw5k/PjxJBIJSkpKyMnJCZ0p6SQ49Oue1atXk5ube/B65IkTJ9K3b9/QiZIkSVKb4PBNkiRJktQubd++naqqKlKpFMuWLaOlpYXi4mKSySRTpkxhwIABoRMlHUebN2+mqqqKOI554oknaG1tPfjv/NSpU8nPzw+dqCP0j/wjj/EYf+bPdCWzT+8czGCu4zq+wTdCp6gdqaurI5VKkU6nqa2tpWfPnowZM4ZEIsGkSZM4/fTTQydKOk4OPek6lUqxdu1aevXqxYQJE4iiiNLSUrp16xY6U5IkSWpzHL5JkiRJktq9hoYGqqurieOYxYsXs3v37oOnP0VRxLBhw0InSjoKdXV1pNNp4jh+1ymP5eXldO/ePXSijtKLvMj5nM/d3M3N3Bw654QbxSiGMpR7uTd0itqpTZs2UVlZSTqdZsWKFeTk5Bw8/amsrIy8vLzQiZKOUHNzM8888wypVIqFCxeyZcsWCgoKKCsrI4oiRo0aRefOnUNnSpIkSW2awzdJkiRJUkZpampi5cqVxHHMY489xtatWyksLCSKIl9Aktq4Q087mTdvHhs2bKBPnz6UlJSQTCYZN24cubm5oTN1HFzLtTzLs/yRP5JD5l/dOJ3pNNJITBw6RRlg586dLFmyhFQqRXV1Nc3NzRQXFxNFEZMmTWLIkCGhEyW9h71791JTU0MqlaKyspLGxka/YUeSJEk6Bg7fJEmSJEkZ69ARzYIFC1i3bh29e/emtLSUKIqYMGECXbtm9vV6Ult36Fh1wYIFbNu2jUGDBpFIJEgmkwwfPpxOnTqFztRx9Ht+z0VcxHzmM5WpoXNOiq/yVaqp5rf8NnSKMsyhI5o4jmloaKCoqIgoikgkEowYMYKsrKzQmVKHtmPHDpYuXXrYserkyZMZPHhw6ERJkiSp3XL4JkmSJEnqMDZu3Egcx6RSqXddm1hWVkaPHj1CJ0odwq5du1i+fDlxHFNRUcGePXsOnnYybdo0ioqKQifqBBrPeHaxi//mv8miYwxyfsJP+A7f4VVeDZ2iDNbS0sLq1atJpVIsWrSI+vp6Bg4cyPjx40kkEpSUlJCTk/knLEptwaFfd6xevZrc3NyD1xNPnDiRvn37hk6UJEmSMoLDN0mSJElSh7R9+3aqqqpIpVIsW7aMlpYWiouLSSaTTJkyhQEDBoROlDLK5s2bqaqqIo5jnnjiCVpbWw/+Ozd16lTy8/NDJ+okiIkpp5wVrOBTfCp0zkmzkIUkSfIX/kIuXterk6Ouro5UKkU6naa2tpaePXsyZswYEokEkyZN4vTTTw+dKGWMQ0+aTqVSrF27ll69ejFhwgSiKKK0tJRu3bqFzpQkSZIyjsM3SZIkSVKH19DQQHV1NXEcs3jxYnbv3n3w9Kkoihg2bFjoRKldqqurI51OE8fxu05ZLC8vp3v37qETdRL9lb/yf/g/DGMYj/BI6JyT6hme4RIuYRObKKAgdI46oE2bNlFZWUk6nWbFihXk5OQcPH2qrKyMvLy80IlSu9Pc3MwzzzxDKpVi4cKFbNmyhYKCAsrKyoiiiFGjRtG5c+fQmZIkSVJGc/gmSZIkSdIhmpqaWLlyJXEc89hjj7F161YKCwuJosgXsKQP0NrayqpVq0in01RUVLBhwwb69OlDSUkJyWSScePGkZvraVcd1Xf5LndwB+tYx0AGhs45qeqp52zOZiUrGcGI0Dnq4Hbu3MmSJUtIpVJUV1fT3NxMcXExURQxadIkhgwZEjpRarP27t1LTU0NqVSKyspKGhsb/YYZSZIkKSCHb5IkSZIkvYdDryxasGAB69ato3fv3pSWlhJFERMmTKBr166hM6WgDh2LLliwgG3btjFo0CASiQTJZJLhw4fTqVOn0JkKbAtbOJ/z+Spf5Rt8I3TOSddMM6dyKo/wCNOYFjpHOujQEU8cxzQ0NFBUVEQURSQSCUaMGEFWVlboTCmoHTt2sHTp0sOORadMmcJ5550XOlGSJEnqsBy+SZIkSZL0IW3cuJE4jkmlUu+6trGsrIwePXqETpROil27drF8+XLiOKaiooI9e/YcPO1k2rRpFBUVhU5UGzOd6axiFWtZy6mcGjoniP7051Zu5Z/4p9Ap0mG1tLSwevVqUqkUixYtor6+noEDBzJ+/HgSiQQlJSXk5OSEzpROikOf969evZrc3NyD1wNPnDiRvn37hk6UJEmShMM3SZIkSZKOSn19PZWVlVRUVLBixQoARo0aRUlJCd26dQsbJ50gu3fvZunSpfzmN78hOzubyy+/nIkTJ1JWVsZZZ50VOk9t1NM8zaVcymM8xmQmh84J5hN8gsu4jLu4K3SK9IEOHDjAs88+y+OPP87ixYtZu3YtvXr1IooiLr74Yk/yVMZ64YUXqKio4E9/+hN9+/alrKyM8vJyxo4dy6mndszhtiRJktSWOXyTJEmSJOkYNTQ08Ktf/YrFixfzX//1X+zfvz90kv7mr1f9lb+W/ZVu1zhGPB5OOeWUg2O30tJSzjjjjNBJauP2s59hDCOPPJaxLHROUJOYxKmcyqM8GjpFOmJ//vOfD47g1q1bFzqnzWr6chM5cQ7Zf8oOnaKj1KdPn4Onul1yySVkZ/vPUpIkSWrLHL5JkiRJkqSM9Z/8J7dwC2/wRugUqUP6Lt/lDu7g9/ye8zgvdE5Qf8/f8xzP8RRPhU6RdAK8xEsUUEA11YxlbOgcSZIkSeoQPI9ckiRJkiRlrEIKeZM32cGO0ClSh/M8z3MHd/BNvtnhR28A+eSzhS2hMySdIJVU0o1uXMqloVMkSZIkqcNw+CZJkiRJkjJWAQUAvMiLQTukjujv+DvO4zy+zJdDp7QJ+eSzla0cwAs4pEwUE1NKKbnkhk6RJEmSpA7D4ZskSZIkScpYZ3M22WSziU2hU6QO5Rf8gid5kl/wC3LICZ3TJuSTzz728RqvhU6RdJy9wRv8ht8QEYVOkSRJkqQOxeGbJEmSJEnKWDnkMIABnvgmnUT11HMrt/Jlvswn+WTonDYjn3zgf/98JGWWKqpopplSSkOnSJIkSVKH4vBNkiRJkiRltAIKHL5JJ8kBDvBZPkseedzGbaFz2pQBDABgC1sCl0g63mJiiimmN71Dp0iSJElSh+LwTZIkSZIkZbRCCr3qVDpJ7uEeaqjhQR7kNE4LndOmdKMbZ3CGwzcpw7TSShVVXnMqSZIkSQE4fJMkSZIkSRnNE9+kk+NP/Il/5p/5Cl/xitP3kE++wzcpw6xmNdvZ7vBNkiRJkgJw+CZJkiRJkjLaW8O3AxwInSJlrH3s4yqu4nzO5//x/0LntFkO36TMkybNIAZRRFHoFEmSJEnqcDqHDpAkSZIkSTqRCimkiSa2sY2zOCt0jpSRvsyX+TN/ppZaTuGU0Dlt1gAGOHyTMkxM7GlvkiRJkhSIJ75JkiRJkqSMVkABgNedSidImjT3cA/3cR9DGBI6p03LJ5966kNnSDpOXuIl6qhz+CZJkiRJgTh8kyRJkiRJGS2ffE7hFDaxKXSKlHFe5mWu53pu4iau4ZrQOW2eV51KmWUxizmDM7iUS0OnSJIkSVKH5PBNkiRJkiRltGyyOZuzPfFNOs6aaeZqriaPPH7Mj0PntAv55LOLXbzJm6FTJB0HMTEllHjFsyRJkiQF4vBNkiRJkiRlvAIKHL5Jx9k3+Aa/43csYAFd6BI6p13IJx+AV3glcImkY7Wb3fyG33jNqSRJkiQF5PBNkiRJkiRlvEIKvepUOo6e5El+wA/4KT+liKLQOe1Gf/oDsJWtgUskHasneIIWWiihJHSKJEmSJHVYDt8kSZIkSVLG88Q36fh5mZe5iqu4mqv5DJ8JndOu9KUv2WR74puUAWJihjOc3vQOnSJJkiRJHZbDN0mSJEmSlPEKKOAlXqKFltApUru2l71MZCJ96cu93Bs6p93JJpu+9PXEN6mda6GFpSz1mlNJkiRJCszhmyRJkiRJyniFFLKf/Y5NpGNwgAPcyI28yIs8zuOczumhk9ql/vT3xDepnVvNanay0+GbJEmSJAXm8E2SJEmSJGW8AgoAvO5UOgbf4lssZCGP8RjncV7onHbL4ZvU/sXEnMu5nM/5oVMkSZIkqUNz+CZJkiRJkjLeWZzFqZzKJjaFTpHapUUs4nZu5yf8hMu5PHROu3YWZ3n6pNTOpUlTRlnoDEmSJEnq8By+SZIkSZKkjJdFFgMZ6Ilv0lH4Hb9jJjP5Al/gc3wudE675/BNat82spG1rCVBInSKJEmSJHV4Dt8kSZIkSVKHUECBwzfpCL3Kq5RRxjCG8UN+GDonI3jVqdS+xcR0pzsjGRk6RZIkSZI6PIdvkiRJkiSpQyik0KtOpSPwV/7KNKbRmc4sZCGncEropIxwFmfRSCNv8mboFElHISamhBIfEyVJkiSpDXD4JkmSJEmSOgRPfJM+vFZauZ7reY7n+BW/oje9QydljP70B/DUN6kd2s1unuIpIqLQKZIkSZIkHL5JkiRJkqQOooACXuZl9rM/dIrU5n2JL7GIRSxkIUMZGjono5zFWYDDN6k9qqKKFloooSR0iiRJkiQJh2+SJEmSJKmDKKSQFlqopz50itSmfYfv8FN+yhzmMIYxoXMyTj/6kU02W9kaOkXSEYqJGcEIetErdIokSZIkCYdvkiRJkiSpgyikEMDrTqX3MYc5/Cv/yo/4EdOYFjonI2WTTV/6OnyT2pkWWqiiymtOJUmSJKkNcfgmSZIkSZI6hD70oRvd2MSm0ClSmxQTcyM38k2+yS3cEjono/Wnv1edSu3MKlaxk50O3yRJkiSpDXH4JkmSJEmSOoyBDPTEN+kwVrOaq7iKG7mR27gtdE7GO4uzHL5J7UxMzLmcy0f4SOgUSZIkSdLfOHyTJEmSJEkdRiGFDt+kd/gDf+BKrmQc4/gZPwud0yH0p79XnUrtTExMOeWhMyRJkiRJh3D4JkmSJEmSOowCCrzqVDrERjYynvFcxEXMYx7ZZIdO6hA88U1qX17gBdaz3mtOJUmSJKmNcfgmSZIkSZI6jAIKPPFN+puNbORyLieffB7ncXLJDZ3UYXjim9S+VFJJd7ozghGhUyRJkiRJh+gcOkCSJEmSJOlkKaSQrWxlE5vYwhY2sYkXeZEGGvghPwydJ500L/ESYxhDL3pRRRVncEbopA7lLM6ikUbe5E260jV0jqQPkCbNBCaQQ07oFEmSJEnSIRy+SZIkSZKkjLSf/TzGY7z4tx/P8zwb2EAWWQxiEACd6MQBDjCa0YFrpZPnJV5iFKM4kzNZznJ60jN0UofTn/4AvMIrnMd5gWskvZ9GGlnJSh7ggdApkiRJkqR3cPgmSZIkSZIyUg453MM9PM3TdKYz+9n/rvdppZVTOIViigMUSiefo7e24SzOAhy+Se1BFVW00MI4xoVOkSRJkiS9Q6fQAZIkSZIkSSfKbdzGAQ4cdvT2lr/yV4dv6hAcvbUd/ehHNtlsZWvoFEkfICbmUi6lF71Cp0iSJEmS3sHhmyRJkiRJylhjGMNwhtP5Aw69/wSfOElFUhgv8qKjtzYkm2z60pdXeCV0iqT30UILVVQREYVOkSRJkiQdhsM3SZIkSZKU0W7ndpppfs+355NPP/qdxCLp5Hqe5/kUn6IPffg1v3b01kb0p7/DN6mNe5qneY3XSJAInSJJkiRJOgyHb5IkSZIkKaO936lv2WQzghEBqqST4/f8nk/xKfLIYxnL6EGP0En6m7M4y6tOpTYuJuY8zmMIQ0KnSJIkSZIOw+GbJEmSJEnKeN/iW4c99a0TnbiYiwMUSSfef/PfjGY0H+EjLGe5o7c25izO8sQ3qY2LiSmnPHSGJEmSJOk9OHyTJEmSJEkZbyxjD3vq2372O3xTRkqTZjSjGclIlrCEMzgjdJLeIY88XuXV0BmS3sMLvMAGNhARhU6RJEmSJL0Hh2+SJEmSJKlDONypb9lkcxEXBSqSToyHeIjJTCZJksd4jNM4LXSSDqMf/djGttAZkt7DYhZzJmd6JbokSZIktWEO3yRJkiRJUocwlrEUU/y2U9+GMpQudAlYJR1fP+EnXMd1fIkvcT/3v+uUQ7UdeeTxGq+xn/2hUyQdRpo0pZT6OCpJkiRJbZjDN0mSJEmS1GHczu0HT33LIYeRjAxcJB0fBzjAbdzGF/ki//a3H1lkhc7S++hHPw5wgO1sD50i6R0aaWQlK73mVJIkSZLaOIdvkiRJkiSpw7iCK7iYi8kmm1Za+SSfDJ0kHbNmmrmJm/gu3+VBHuRWbg2dpA8hjzwArzuV2qClLOUABxjP+NApkiRJkqT34fBNkiRJkiR1KN/m27T87cfFXBw6RzomjTSSIMGjPMrjPM4MZoRO0of01vDtVV4NXCLpnWJiLuVSzuTM0CmSJEmSpPfROXSAJEmSJEn68LZt28ajjz7Kq686lDgWZ33hLHb228mD/+9Bsg54HWRbU1xczJVXXklOTk7olDatnnoiIl7lVVawgk/widBJOgLd6EZXunrim9TGtNDCEzzB1/l66BRJkiRJ0gdw+CZJkiRJUhu3f/9+fvWrX/HLX/6SpUuXcvrppzNo0KDQWe1atze68cbMN6iprgmdonfYv38/P/jBD+jduzfTp0/nhhtu4IILLgid1eY8wzNMZCL96MczPMM5nBM6SUchjzyHb1Ibs5KVvMZrJEiETpEkSZIkfQCHb5IkSZIktVHr1q3jwQcf5IEHHmDHjh1ccskl/OxnP2P69Ol06dIldF67FxMTPRuFztBhbNmyhYceeoif//zn/OhHP2LYsGHMmDGD6dOn06tXr9B5waVIcR3XcRmXMZ/5nMEZoZN0lPrRz6tOpTYmJuZ8zmcwg0OnSJIkSZI+QNaBAwcOhI6QJEmSJEn/q7Gxkfnz5zNnzhyefvppzj77bK655hpuvvlmCgsLQ+dJJ11tbS2zZ8/mkUceYf/+/ZSVlTFjxgwmTJhAdnZ26LyT6gAH+D7f51/4F/6Bf+BH/IhsOtafQaaZwhRyyGEe80KnSPqbj/ARyinn+3w/dIokSZIk6QM4fJMkSZIkKbDW1lZWrVrF3Llzefjhh2lpaSGKImbNmsWYMWPIysoKnSgFt3v3bioqKpg7dy41NTX079+f6dOnc9NNN3HuueeGzjvh9rGPz/JZ5jGPf+ff+QJfCJ2k4+ALfIE66ljBbZQeVAAAIABJREFUitApkoDneZ7BDOY3/IZLuTR0jiRJkiTpAzh8kyRJkiQpkPr6eh5++GFmz57Nxo0bD17nOGPGDHr27Bk6T2qzNmzYwKOPPsr9999PfX09l1xyCTNnzuTaa6+la9euofOOu61sZQpT2MAGUqQYw5jQSTpObud2HuER1rM+dIok4If8kO/yXV7lVTrTOXSOJEmSJOkDOHyTJEmSJOkkampqIo5j5syZw9KlS+nTpw/Tpk3jhhtu4KMf/WjoPKldaWlp4cknn2T27NksXryYU089lfLycmbOnMnYsWND5x0XT/EU05hGd7qzmMV8hI+ETtJxNJvZfJWvsotdoVMkAaMYxdmczVzmhk6RJEmSJH0InUIHSJIkSZLUEdTW1nLLLbcwYMAArr76apqamnj00UfZvHkzd999t6M36ShkZ2czduxYFixYwLZt2/jBD37AH/7wB6644gqGDh3KnXfeyauvvho68z09zdO8yZvv+fbZzGYMY/gEn+AZnnH0loH60Y8GGvgLfwmdInV4DTSwilVERKFTJEmSJEkfksM3SZIkSZJOkNdff53Zs2dz4YUX8vGPf5zq6mpuvfVWtmzZQnV1NclkkpycnNCZUkY488wzmTVrFmvWrOHZZ59l3Lhx/OAHPyA/P58rrriCVCrF/v37Q2cetJOdTGISf8/fv+ttTTTxGT7D5/k8X+NrVFBBD3oEqNSJlkceANvZHrhE0hKWADCOcYFLJEmSJEkflledSpIkSZJ0HB169WJFRQVdunTh05/+NDNmzGDkyJGh86QOZd++fVRWVh68Wrh79+5MnTqVz3/+88FPWZzMZCqppIUW5jGPT/NpAJ7neaYwhS1s4REecYCR4V7iJQoo4Bme4WIuDp0jdWjXcA2v8io11IROkSRJkiR9SA7fJEmSJEk6DtavX88DDzzAAw88wI4dO7jkkkuYOXMm1157LV27dg2dJ3V4W7Zs4aGHHuLnP/85L7zwAsOGDWPGjBlMnz6dXr16ndSWB3iAG7iBAxwgiyy60IU/8AfWsY7pTKeAAhaykEIKT2qXTr4mmjiN06iggnLKQ+dIHVYzzfSlL9/km3yRL4bOkSRJkiR9SA7fJEmSJEk6Srt376aiooK5c+dSU1NDfn4+1157LbNmzWLQoEGh8yQdRmtrK6tWrWLu3Lk8/PDDtLS0EEURM2bMYMKECWRnZ5/Qj19PPUUUsYc9B38uhxz60Y+tbOU6ruMe7uFUTj2hHWo7zuRM7uROZjErdIrUYa1gBZdzOX/iTwxmcOgcSZIkSdKH1Cl0gCRJkiRJ7UlraysrV67k5ptvpn///tx8882ceeaZLF68mBdffJF/+7d/c/QmtWGdOnVi5MiR3HfffWzdupX77ruPXbt2UV5eTkFBAf/8z//Mxo0bT8jHbqWVq7maJpre9vP72c9WtlJCCb/kl47eOph+9GMb20JnSB1aTMxQhjp6kyRJkqR2xhPfJEmSJEn6ENrSNYmSjr+TcV3x9/k+/8K/0ErrYd+eRRbLWc5oRh+Xj6f2YRSjuIAL+Bk/C50idVgf4SNMZCJ3cmfoFEmSJEnSEXD4JkmSJEnSe9i3bx+VlZXMmTOHpUuX0r17d6ZOncrnP/95PvrRj4bOk3QCtLS08OSTTzJ79mwqKiro0qULn/70p5kxYwYjR4486t+3jjou4iL2s/893yebbHrRi7WspRcOajuKq7iK/exnIQtDp0gd0gY2cD7n8xRPMZKjf5yXJEmSJJ18Dt8k6STYsGEDb7zxRugM6YQpKCjwpBtJUkapra1lzpw5PPzwwzQ0NHD55Zcza9YsJk6cSE5OTug8SSfJ66+/zmOPPcY999zDc889x9ChQ7nuuuu4/vrr6dev34f+ffaxj4u4iD/zZ5ppft/3zSKLiIjFLD7WfLUTt3ALtdSykpWhU6QO6S7u4nt8j1d5lc50Dp0jSZIkSToCDt8k6QRoaWnh6aefpqKigoqKCjZt2hQ6STqhsrOzufTSS5k4cSLl5eUUFBSETpIk6Yjt2rWLVCrFvffey+9+9zvOP/98rr/++iMeuEjKTMcyiP0KX+HH/Ph9R2855NBMM53pzOVczi/4BWdz9vH+NNQGfZfv8kt+yfM8HzpF6pAu4zIGMpA5zAmdIkmSJEk6Qg7fJOk4+ctf/kJ1dTUVFRXEcczOnTs5//zzmThxImVlZb5Yqox14MABamtrqaioYOnSpTQ0NHDhhRceHMFdeOGFoRMlSXpPh15puHjxYk499VTKy8uZOXMmY8eODZ0nqQ1qamoijuODVyD36dOHadOmccMNNxz2CuSVrOQyLqOV1ne9LYcc9rOfHvQgQYIyyhjPeM7gjJPxqaiN+CW/5B/5R97Ak+Klk+11Xqcf/XiER0iSDJ0jSZIkSTpCDt8k6Rjs2rWL5cuXE8cxFRUV7Nmzh6KiIpLJJNOmTaOoqCh0onRStbS0sHr1alKpFIsWLaK+vp6BAwcyfvx4EokEJSUlXg8nSWoTNmzYwKOPPsr9999PfX09l1xyCTNnzuTaa6+la9euofMktRP19fU8/PDDzJ49m40bNzJs2DBmzJjBjBkz6NmzJ7vZzVCGso1ttNJKJzqRRRattHIBFzCZyUREDGMYWWSF/nQUyBKWcCVXsoc9dKNb6BypQ3mYh/kMn2E72+lBj9A5kiRJkqQj5PBNko7Q5s2bqaqqIo5jnnjiCVpbWykuLiaZTDJ16lTy8/NDJ0ptRl1dHalUinQ6TW1tLT179mTMmDEkEgkmTZrE6aefHjpRktSB7N69m4qKCubOnUtNTQ39+/dn+vTp3HTTTZx77rmh8yS1Y62traxatYq5c+fy8MMP09LSQhRFNNzdQPVZ1QDkkstoRjORiVzJleTj1476X7XU8nE+zvM8z7n495F0Ml3FVbzGa1RTHTpFkiRJknQUHL5J0odQV1dHOp0mjmNWrVrFaaedxujRo0kmk5SXl9O9e/fQiVKbt2nTJiorK0mn06xYsYKcnBzGjBlDFEWUlZWRl5cXOlGSlKFqa2uZPXs2jzzyCPv376esrIwZM2YwYcIEsrOzQ+dJyjCNjY3Mnz+fH7/0Y9b/3Xq6/Vc3SvaXcPuo2xlaMDR0ntqgl3mZcziHVaziEi4JnSN1GM0004c+fItv8Y/8Y+gcSZIkSdJRcPgmSYfx1nfrp9NpKioq2LBhA3369KGkpIRkMsm4cePIzc0NnSm1Wzt37mTJkiWk02mWLFlCU1MTxcXFRFHEpEmTGDJkSOhESVI7t2XLFh566CF+/vOf88ILLxy8fnD69On06tUrdJ6kDuAlXmLvur08+OCDPPDAA+zYsePgtcrTp0+nS5cuoRPVRuxjH6dyKhVUUE556Bypw3iSJxnNaP7MnzmP80LnSJIkSZKOgsM3SfqbpqYmVq5cSRzHLFiwgG3btjFo0CASiQTJZJLhw4fTqVOn0JlSxtm7dy81NTWkUiniOKahoYGioiKiKCKRSDBixAiysrJCZ0qS2oF9+/ZRWVnJnDlzqKqq4vTTTyeZTPJ3f/d3XHjhhaHzJHVgLS0tPPnkk8yePZuKigq6dOnCpz/9aWbMmMHIkSND56kN6E537uIubuKm0ClSh/ElvsQylvFH/hg6RZIkSZJ0lBy+SerQXn/9dWpqaojjmIqKCvbs2UNRURHJZJJp06ZRVFQUOlHqUFpaWli9ejWpVIpFixZRX1/PwIEDGT9+PIlEgpKSEnJyckJnSpLamLq6OubOnct//ud/smvXLi6//HJmzZrFxIkT/XtDUpuzbds25s+fz/33389zzz3H0KFDue666/jMZz5D3759Q+cpkMEM5jN8hq/xtdApUocxhCFMYQrf43uhUyRJkiRJR8nhm6QOZ/PmzVRVVRHHMU888QQHDhzg4osvJplMMnXqVPLz80MnSvqburo6UqkU6XSa2tpaevbsyZgxY0gkEkyaNInTTz89dKIkKZBdu3aRSqX4j//4D9asWcNHPvIRrrrqKm644QbOOeec0HmS9KHU1tYyZ84cHnroIRobGx3udmAjGMEn+SQ/5sehU6QOYT3rGcpQnuZphjM8dI4kSZIk6Sg5fJPUIdTV1ZFOp4njmFWrVnHaaacxevRokskk5eXldO/ePXSipA+wadMmKisrSafTrFixgs6dOzN27FiiKKKsrIy8vLzQiZKkE6y1tZVf//rXzJ49m8WLF3PqqadSXl7OzJkzGTNmjFdjS2q3mpqaiOOY2bNnU1NTQ15eHslkkhtvvJH/+3//b+g8nQQTmUhXuvIwD4dOkTqEH/AD7uROXuVVsskOnSNJkiRJOkoO3yRlpNbWVlatWkU6naaiooINGzbQp08fSkpKSCaTjBs3jtzc3NCZko7Szp07WbJkCel0miVLltDU1ERxcTFRFDFp0iSGDBkSOlGSdBxt2LCBRx99lPvvv5/NmzczbNgwZs2axTXXXEO3bt1C50nScfXyyy/zyCOPcN9997Fp06aDj3lXX321Jx5nsFnMYhObqKY6dIrUIXyKT1FIIQ/yYOgUSZIkSdIxcPgmKWM0NTWxcuVK4jhmwYIFbNu2jUGDBpFIJEgmkwwfPpxOnTqFzpR0nO3du5eamhpSqRRxHNPQ0EBRURFRFJFIJBgxYoQnAElSO7R7924qKiqYO3cuNTU19O/fn+nTp3PTTTdx7rnnhs6TpBPurW/omjt3Lg899BCtra1EUcSsWbM85TIDfYNvEBPzHM+FTpEy3uu8Tj/68SiPMpWpoXMkSZIkScfA4Zukdu3111+npqaGOI6pqKhgz549FBUVkUwmmTZtGkVFRaETJZ1ELS0trF69mlQqxaJFi6ivr2fgwIGMHz+eRCJBSUkJOTk5oTMlSe+jtraW2bNn88gjj7B//37KysqYMWMGpaWldO7cOXSeJAXR2NjI/PnzmTNnDk8//TRnn30211xzDTfffDOFhYWh83Qc3M3d3MmdbGVr6BQp4z3Mw9zADexgB2dwRugcSZIkSdIxcPgmqd3ZvHkzVVVVxHHME088wYEDB7j44otJJpNMnTqV/Pz80ImS2oi6ujpSqRTpdJra2lp69uzJmDFjSCQSTJo0yauiJKmN2Lp1K3PnzuUXv/gFzz//PEVFRcycOZMbb7yR3r17h86TpDZl3bp1PPjgg9x///3s3LmT0aNHM2PGDKZOnUqXLl1C5+koPcqjzGQm+9hHJzytXjqRruIqXud1lrEsdIokSZIk6Rg5fJPULtTV1ZFOp4njmFWrVnHaaacxevRokskk5eXldO/ePXSipDZu06ZNVFZWkk6nWbFiBZ07d2bs2LFEUURZWRl5eXmhEyXp/2fvzuOqLPP/j7+OIghCiICikomWoqhoLmVBIYpineM2icsoM2qKOe6PSm38+bWcmTKd6uRME2ZamBs0ih5cSlEbxSWl1AkX3AWVEFBDAxI4vz/6wjfCBQg9iO9nD/7gvj/Xfb+v+xyU5MN1PVDy8vL48ssvWbp0KWvWrMHFxYWBAwcyduxYOnToYOt4IiJVXkFBAdu2bWPhwoXExsZSp04dwsLCGD58OAEBAbaOJ+UUTzw96EEGGbjjbus4ItXWDW5Qn/rMYQ7jGW/rOCIiIiIiIvIbqfFNRKqkwsJCdu3aRVxcHLGxsRw7dgxPT09CQ0MZOHAgPXv2xMHBwdYxReQ+lZGRwYYNG4iLi2PDhg3k5uby5JNPYjKZ6N+/Py1atLB1RBGRaispKYmlS5fy8ccfk5WVRXBwMGPGjKFv377Y29vbOp6IyH3p4sWLREdHs3jxYg4dOlS8cuaIESOoX7++reNJGRziEP74c5jDtKKVreOIVFtf8iW96MVpTtOUpraOIyIiIiIiIr+RGt9EpMrIzc1l586dWCwWoqOjSUtLo1mzZhiNRgYOHMhTTz1FjRra7kNEKtePP/5IfHw8MTExWCwWrly5QuvWrTGZTBiNRp5++mkMBoOtY4qI3NeuXLlCdHQ0kZGRfPPNN7Rs2ZLBgwczcuRImjRpYut4IiLVSmJiIlFRUXz22Wdcu3aNnj17Eh4eTv/+/bGzs7N1PLmFNNJoSEO+4iue4RlbxxGptiYwgZ3s5Fu+tXUUERERERERqQRqfBMRm8rKyiI+Ph6LxUJsbCzXr1+nQ4cOGI1GwsLCaN26ta0jisgDpKCggN27dxMTE8Pq1atJTU2lSZMmhIaGYjQaCQ0NpVatWraOKSJyXygsLGTr1q1ERUXx+eefU6tWLfr27Ut4eDjdu3dXU7GIyF2Wm5uLxWJh4cKFxMfH4+XlxcCBA3nxxRdp27atrePJrxRQgD32rGIVL/CCreOIVFs++BBOOK/zuq2jiIiIiIiISCVQ45uI3HPnzp1j06ZNWCwWvvjiC6xWK0888QQDBw7khRdeoHHjxraOKCIC/LwdX0xMDHFxcSQmJlKvXj26d++O0Wikf//+uLi42DqiiEiVk5yczPLly/nkk084e/YsHTt2ZMyYMQwdOhRnZ2dbxxMReSClpKSwfPlyIiMjOX36dPGfzUOGDNH3tFWIBx68wRuMY5yto4hUSwc4QAc6sI99dKKTreOIiIiIiIhIJVDjm4jcE0lJScTFxWGxWNi1axeOjo4EBwczcOBA+vbti6urq60jiojc1unTp1m3bh1xcXFs374dOzs7AgICMBqNDBo0CC8vL1tHFBGxmZycHOLi4opXFWrYsCHDhw/nxRdf5NFHH7V1PBER+V+/XI3z3//+N4WFhZhMJsaMGaPVOKuA1rQmjDBmM9vWUUSqpTd4g0giSSUVA/rzTkREREREpDpQ45uI3BWFhYXs2rWLuLg4YmNjOXbsGJ6enoSGhjJw4EB69uyJg4ODrWOKiFRIRkYGGzZsIC4ujg0bNpCTk0PXrl0xmUz069ePli1b2jqiiMg9kZiYyMKFC1m+fDk3btygT58+DB8+nN69e2NnZ2freCIichtXrlwhOjqaqKgoEhISaNKkCUOGDGHs2LE0bdrU1vEeSEEE4Ycf/+Sfto4iUi11pjOd6MS/+Jeto4iIiIiIiEglqWHrACJSfeTm5rJlyxYmTZpE48aNCQwMJCYmhl69erFjxw7S0tKIiorCZDKp6U1E7mseHh6Eh4cTHR1Neno6sbGxNGvWjLfeegtfX1/8/PyYPn06O3fuRL9jICLVzYULF5g7dy4tWrSgU6dO7Ny5k5kzZ5Kamkp0dDQmk0lNb1IpTpw4gcFgYOXKleUaN3/+fAwGAwaDAW9v77uU7re5fPkyH374IcHBwdSrVw9HR0cee+wxfv/733Pw4MFS9RV9FiK3U7duXcaMGcPOnTtJSkpiyJAhLFmyhObNmxMSEkJUVBQ5OTm2jvlAqU99LnHJ1jFEqqULXCCRREyYbB1FREREREREKpEa30TkN8nKyiImJobw8HDq169Pr169SEhIICIigqSkJE6ePInZbCYgIIAaNfRHjohUP05OTphMJqKiosjIyGDHjh306NGDZcuWERgYSNOmTYmIiMBisXDjxg1bxxURqZC8vDwsFgthYWE88sgjzJ07l27dupGYmEhSUhLTpk3Dw8PD1jFFAHj55ZexWq34+/vbOsotvfLKK0yYMIG+ffty+PBhMjMzWbx4MQcOHKBjx47ExsbaOqI8YFq3bs1bb71FSkoKsbGxuLm5MWrUKBo1akRERASJiYm2jvhA8MSTdNJtHUOkWlrHOpxwIphgW0cRERERERGRSqQuFBEpt3PnzrFw4UJMJhNeXl4MHTqUU6dOMWfOHM6dO8f+/fuZPXs2rVu3tnVUEZF7qmbNmgQEBGA2m0lJSeG7775jxIgRJCYm0qdPH7y8vAgLCyMqKors7GxbxxURuaOkpCSmT5/Oww8/TL9+/bh8+TIff/wx58+fJzIykscff9zWEUXuWyNHjmTSpEl4eXnh5OREYGAgy5cvp6CggFdffdXW8eQBZW9vj8lkIjo6mnPnzjF79mx2795Np06d8PPzY+7cuVy6pBXJ7hY1voncPRYs9KIXtalt6ygiIiIiIiJSiQxW7b8lImWQlJREXFwcFouFXbt24ejoSHBwMAMHDqRv3764urraOqKISJV2+vRp1q1bR1xcHNu3b8fOzo6AgACMRiODBg3Cy8vL1hFFRAC4cuUK0dHRLFy4kMTERFq0aMGQIUMYMWIEjzzyiK3jyQPkxIkTPPbYY6xYsYLBgweXe3z79u3JyMggNTX1LqS7e5ycnMjLyyM/Px+DwQD89mch8lslJiaycOFCVqxYwU8//URISAjh4eH0799f21tXog/4gFnMIoMMW0cRqVaucx0PPPgX/+KP/NHWcURERERERKQSacU3EbmpgoICdu7cyfTp0/H19aVNmzb8/e9/p1mzZqxdu5asrCwsFgvh4eFqehMRKQMfHx8mTZrE5s2buXjxIpGRkbi5ufHnP/+Zxo0bExAQwNy5czl27Jito4rIA6iwsJAtW7YQHh5Oo0aNmDx5Ms2aNWPz5s0cPXqU2bNnq+lN5B64fv06OTk5tGnTprjpTaQq6NixI5GRkaSnp7N06VJyc3MZNGgQjzzyCNOnT+f48eO2jlgt1Kc+WWSRT76to4hUK1/wBT/xE73pbesoIiIiIiIiUsnU+CYixXJzc9myZQuTJk3C29ubwMBAYmJi6NWrFzt27CAtLY2oqChMJhMODg62jisict/y8PAgPDyc6Oho0tPTiY2NpVmzZrz11lv4+vri5+fH9OnT2blzJ1qcV0TupnPnzjF37lyaN29OSEgIhw8f5r333iM9PZ3o6Gh69Oih5huxmUcffRSr1VpihbO8vDxmzZqFr68vTk5O1KtXD5PJxLp16ygoKCjTdS9dusTEiRNp2rQp9vb2eHp6MmDAAA4cOFCh2vnz52MwGDAYDHh7e7Nv3z66d++Oi4sLTk5OdOvWjYSEhDJli4mJAeDPf/7zHZ+FiC3Url2bgQMHsnnzZs6cOcPEiRNZtWoVLVq0oFOnTixcuJBr167ZOuZ9qz71sWLVim8ilcyChad4igY0sHUUERERERERqWTa6lTkAZeVlUV8fDwWi4XY2FiuX79Ohw4dMBqNhIWF0bp1a1tHFBF5YBQUFLB7925iYmJYvXo1qampNGnShNDQUIxGI6GhodSqVcvWMUXkPpebm4vFYmHhwoXEx8fTsGFDhg8fzqhRo3jsscdsHU/ktkaPHk1MTAwxMTEEBATwww8/MH/+fObPn8+2bdsICgoqrr3ZVqcXL16ka9eu5ObmsnjxYp555hnOnj3Ln/70J/bu3cvWrVvp2rVruWuL7nfixAnatWvH3//+d9q1a8eRI0cYNWoUR48e5csvv+TZZ5+95dy+//57/P39MZlMfPTRR5X/8ETuksLCQrZu3UpUVBT//ve/sVqtGI1GxowZQ/fu3dVAXQ5HOUorWnGQg7Sjna3jiFQLhRTSiEZMZSqv8qqt44iIiIiIiEglU+ObyAPo3LlzbNq0CYvFwhdffIHVauWJJ55g4MCBvPDCCzRu3NjWEUVEBEhKSiImJoa4uDgSExOpV68e3bt3x2g00r9/f1xcXGwdUUTuI4mJiSxcuJAVK1bw008/ERISQnh4OP3798fOzs7W8UTKpFmzZjRs2LDUCmotW7YkMjLyjo1vf/zjH/n0009ZtmwZQ4cOLT6elpZG06ZNadOmDfv37y93bdH9Dh48yLfffkv79u2Lj//3v/+lXbt2+Pv733RVOYDMzEx69OhBy5YtWbZsGTVr1qzYAxKxsStXrhAdHU1UVBQJCQm0aNGCIUOGMGLECG2ZXQaZZOKBB5vZTA962DqOSLWwk50EEsgRjuCLr63jiIiIiIiISCVT45vIAyIpKYm4uDgsFgu7du3C0dGR4OBgBg4cSN++fXF1dbV1RBERuY3Tp0+zbt064uLi2L59O3Z2dgQEBGA0Ghk0aBBeXl62jigiVdDFixeJjo7m448/5r///S+tW7cmPDyckSNH4unpaet4IuU2btw4/vWvfzF69GhGjhxJ586db9kkdrPGt7p165Kdnc3ly5d56KGHStR37NiRb775hpSUFLy9vctVW3S/EydO3HSbx8aNG3PhwgUuXLhAw4YNS5y7fv06zz77LC1btiQqKkpNb1JtJCUlsXTpUhYvXkxmZibBwcEMHz6cgQMH4ujoaOt4VZIVK/bYE0UUQxhi6zgi1cI0prGa1RznuK2jiIiIiIiIyF2gxjeRaqpou7y4uDjWrFlDcnIynp6ehIaGMnDgQHr27ImDg4OtY4qISAVkZGSwYcMG4uLi2LBhAzk5OXTt2hWTyUS/fv1o2bKlrSOKiA399NNPfPHFFyxdupQ1a9bg7OxMWFgYY8aMoWPHjraOJ/KbWK1WPvvsMz799FN2794NQGBgIBEREfTv379E7a8b3/Ly8qhdu/Yd77F161aeeuqpMtd269btpvf7pQ4dOnDgwAEOHDiAv79/8fH8/Hz69OlDrVq1+Pe//63VF6VautXfSxERETz++OO2jlfleOHFn/kzE5hg6ygi1UIrWmHEyDzm2TqKiIiIiIiI3AU1bB1ARCpPbm4uFouFiIgIvL29CQwMJCYmhtDQUHbs2EFaWhpRUVGYTCY1vd2nTpw4gcFgYOXKlbesOX78OAaDgSeffPKm5+fPn4/BYMBgMBSvTiF31/vvv4+3tzeOjo707t2bc+fO3bRu8ODBxT84LavLly/z4YcfEhwcTL169XB0dOSxxx7j97//PQcPHixVX5b3kFR9Hh4ehIeHEx0dTXp6OrGxsTRr1oy33noLX19f/Pz8mD59Ojt37kS/4yDy4Dh8+DDTp0/n4Ycfpl+/fly+fJmPP/6YCxcuEBkZqaY3qRYMBgPDhw9ny5YtXLlyhdjYWKxWKwMGDOCdd9657VgHBwfq1q2LnZ0dN27cwGq13vSjW7du5ar9pczMzJv+3ZvZBTbvAAAgAElEQVSeng5A/fr1SxyPiIggLy+P6OjoEk1vjz76KHv27KnoYxKpUuzt7TGZTERHR3P27FmmT5/Otm3b6NixI35+fsydO5eMjAxbx6wy3HEnk0xbxxCpFk5wgqMcxYTJ1lFERERERETkLlHjm8h9Lisri5iYGMLDw6lfvz79+vUjMTGRiIgIkpKSOHnyJGazmYCAAGrU0Jf8g2DJkiUA7N27l8OHD5c6//LLL2O1WkusNCF3T1xcHFOmTMFsNnP27FlycnJ44YUXStV9+eWXrFmzhn/961/luv4rr7zChAkT6Nu3L4cPHyYzM5PFixdz4MABOnbsSGxsbGVNRaooJycnTCYTUVFRZGRksGPHDnr06MGyZcsIDAykadOmREREYLFYuHHjhq3jikglu3LlCgsXLiQgIAA/Pz9Wr17NSy+9xMmTJ9m8eTPh4eHaTk6qlbp163L06FEAatWqRUhICLGxsRgMBtavX3/H8QMGDCA/P5+EhIRS5+bOnUuTJk3Iz88vd22R3Nxc9u3bV+LYf//7Xy5cuIC/v3+JbU5nz55NUlISa9eu1S8myQOjUaNGTJs2jeTkZPbv309AQAB//etf8fb2xmQyERMTU+rr6kHjgYca30QqSSyx1KMeT/GUraOIiIiIiIjIXaIuGJH70NmzZ1m4cCEmkwkvLy+GDh3KqVOnmDNnDufOnWP//v3Mnj2b1q1b2zqq3GOFhYVERUXRoUMH4P+a4MrD2dmZgICAyo5mE1VhLmazmaCgIH73u99Rv359Xn/9dfbt21fiB6i5ubmMGzeOV199FV9f33LfY+TIkUyaNAkvLy+cnJwIDAxk+fLlFBQU8Oqrr1bmdKSKq1mzJgEBAZjNZlJSUvjuu+8YMWIEiYmJ9OnTBy8vL8LCwoiKiiI7O9vWcUWkggoLC9myZQvh4eE0btyYSZMm0ahRIzZv3syxY8eYPXs2TZs2tXVMkbtm7NixHDp0iLy8PNLT03n77bexWq0EBwffceybb75J8+bNGTlyJBs3buTq1atkZWURGRnJG2+8wfz584tXXitPbRFXV1dee+01du/ezfXr19m/fz/Dhg3D3t4es9lcXPfJJ5/w+uuvs3fvXlxcXIpXZC76OHnyZOU+NJEqqGPHjkRGRvL999+zdOlScnNzGTRoEI888gjTp0/nxIkTto5oEx54kIFWwBOpDBYsGDFih7YSFxERERERqa7U+CZyn0hKSmLu3LkEBATg4+PD1KlTAVi0aBEZGRns3LmTSZMm0bhxYxsnFVv68ssvsbOzY+HChQAsXbr0gf9teVs7evRoiSZUPz+/4uNF/vrXvwLw5z//udzXX7RoEZGRkaWO+/v74+joyMmTJ7XV5QPMz8+P2bNns3//fk6dOsWsWbO4fPkyo0aNon79+oSEhGA2m0lLS7N1VBEpo/T0dB555BF69uzJ6dOn+cc//sGlS5eIjo6mR48eGAwGW0cUuau++uorfH19GTx4MPXq1aNVq1Zs2rSJjz76iNdeew2A+fPnYzAYOHjwIOfPn8dgMDBz5kzg561Gv/76a/r168f48ePx9PTE19eX1atXs3btWsLCworvVZ7aIs7OzixYsIDXX3+dhg0b8swzz+Dm5sbWrVt59tlni+s+//zzu/ykRO4fjo6ODBw4kM2bN3P06FH+8Ic/sHTpUlq0aMHYsWNtHe+ec8ddjW8ilSCLLHaxS9ucioiIiIiIVHMGq34aLlIlFRQUsHv3buLi4lizZg3Jycl4enoSGhrKwIED6dWrF/b29raOKffYiRMneOyxx1ixYgWDBw8udT4sLIzWrVsze/Zs/P39OXToEGvXrqVPnz6latu3b09GRgapqakljjs7O9O+fXt27tx51+Zxr1SFuXh7e9O/f38WLFgAQEZGBp6ennz88ceMHDmSo0eP4u/vj8VioWfPnpV23+vXr+Ps7Ey7du04ePBg8fE7vYfkwZCRkcGGDRuIi4tjw4YN5OTk0LVrV0wmE/369aNly5a2jigit3DmzBl8fHyIi4vj+eeft3UcEfmFW31/LSLlV1BQwJAhQ8jMzCQ+Pt7Wce6p13iNTWziG76xdRSR+1oUUYxhDJe4hAsuto4jIiIiIiIid4lWfBOpQnJycrBYLERERODt7U1gYCAxMTGEhoayY8cO0tLSiIqKwmQyqentAfXoo49itVpv2rCUlZWFxWLhD3/4AwAjRowAYPHixWW6dtHKGNevXychIaF4m6Vfb9906dIlJk6cSNOmTbG3t8fT05MBAwZw4MCB4prY2NgSWzUdO3aMsLAw3N3di48tWrSoRM2ZM2cYNGgQdevWxd3dHaPRWGqLp/z8fFatWkVISAheXl44OjrStm1bzGYzhYWF5Z5LZmYmU6dOpXnz5tjb2+Pm5kbv3r3Ztm1bueaSkXHr38b39fXlu+++K/48KSkJoLix6KWXXmLAgAGV2vQGEBMTA5ReRe527yF5cHh4eBAeHk50dDTp6enExsbSrFkz3nrrLXx9ffHz82P69Ons3LlTKwaKVFGenp62jiAiInLX1KxZE3d3d1vHsAmt+CZSOSxY6EY3Nb2JiIiIiIhUc2p8E7GxrKwsYmJiCA8Pp0GDBvTr14/ExEQiIiJISkri5MmTmM1mAgICqFFDX7Jya8uXL6dr1674+PgAMGzYMGrVqsX69etJT0+/4/iXX34Zq9VKnTp1ePrpp7FarVit1hJbpV68eJHOnTsTHR3NBx98QFZWFtu3bycrK4uuXbuye/duAPr164fVaqVv374AREREMG7cOFJSUtizZw81a9YsVTN58mQmT57M+fPnWbVqFVu3bmXIkCElMm7atInBgwcTHBzMkSNHSElJYcyYMUydOpVp06aVay5paWl07tyZ5cuXYzabycjIYO/evTg5OdG9e3cWLVpU5rnczsSJE/nPf/5DTEwM6enp/M///A8dO3bk6aef5tNPP+Xbb7/l3Xff5eLFi/Tp0wcnJycaNWrE3Llz7/ia3cr333/P9OnTefHFF2+6BZfILzk5OWEymYiKiiIjI4MdO3bQo0cPli1bRmBgIE2bNiUiIgKLxcKNGzdsHVdEREREpFpT45vIb5dHHl/whbY5FREREREReQCoi0bEBs6ePcvChQsxmUx4eXkxdOhQTp06xZw5c0hJSWH//v3Mnj2b1q1b2zqq3EeWLFlSvMob/Lyik9FoJD8/n6VLl1bKPWbMmMHZs2d55513eO6553B2dsbPz4+VK1ditVqZMGHCTcdNmzaNoKAgnJyceOKJJ8jPz8fDw6NEzYsvvkjXrl2pU6cOPXr04Pnnn2ffvn2lVlMLCgpixowZuLm54eHhwYQJExg6dChms5kffvihXHM5ffo07733HkajkYceeogWLVqwfPlyGjZsyMSJE/n+++8rNJdf6tOnD/PmzWPy5Mk0adIEe3t7Pv/8c7KysnjllVf429/+hpeXF7///e9JS0vj5MmTREZGMnPmTFauXFnm+RTJzMwkNDSUoKAgPvzww3KPlwdbzZo1CQgIwGw2k5KSwnfffceIESNITEykT58+eHl5ERYWRlRUFNnZ2baOKyIiUiUUrTZ88OBBzp8/j8FgYObMmbaOJSL3KQ88yCGHH/nR1lFE7lvb2MY1rqnxTURERERE5AGgxjeReyQpKYm5c+cSEBCAj48PU6dOBWDRokVkZGSwc+dOJk2aRKNGjWycVO5Hhw4d4vjx4/zud78rcbyoEW7JkiWVcp/Y2Fhq1KiB0WgscdzLyws/Pz8SExNJTU0tNa5Lly53vHbnzp1LfP7www8DcOHCheJjRqOxxDakRfz9/blx40bxNqJlsWbNGgCef/75EscdHBzo3r07OTk5fPHFF6XGlWUuvzZ16lTOnz9Pbm4uX375JU2bNuXVV1/Fx8eHsWPH8t1337Ft2zb+3//7fzRs2BCTyUTPnj0xm83lus/169fp1asXrVu3ZtmyZXdcjU7kTvz8/Jg9ezb79+/n1KlTzJo1i8uXLzNq1Cjq169PSEgIZrOZtLQ0W0cVERGxmaLVhn/58Ze//MXWsUTkPuXOz1u8ZpJp4yQi9y8LFjrQgYd52NZRRERERERE5C5T45vIXZSdnc2UKVPw8fGhTZs2LFiwgHbt2rFp0yaysrKwWCyEh4fj6upq66hyn1u8eDHZ2dnUqVMHg8FQ/NGnTx/g58bLr7/++jfdIy8vj6tXr1JYWIirq2uJ+xgMBr755hsAjh8/XmpsnTp17nj9X38d2NvbA1BYWFh87OrVq8yaNYu2bdvi5uZWfO9XXnkFgB9/LNtvxBfNpXbt2ri4uJQ636BBA4CbNvOUZS53kpCQwKeffkpkZCQ1atTg2LFjACVWeWzTpg1Hjx4t8zXz8/MZOHAgjRs35tNPP1XTm1Q6Hx8fJk2axObNm0lNTeX999/HwcGB6dOn4+3tTVBQEJ999pmtY4qIiIiI3Nc8+HlFcW13KlIxVqxYsGi1NxERERERkQeEGt9E7qLMzEzee+89evbsyd69e0lJSeGDDz6gZ8+exU09Ir/VjRs3WLZsGQkJCaVWmrBarUyePBko+6pvBoPhpscdHByoW7cudnZ23Lhx46b3slqtdOvWrdLm9msmk4k5c+YwevRokpOTKSwsxGq18u677wJgtVrLPBdXV1dyc3Nvul1j0RanXl5elTyDn1+vsWPHMmHCBNq3bw/8X+5f5q1Ro8Yt899MREQEeXl5REdHY2dnV3z80UcfZc+ePZWUXuRnDRo0YPTo0cTFxXHp0iVWrFjB5cuXK211SRERqb6KtgU1GAx4e3vbOs5vUlBQwIcffshTTz2Fq6srtWrVolGjRjz33HP84x//4MyZM8W11WneInJ3FTW+acU3kYr5lm9JIYU+9LF1FBEREREREbkH1Pgmcg+MGjWKLl26lKuJRaSsLBYLHh4ePPXUUzc9P2rUKABWrFhBTk7OHa/n5OTETz/9VPx5y5YtWbhwIQADBgwgPz+fhISEUuPmzp1LkyZNyM/Pr8g07qigoICEhAS8vLyYOHEinp6exV9Tt5rX7ebSv39/ANavX19iTF5eHvHx8Tg6OtKrV69Kn8ff//53rly5whtvvFF8zNfXF6DEVq2HDx+mZcuWZbrm7NmzSUpKYu3atTg4OFRuYJE7cHZ2ZuDAgbf8M0hEROSXirYF9ff3t3WU32z48OH86U9/ol+/fiQlJZGdnc2OHTvo0KEDEydOpFOnTsW11WneInJ31aUudthpxTeRClrHOhrTmA50sHUUERERERERuQfU+CYicp9bsmQJI0eOvOX5Nm3a0KVLF65evcrq1avveL3HH3+c5ORkUlJS2L17N6dOnSIwMBCAN998k+bNmzNy5Eg2btzI1atXycrKIjIykjfeeIP58+eXWG2sMtWsWZOgoCDS0tKYN28eGRkZ5OTksG3bNj788MMKzcXHx4fJkycTFxdHdnY2ycnJDB06lIsXL2I2m4u3PK0sZ86cYc6cObz//vs4OzsXH2/Tpg3dunXjL3/5CxcvXmTjxo1s3LiRKVOm3PGan3zyCa+//jp79+7FxcWl1Ba0J0+erNQ5iIiIiAjs27ePFStWMGrUKF599VW8vb2pXbs2zZs3569//SsvvfSSrSOKyH3KgAE33LTim0gFWbDQl74Y0C8gi4iIiIiIPAjU+CYicp9KTU3FYDAQFxfHq6++ypNPPlmq5syZMxgMBr7++msAhg0bVtwQdfDgQc6fP4/BYGDmzJnFY9577z3atWtHq1atGDRoEGazmVatWgFQv359vv76a/r168f48ePx9PTE19eX1atXs3btWsLCwgDYs2cPBoOBtWvXAuDo6FhqxcOb1RTlMBgMzJ07F4AOHTpgNBoBWLVqFRERESxYsIBGjRrh4+NDVFQUQ4cOBSAkJKTEyhq3m4uXlxf79u1jyJAhTJw4EXd3d7p06cL169fZsmULo0ePLvNcymr8+PEEBwcXrzb3S5999hn169enWbNmjBw5kjlz5hQ/z9v5/PPPK5RFRERERCquaKXeW63QW5bv40REbsUDD634JlIB5znPt3yLCZOto4iIiIiIiMg9YrBarVZbhxCprs6cOYOPjw979+6lS5cuto4jIiJy17z00kskJycTHx9v6ygi1Zq+v5Tqon379mRkZJCammrrKBWyceNGnnvuOXr16sWmTZvKPO5+n7fIvfQgf3/5DM/Qnva8z/u2jiJyX/mAD5jGNC5xidrUtnUcERERERERuQe04puIiIiIiIiIVIrMzEymTp1K8+bNcXBwwNvbmx49evDJJ5+Qk5Nz27H5+fmsWrWKkJAQvLy8cHR0pG3btpjNZgoLC0vU5uXlMWvWLHx9fXFycqJevXqYTCbWrVtHQUFBuevKKzAwEC8vL7744gt69+7N9u3bS2Usj0uXLjFx4kSaNm2Kvb09np6eDBgwgAMHDlSodv78+cUrPXt7e7Nv3z66d++Oi4sLTk5OdOvWjYSEhArnFZG7yx13rfgmUgEWLIQSqqY3ERERERGRB4ga30RERERERETkN0tLS6Nz586sWLECs9lMRkYGiYmJBAUFMWLECCIjI287ftOmTQwePJjg4GCOHDlCSkoKY8aMYerUqUybNq1E7fjx43n//fdZsGABmZmZHDlyBF9fX/r27cuOHTvKXQcQHByMu7s7e/bsueNcnZ2diYmJ4eGHH2bTpk1069aNhg0bMmzYMFasWMGPP/5Y5ud28eJFOnfuTHR0NB988AFZWVls376drKwsunbtyu7du8td+/LLL2O1WvH39+fKlStMmjSJv/zlL6SlpfGf//yHrKwsgoOD+eqrr8qcU0TuHQ88yCTT1jFE7ivXuMZ2tmubUxERERERkQeMGt9ERERERERE5DebMWMGp0+fxmw2YzQacXFxoUGDBsycOZPQ0NAyXSMoKIgZM2bg5uaGh4cHEyZMYOjQoZjNZn744Yfiuvj4ePz8/AgJCcHR0ZEGDRowb948WrRoUeJ6Za0DKCwsxGq1YrVay5Q1ICCA48eP8+mnn9K3b19ycnJYtmwZQ4cOpUmTJqxcubJM15kxYwZnz57lnXfe4bnnnsPZ2Rk/Pz9WrlyJ1WplwoQJFaotcv36dT744AO6du1KnTp16NSpE5999hk//fQTkyZNKlNGEbm3tOKbSPltYhM3uMFzPGfrKCIiIiIiInIPqfFNRERERERERH6zNWvWANC7d+9S5zZu3MjkyZNvO95oNLJt27ZSx/39/blx4wZJSUnFx0JDQ9m1axdjxoxhz549xduWHjt2jKCgoHLXASVWTisrBwcHwsPDiY2NJSsri/j4eAYPHkxmZibDhg3j22+/veM1YmNjqVGjBkajscRxLy8v/Pz8SExMJDU1tdy1RerUqUP79u1LHGvbti2NGjXi4MGDXLx4sczzFZF7wx13rfgmUk4WLDzN03jgYesoIiIiIiIicg+p8U1EREREREREfpO8vDyuXr1K7dq1cXFxqdA1rl69yqxZs2jbti1ubm4YDAYMBgOvvPIKQIntQ//5z38SFRXFqVOn6N69Ow899BChoaHFzXflrasMdnZ2BAcHs2LFCqZNm0ZBQQGff/75bccUPbfCwkJcXV2L51z08c033wBw/PjxctX+Ut26dW967/r16wOQnp7+W6cuIpXMAw+t+CZSDgUUsIEN2uZURERERETkAaTGNxGRamD+/PnFP/Dy9va2dZxKc/z4cQwGA08++eRNz1fXeYuIiIjcbxwcHHB1dSU3N5fs7OwKXcNkMjFnzhxGjx5NcnJy8daj7777LkCJLUgNBgPDhw9ny5YtXLlyhdjYWKxWKwMGDOCdd94pd115JSQk0KBBg1ue79atGwCXL1++7XUcHByoW7cudnZ23Lhxo3ir1V9/dOvWrVy1v5SZmXnT7VuLGt6KGuBEpOrwwIPrXCeHHFtHEbkvJJBABhn0oY+to4iIiIiIiMg9psY3EZFq4OWXX8ZqteLv72/rKJVqyZIlAOzdu5fDhw+XOl9d5y0iIiJyP+rfvz8AGzZsKHWuQ4cOTJky5ZZjCwoKSEhIwMvLi4kTJ+Lp6YnBYAAgJ6d040fdunU5evQoALVq1SIkJITY2FgMBgPr168vd115Wa1W0tPT2bNnz03P79+/H/h53ncyYMAA8vPzSUhIKHVu7ty5NGnShPz8/HLXFsnNzWXfvn0ljv33v//lwoUL+Pv707BhwztmFJF7yx13AG13KlJGFiz44ksLWtg6ioiIiIiIiNxjanwTEZEqqbCwkKioqOIfFhY1wZWHs7MzAQEBlR3NJqrTXERERKR6evPNN/Hx8WHKlCmsX7+e7OxsUlNTGTduHBcvXrxt41vNmjUJCgoiLS2NefPmkZGRQU5ODtu2bePDDz+86ZixY8dy6NAh8vLySE9P5+2338ZqtRIcHFyhuuDgYNzd3W/ZzHYzYWFhLF++nAsXLpCXl8eZM2eYP38+b7zxBh07diQ8PPyO13jzzTdp3rw5I0eOZOPGjVy9epWsrCwiIyN54403mD9/PnZ2duWuLeLq6sprr73G7t27uX79Ovv372fYsGHY29tjNpvLPFcRuXc88ADU+CZSVutYp9XeREREREREHlBqfBMRkSrpyy+/xM7OjoULFwKwdOnSUqtXiIiIiEjV4eXlxb59+xg0aBATJkzA3d2dLl26cPnyZXbs2EGTJk2Kt6o/ePAg58+fx2AwMHPmTABWrVpFREQECxYsoFGjRvj4+BAVFcXQoUMBCAkJoVOnTgB89dVX+Pr6MnjwYOrVq0erVq3YtGkTH330Ea+99lpxprLWAeTn5xdvF3onTz31FDt37mTQoEG8//77dO7cGWdnZ9q1a8eqVauYPXs2//nPf3BwcAC47bzr16/P119/Tb9+/Rg/fjyenp74+vqyevVq1q5dS1hYWPF9y1NbxNnZmQULFvD666/TsGFDnnnmGdzc3Ni6dSvPPvtseV5iEblHilZ8yyDDxklEqr6jHCWZZEyYbB1FREREREREbMBgLcu/6IpIhZw5cwYfHx/27t1Lly5dbB1HHgDt27cnIyOD1NRUW0f5zcLCwmjdujWzZ8/G39+fQ4cOsXbtWvr0Kf0bvLeat7OzM+3bt2fnzp33KvZdU53mItXTSy+9RHJyMvHx8baOIlKt6ftLESmP6vT/B/LgeZC/vyykEHvsWc5ywijd0Coi/+ft//3ve76nJjVtHUdERERERETuMa34JiJyH8jMzGTq1Kk0b94cBwcHvL296dGjB5988gk5OTm3HZufn8+qVasICQnBy8sLR0dH2rZti9lsprCwsERtXl4es2bNwtfXFycnJ+rVq4fJZGLdunUUFBSUu66isrKysFgs/OEPfwBgxIgRACxevLhM44tW1Lh+/ToJCQkYDAYMBkOpbZ8uXbrExIkTadq0Kfb29nh6ejJgwAAOHDhQXBMbG1s83mAwcOzYMcLCwnB3dy8+tmjRohI1Z86cYdCgQdStWxd3d3eMRiMnT54sce+yvi5lncsv3yP29va4ubnRu3dvtm3bVq65ZGRoRQERERERERFbqkEN6lKXLLJsHUWkyrNgwYRJTW8iIiIiIiIPKDW+iYhUcWlpaXTu3JkVK1ZgNpvJyMggMTGRoKAgRowYQWRk5G3Hb9q0icGDBxMcHMyRI0dISUlhzJgxTJ06lWnTppWoHT9+PO+//z4LFiwgMzOTI0eO4OvrS9++fdmxY0e56wCCg4Nxd3dnz549ZZ7z8uXL6dq1Kz4+PgAMGzaMWrVqsX79etLT0+84/uWXX8ZqtVKnTh2efvrp4i2rfrlV6sWLF+ncuTPR0dF88MEHZGVlsX37drKysujatSu7d+8GoF+/flitVvr27QtAREQE48aNIyUlhT179lCzZs1SNZMnT2by5MmcP3+eVatWsXXrVoYMGVIiY1lfl7LMpeg9snz58uL3yN69e3FycqJ79+4sWrSozHMRERERERER23PDTY1vIneQSSa72a1tTkVERERERB5ganwTEaniZsyYwenTpzGbzRiNRlxcXGjQoAEzZ84kNDS0TNcICgpixowZuLm54eHhwYQJExg6dChms5kffvihuC4+Ph4/Pz9CQkJwdHSkQYMGzJs3jxYtWpS4XlnrAAoLC4ubtcpqyZIlxau8AXh4eGA0GsnPz2fp0qVlvs7tzJgxg7Nnz/LOO+/w3HPP4ezsjJ+fHytXrsRqtTJhwoSbjps2bRpBQUE4OTnxxBNPkJ+fj4eHR4maF198ka5du1KnTh169OjB888/z759+0qtplbW16Usczl9+jTvvfceRqORhx56iBYtWrB8+XIaNmzIxIkT+f777ys0FxERERG5/xStGnzw4EHOnz+PwWBg5syZto4lIuXghhuXuWzrGCJVmgULdtgRQoito4iIiIiIiIiNqPFNRKSKW7NmDQC9e/cudW7jxo1Mnjz5tuONRmOJ7S6L+Pv7c+PGDZKSkoqPhYaGsmvXLsaMGcOePXuKty09duwYQUFB5a4DSqyiVhaHDh3i+PHj/O53vytxvKgRbsmSJWW6zp3ExsZSo0YNjEZjieNeXl74+fmRmJhIampqqXFdunS547U7d+5c4vOHH34YgAsXLhQfK8/rcidF75Hnn3++xHEHBwe6d+9OTk4OX3zxRalxZZmLiIiIiNx/ilYN/uXHX/7yF1vHEpFyqEc9Nb6J3IEFC93pjgsuto4iIiIiIiIiNqLGNxGRKiwvL4+rV69Su3ZtXFwq9o94V69eZdasWbRt2xY3NzcMBgMGg4FXXnkFgB9//LG49p///CdRUVGcOnWK7t2789BDDxEaGlrcWFXeuopYvHgx2dnZ1KlTpzirwWCgT58+ACQlJfH111//pnsUPdfCwkJcXV1L3MdgMPDNN98AcPz48VJj69Spc8fru7q6lvjc3mlk07MAACAASURBVN4e+Hn1uyLleV3KMpdbvUcaNGgA/LwdakXmIiIiIiIiIveeVnwTub088tjMZm1zKiIiIiIi8oBT45uISBXm4OCAq6srubm5ZGdnV+gaJpOJOXPmMHr0aJKTk4u3Hn333XcBSmxBajAYGD58OFu2bOHKlSvExsZitVoZMGAA77zzTrnryuvGjRssW7aMhISEUitUWK3W4tXtyrrqm8FguOlxBwcH6tati52dHTdu3LjpvaxWK926davwXO6kPK/LneZyu/dI0RanXl5elTwDEREREamolStXFv/iQ+3atW0dR0SqIDfcyCLL1jFEqqx44rnGNYwY71wsIiIiIiIi1ZYa30REqrj+/fsDsGHDhlLnOnTowJQpU245tqCggISEBLy8vJg4cSKenp7FDVQ5OTml6uvWrcvRo0cBqFWrFiEhIcTGxmIwGFi/fn2568rLYrHg4eHBU089ddPzo0aNAmDFihU3zf9rTk5O/PTTT8Wft2zZkoULFwIwYMAA8vPzSUhIKDVu7ty5NGnShPz8/IpM447K+7rA7edS9B759bPPy8sjPj4eR0dHevXqdTemIiIiIiIVMHjwYKxWK927dy917tq1azz22GMYjeX7QX5Fx4lI1aStTkVuz4KFjnTEG29bRxEREREREREbUuObiEgV9+abb+Lj48OUKVNYv3492dnZpKamMm7cOC5evHjbxreaNWsSFBREWloa8+bNIyMjg5ycHLZt28aHH3540zFjx47l0KFD5OXlkZ6ezttvv43VaiU4OLhCdcHBwbi7u7Nnz547znXJkiWMHDnylufbtGlDly5duHr1KqtXr77j9R5//HGSk5NJSUlh9+7dnDp1isDAQODn59q8eXNGjhzJxo0buXr1KllZWURGRvLGG28wf/587Ozs7niPiqjI63Knufj4+DB58mTi4uLIzs4mOTmZoUOHcvHiRcxmc/GWpyIiIiK/hbOzMwEBAdX2flWB1WqlsLCQwsLCUudu9zxuN05E7j/a6lTk1qxYiSNO25yKiIiIiIiIGt9ERKo6Ly8v9u3bx6BBg5gwYQLu7u506dKFy5cvs2PHDpo0acL8+fMxGAwcPHiQ8+fPYzAYmDlzJgCrVq0iIiKCBQsW0KhRI3x8fIiKimLo0KEAhISE0KlTJwC++uorfH19GTx4MPXq1aNVq1Zs2rSJjz76iNdee604U1nrAPLz84u3Dr2V1NRUDAYDcXFxvPrqqzz55JOlas6cOYPBYODrr78GYNiwYcXbQ91s3gDvvfce7dq1o1WrVgwaNAiz2UyrVq0AqF+/Pl9//TX9+vVj/PjxeHp64uvry+rVq1m7di1hYWEA7NmzB4PBwNq1awFwdHQste3ozWqKchgMBubOnQv8vEJf0Qoc5Xld7jSXovfIkCFDmDhxYvF75Pr162zZsoXRo0eXeS4iIiIiYlsuLi6cPHnypis+341xIlI1aatTkVtLJJFUUulDH1tHERERERERERszWG/XiSAiv8mZM2fw8fFh7969dOnSxdZxRERE7pqXXnqJ5ORk4uPjbR1FpFrT95dia87OzrRv356dO3dWy/vdaz169GDnzp3k5uaWqb66Pw+RX3rQv79cwxoGMICf+Ila1LJ1HJEq5X/4Hz7hE85wBgP6hT4REREREZEHmVZ8ExEREREREXmA5eXlMWvWLHx9fXFycqJevXqYTCbWrVtHQUEBQPEKw9evXychIaF45d1fbg2fn5/PqlWrCAkJwcvLC0dHR9q2bYvZbC6x/WZsbGzxeIPBwLFjxwgLC8Pd3b342PTp0+94v7LKzMxk6tSpNG/eHAcHB7y9venRoweffPIJOTk5N62zt7fHzc2N3r17s23btltmP3PmDIMGDaJu3bq4u7tjNBo5efJkqQxHjx6lX79+uLq6UqdOHQIDA2/avPbr6xc1xN3p+d9q3L2Ym4jcHfWoB8AVrtg4iUjVs4519KGPmt5EREREREREjW8iIiIiIiIiD7Lx48fz/vvvs2DBAjIzMzly5Ai+vr707duXHTt2APDyyy9jtVqpU6cOTz/9dPFW9vn5+cXX2bRpE4MHDyY4OJgjR46QkpLCmDFjmDp1KtOmTSuu69evH1arlb59+wIQERHBuHHjSElJYc+ePdSsWbNM9yuLtLQ0OnfuzIoVKzCbzWRkZJCYmEhQUBAjRowgMjKyRN3y5cuL6/bu3YuTkxPdu3dn0aJFN80+efJkJk+ezPnz51m1ahVbt25lyJAhJTKcOHGCrl27sn//fj7//HO+//57PvjgA+bMmVOqkezX1y9yp+dxq3F3e24AwcHBuLu7s2fPnnK9NiJye264AWi7U5FfOcc5DnIQEyZbRxEREREREZEqQI1vIiIiIiIiIg+w+Ph4/Pz8CAkJwdHRkQYNGjBv3jxatGhR7msFBQUxY8YM3Nzc8PDwYMKECQwdOhSz2cwPP/xw0zHTpk0jKCgIJycnnnjiCfLz8/Hw8Pit0wJgxowZnD59GrPZjNFoxMXFhQYNGjBz5kxCQ0NL1b333nsYjUYeeughWrRowfLly2nYsCETJ07k+++/L3X9F198ka5du1KnTh169OjB888/z759+8jIyCiuee2117hy5Qpms5mQkBCcnZ1p27YtS5Ys4eLFi5Uyz7I8g7sxN4DCwsLiRjwRqTxFjW+XuWzjJCJVyzrWUYc6PMuzto4iIiIiIiIiVYAa30RERERERET+13fffVdiu0eDwcD48eOr7XGA0NBQdu3axZgxY9izZ0/x9qbHjh0jKCiozM/OaDSW2DqziL+/Pzdu3CApKemm47p06VL+F6qM1qxZA0Dv3r1Lndu4cSOTJ08uUff888+XqHFwcKB79+7k5OTwxRdflLpG586dS3z+8MMPA3DhwoXiY5s2bQKgV69eJWobNWpUoebC8rqbcwPYvn07WVlZdO3aFXgwv4ZE7gY1voncnAULz/EcDjjYOoqIiIiIiIhUAXa2DiAiIiIiIiJSVbRp0+aWK1dV1+P//Oc/6dq1K59++indu3cHIDAwkIiICPr373/TMTdz9epV/v73v7NmzRpSU1O5cuVKifM//vjjTcfVqVOnzPcoj7y8PK5evUrt2rVxcXGpcF2DBg2An7cM/TVXV9cSn9vb2wM/r4JWdO3s7Gxq166Ns7NzqfH169cnOTm57JMqp7s5t1t5EL+GRO4GZ5yxx15bnYr8wjWu8RVfsYhFto4iIiIiIiIiVYRWfBMREbmDlStXFq/qULt2bVvHEREREalUBoOB4cOHs2XLFq5cuUJsbCxWq5UBAwbwzjvvlKq9FZPJxJw5cxg9ejTJycnFW2C+++67QMWahm53vztxcHDA1dWV3NxcsrOzK1xXtA2ol5dXhTK4uLiQm5vLtWvXSp3PyipfQ0t5n8fdnJuI3H11qasV30R+YQMbyCef3pReyVVEREREREQeTGp8ExERuYPBgwdjtVqLV0D5pWvXrvHYY49hNBrLdc2KjhMRERGpbHXr1uXo0aMA1KpVi5CQEGJjYzEYDKxfv75ErZOTEz/99FPx5y1btmThwoUUFBSQkJCAl5cXEydOxNPTs7hJKycnp8LZbnW/sipasW7Dhg2lznXo0IEpU6aUqPv1fPPy8oiPj8fR0bHUVqVlVbTNatGWp0UyMjI4duxYua5VkedxN+cmIndXPeqp8U3kFyxYCCQQd9xtHUVERERERESqCDW+iYhUY87OzgQEBFTb+1UFVquVwsLCm275dLvncbtxIiIiIvfa2LFjOXToEHl5eaSnp/P2229jtVoJDg4uUff444+TnJxMSkoKu3fv5tSpUwQGBlKzZk2CgoJIS0tj3rx5ZGRkkJOTw7Zt2/jwww8rnOtW9yurN998Ex8fH6ZMmcL69evJzs4mNTWVcePGcfHixeLGt6K6yZMnExcXR3Z2NsnJyQwdOpSLFy9iNpuLtwUtr7/97W/Uq1ePyZMns3nzZq5du8bhw4cZNmzYTbc/vZ2KPI+7OTeA4OBg3N3d2bNnT4WvISI354abGt9E/lcBBWxkIyZMto4iIiIiIiIiVYga30RERH4DFxcXTp48edNVRO7GOBEREZHK9tVXX+Hr68vgwYOpV68erVq1YtOmTXz00Ue89tprJWrfe+892rVrR6tWrRg0aBBms5lWrVoBsGrVKiIiIliwYAGNGjXCx8eHqKgohg4dCkBISAidOnViz549GAwG1q5dC4Cjo+Mtt/C83f3KwsvLi3379jFo0CAmTJiAu7s7Xbp04fLly+zYsYMmTZqUqBsyZAgTJ04srrt+/Tpbtmxh9OjRADfNPnPmTODnbUjnzp0L/LyaXNHKvs2bN2f37t107tyZF154gfr16/PHP/6RCRMm0LZtW/Ly8vj/7N15XJV13v/x11Fc2ARFEclKNM0lxwU1nGgiFifUAy7hlpCVYnVrUlNpNc3t3diU5TTRNkpZBhOGR2/BY7kAtghCKZkVmhtpCCiiAm6gwPn90U/uTE3A5WJ5P3ucx3Su63td1/s6PA5D8Dmfj8lkYurUqdWd9n59/smTJ1/29fi9467lvQFUVFRgs9nqNMpWRH6fCt9E/s9GNnKEIyp8ExERERERkfOYbPrNpMg1s2/fPry8vPjqq68YMmSI0XGkCXJycqJ///6kpaU1yutdb4GBgaSlpVFWVlaj9Y399RD5tUceeYRdu3aRmppqdBSRRk0/X4qISFOhny8hnHBKKSWJJKOjiBjuL/yFtawlm2yjo4iIiIiIiEg9oo5vIiINTHl5OX/729/o2bMnDg4OtGvXDrPZzKpVq6isrARgwYIFmEwmTp48SXp6OiaTCZPJhJ2dXfV5KioqSEhIICgoCA8PD+zt7enbty/R0dHnjd881z3i3GPnzp2MGzcONze36m1z5sy57PVq6siRIzzxxBN069aNVq1a0blzZwIDA1myZAmnT5++6LqWLVvStm1bgoOD+eyzzy6Zfd++fYwfPx5XV1fc3NwYOXIke/fuvSDDjz/+yKhRo3BxccHR0ZE777zzosVrvz3/uYK4y73+lzruetybiIiIiIiINAzq+Cbyf6xYCSHE6BgiIiIiIiJSz6jwTUSkgZkxYwZvvPEGb775JkeOHGHHjh307NmT0NBQNm7cCMCTTz6JzWbD0dGRO+64o3r0UEVFRfV51q5dy4QJE/D392fHjh3k5uYSGRnJE088wezZs6vXjRo1CpvNRmhoKADTp0/n0UcfJTc3l8zMTJo3b16j69XEwYMHGTx4MEuXLiU6OpqioiKysrLw8/PjgQceYNGiReeti4+Pr1731Vdf4eDgQEBAAO+9995Fs0dFRREVFUVeXh4JCQls2LCBiRMnnpdhz549DB06lC1btrB8+XIOHTrEO++8w9///vcLCsl+e/5zLvd6XOq4a31vAP7+/ri5uZGZmVmrr42IiIiIiIhcXyp8E/nFdrazm90acyoiIiIiIiIXUOGbiEgDk5qaSp8+fQgKCsLe3p6OHTvy6quv0qNHj1qfy8/Pj2eeeYa2bdvSvn17Zs6cyaRJk4iOjqa0tPSix8yePRs/Pz8cHBy4/fbbqaiooH379ld6WwA888wz/PTTT0RHRzNy5EicnZ3p2LEjf/3rX7nnnnsuWPf6668zcuRI2rRpQ48ePYiPj6dTp0489thjHDp06ILzT506laFDh+Lo6EhgYCAjRoxg8+bNFBUVVa959tlnKS4uJjo6mqCgIJycnOjbty8ffPABBQUFV+U+a/IaXIt7A6iqqqouxBMRERFpqH7d+fZSj7lz5xodU0TkirSlLUc5anQMEcOtYhXuuHM7txsdRUREREREROoZFb6JSIP2ww8/XPAHrhkzZjTa7QD33HMPmzZtIjIykszMzOrxpjt37sTPz6/Gr93IkSPPG515Tr9+/Th79izZ2dkXPW7IkCG1/0LV0MqVKwEIDg6+YN+aNWuIioo6b92IESPOW9OqVSsCAgI4ffo069atu+AcgwcPPu/5jTfeCEB+fn71trVr1wLw5z//+by1np6edSourK1reW8An3/+OUePHmXo0KFA03wPiYiISMN3rpD/9x4qfBORhk4d30R+YcXKSEbSnOZGRxEREREREZF6xs7oACIiV+K22267ZOeqxrr97bffZujQoXz44YcEBAQAcOeddzJ9+nRGjx590WMupqSkhH/+85+sXLmSAwcOUFxcfN7+U6dOXfQ4R0fHGl+jNsrLyykpKaF169Y4OzvXeV3Hjh2BX0aG/paLi8t5z1u2bAn80gXt3LmPHz9O69atcXJyuuB4d3d3du3aVfObqqVreW+X0hTfQyIiIiIiIg1BO9pxmtOUUUZrWhsdR8QQhRTyFV/xFE8ZHUVERERERETqIXV8ExFpYEwmE+Hh4aSkpFBcXExiYiI2m40xY8bw2muvXbD2UsxmM3//+9+ZNm0au3btqh6B+a9//QuoW9HQ713vclq1aoWLiwtlZWUcP368zuvOjQH18PCoUwZnZ2fKyso4ceLEBfuPHq3diJnavh7X8t5EREREGpP9+/cTEhJCaWkpAHv27MFkMvHxxx9Xr3FycrroCNRmzZrRoUMHRo0axebNm426hcu62D2JSNPSlrYA6vomTdpqVmOHHYEEGh1FRERERERE6iEVvomINDCurq78+OOPALRo0YKgoCASExMxmUx88skn5611cHDgzJkz1c9vvfVWYmJiqKysJD09HQ8PDx577DE6dOhQXaR1+vTpOme71PVq6lzHuk8//fSCfQMGDODxxx8/b91v77e8vJzU1FTs7e0vGFVaU+fGrJ4beXpOUVERO3furNW56vJ6XMt7ExEREWkMvv32WwYNGsSwYcNo06bNJdedOHGCrVu3AhAaGlo9AvXYsWPExMSQkZHBHXfcQUpKSq2uf+LECbp3787IkSOv6D5ERC7HFVdAhW/StFmxEkQQTlzYmV9EREREREREhW8iIg3Qww8/zHfffUd5eTmFhYW88sor2Gw2/P39z1s3cOBAdu3aRW5uLhkZGeTk5HDnnXfSvHlz/Pz8OHjwIK+++ipFRUWcPn2azz77jIULF9Y516WuV1MvvfQSXl5ePP7443zyySccP36cAwcO8Oijj1JQUFBd+HZuXVRUFKtXr+b48ePs2rWLSZMmUVBQQHR0dPVY0Nr6xz/+Qbt27YiKiiI5OZkTJ06wfft2Jk+efNHxp7+nLq/Htbw3AH9/f9zc3MjMzKzzOURERESMUlpaitlsZuzYscyYMaNO53BxcWH06NG89tprnD17lqioqFodb7PZqKqquuxI+ZpwcnLC19f3is8jIo2TCy4AHOfSXdFFGrNyykkhBTNmo6OIiIiIiIhIPaXCNxGRBuaLL76gZ8+eTJgwgXbt2tGrVy/Wrl3Lu+++y7PPPnve2tdff50//OEP9OrVi/HjxxMdHU2vXr0ASEhIYPr06bz55pt4enri5eVFbGwskyZNAiAoKIhBgwaRmZmJyWQiKSkJAHt7+0uO8Py969WEh4cHmzdvZvz48cycORM3NzeGDBnCsWPH2LhxIzfddNN56yZOnMhjjz1Wve7kyZOkpKQwbdo0gItm/+tf/wr8MoZ0/vz5wC/d5M517OjWrRsZGRkMHjyYe++9F3d3d6ZMmcLMmTPp27cv5eXlmEwmpk6dWt1p79fnnzx58mVfj9877lreG0BFRUV1txMRERGRhuaVV17h4MGD/O1vf7vic919990AZGdnU1xcXOPjnJ2d2bt370W7FIuIXE1t+KWrZQklBicRMUYyyZzkJCMYYXQUERERERERqadMNv3lW+Sa2bdvH15eXnz11VcMGTLE6DgiIiLXzCOPPMKuXbtITU01OopIo6afL6Ups9lsdOrUiVtuuYW0tLTz9u3Zs4fu3buzdOlSJkyYUL3922+/ZcCAAYSGhpKYmHjeMXl5eXTu3BmA4uJiXFxcrv1N/IaTkxP9+/e/4H7g0vck0lTo50uooooWtOBjPiaMMKPjiFx305nOt3zLV3xldBQRERERERGpp9TxTURERERERETqvW3btnHo0CH69et3wb5bbrkFm81WqwKxzz//HIA+ffrg4uJS3ZX33GPnzp2MGzcONze36m3vvffeeWvKysoALjh23759jB8/HldXV9zc3Bg5ciR79+6tvvaCBQswmUycPHmS9PT06uPs7Oyu6J5EpHFpRjOccKKUUqOjiFx3Nmx8wicacyoiIiIiIiK/S4VvIiIiIiIiIlLv/fDDDwDVXdrqqrS0lJUrV/LEE0/QokULXn/9dQBGjRqFzWYjNDQUgOnTp/Poo4+Sm5tLZmYmzZs3v2DNOb/dHhUVRVRUFHl5eSQkJLBhwwYmTpxYvf7JJ5/EZrPh6OjIHXfcUT2KvqKi4oruTUQaHxdcNOpUmqTNbCaPPEIIMTqKiIiIiIiI1GMqfBMRkWvu190vLvWYO3eu0TFFREREpB4rKCgAqNNI0qSkpOqfO11dXZk2bRo+Pj6kp6cTGBh40WNmz56Nn58fDg4O3H777VRUVNC+ffsaXW/q1KkMHToUR0dHAgMDGTFiBJs3b6aoqKjW2UWkaWtDG3V8kybJipWbuIm+9DU6ioiIiIiIiNRjdpdfIiIicmVsNpvREURERESkgTs3VrRFixa1PjY0NJTExMRaHTNkyJBaX+ecwYMHn/f8xhtvBCA/P7/GxXMiIqCOb9J0rWIVoYRiwmR0FBEREREREanH1PFNREREREREROq91q1bA3D27Nnrcj1HR8c6H/vbrnQtW7YEoKqq6ooyiUjTo8I3aYr2s5/v+A4zZqOjiIiIiIiISD2nwjcRETFM//79azQG9dxj3rx5RkcWEREREYN06tQJgJKSxlMAYjKpi42I/D6NOpWmKIkk2tCGu7jL6CgiIiIiIiJSz6nwTUREDGWxWLDZbNWP6dOnA7BmzZrzto8fP97gpCIiIiJipNtuuw2AAwcOGJzk6nFwcODMmTPVz2+99VZiYmIMTCQi9Y06vklTZMVKMMG0pKXRUURERERERKSeU+GbiIiIiIiIiNR7/fr1w93dnW3bthkd5aoZOHAgu3btIjc3l4yMDHJycrjzzjuNjiUi9YgLLur4Jk1KCSV8yZcacyoiIiIiIiI1Ymd0ABERabq+/fbbGq/9+OOPr2ESEREREanvTCYTU6dO5ZVXXiE/Px9PT8/fXe/k5MTJkycBSEpKwmQyceutt/Ljjz9edH1mZiZDhw6tfm5vbw+AzWar3paYmMjo0aPPW3PfffcxY8aMC4597rnnmDdv3nnjTAcMGMCIESNYvXo1AK+//jrTpk2jV69etGvXjujoaHr16lXTl0REmoA2tFHHN2lS1rCGSiq5h3uMjiIiIiIiIiINgArfRERERERERKRBePrpp/nwww954YUXWLhw4e+uPXHiRK3O7ePjc16R28WMGjXqkmtqux1+GW365Zdf1jykiDQ5GnUqTY0VK3/iT7jhZnQUERERERERaQA06lRERBqMxMRETCZT9WPnzp2MGzcONze36m1RUVHV/+7r61t97Nq1a6u3t2/f/oJzHz58mMcee4wuXbrQsmVLOnTowJgxY2rVlU5EREREri0XFxesVivLly/n7bffNjqOiMg114Y2GnUqTUYFFaxhjcacioiIiIiISI2p8E1ERBqMcx02QkNDAZg+fTqPPvooubm5ZGZm0rx5c/76179is9lwdHQ879h77rkHm82Gt7f3BectKChg8ODBLFu2jHfeeYejR4/y+eefc/ToUYYOHUpGRsZ1uT8RERERubwBAwawZcsW1qxZQ2mpikFEpHFzwYVTnOIsZ42OInLNfcmXHOMYIxlpdBQRERERERFpIFT4JnId/OUvf+Gtt94iNzfX6Cgijcrs2bPx8/PDwcGB22+/nYqKiot2c7ucZ555hv379/Paa68xfPhwnJyc6NOnDx9//DE2m42ZM2deg/QiDV9VVRXp6ek8/fTTJCYmGh1HRESakC5durB69WratGljdBQRkWvKBRcAdX2TJsGKlT70oTvdjY4iIiIiIiIiDYQK30SuIU9PT+Lj4/H09OTZZ5/l5ptvZtCgQcybN48ffvjB6HgiDd6QIUOuynkSExNp1qwZI0ee/4liDw8P+vTpQ1ZWFgcOHLgq1xJp6MrKyvjkk0+IjIzE09MTX19fVq5cSXh4OPPnzzc6noiIiIhIo9KGXwp8SygxOInItbea1YQQYnQMERERERERaUDsjA4g0pi1bNmSiRMnMnHiRCoqKsjMzMRisfDvf/+b559/ni5duhASEoLZbMbPzw87O70lRWrjt+NM66K8vJySkl/+gODi4nLJdbt376Zz585XfD2RhujkyZNs2LABi8VCUlISpaWl9O7dm4cffhiz2XzREcIiIiIiInLl1PFNmoof+IE97MGM2egoIiIiIiIi0oCo45vIdWJnZ4evry/R0dHk5uayZcsW7r//fpKTkwkKCsLDw4OIiAgsFgsnTpwwOq5Ig9esWTPOnDlzwfbi4uLznrdq1QpXV1fs7Ow4e/YsNpvtoo+77777ekUXqRcOHz5MbGwsZrOZdu3aMXr0aHJycnjhhRf4+eefyc7OZu7cuSp6ExGRGtm/fz8hISGUltbfwo09e/ZgMpn4+OOPa3XcggULMJlMmEymBvFBiU8//ZQePXr87gevLvZazJkzh4SEhIuu/719InJl1PFNmopVrMIdd27ndqOjiIiIiIiISAOiwjcRAzRr1gxvb2/mzp3L9u3b2bt3L88//zw5OTmMHz8ed3d3zGYzMTExFBYWGh1XpEHq1KkTeXl55207ePAgP//88wVrx4wZQ0VFBenp6Rfsmz9/PjfddBMVFRXXLKtIfZGTk0N0dDS+vr507NiRRx55BIA333yT/Px80tLSmDVrFjfeeKPBSUVEpCH59ttvzMLDUwAAIABJREFUGTRoEMOGDaNNmzZGx7nqnnzySWw2G/369TM6yu/au3cvISEhPPPMMxw6dKjWx0+bNo1nnnmG559/vlb7ROTKnOv4psI3aeysWDFjppn+ZCEiIiIiIiK1oP+KFKkHunbtyqxZs0hLS+PQoUMsXLgQgJkzZ+Lp6Ymvry/z589nz549BicVaTiGDRtGfn4+b731FidOnGDv3r3MmjULd3f3C9a+9NJLdOvWjQcffJA1a9ZQUlLC0aNHWbRoES+88AILFizQKGJplKqqqsjKymLu3Ln07t2bbt268fe//52uXbuSkJBAYWEhVquVyMjIi753RERELqe0tBSz2czYsWOZMWPGdbuuk5MTvr6+1+16DcHzzz/PH//4R7KysnB2dq718d26dWPlypW8+OKLLFu2rMb7ROTKtPr//2jUqTRmhRTyNV9rzKmIiIiIiIjUmgrfROqZDh06EBERgdVq5ejRo6xcuZKuXbvy0ksv0b17d/r06cPcuXPJysoyOqrIVbVkyRJMJhOLFi0CIDg4GJPJdN7o38zMTEwmE0lJSQDY29tjMpkuer558+YxdepU/vGPf+Du7s6UKVN46qmn8PDw4MiRI5hMJubMmQOAu7s7X3/9NaNGjWLGjBl06NCBnj178r//+78kJSUxbty4a3z3ItdPWVkZKSkp1Z3bBg0aRGxsLEFBQSQnJ3Pw4EFiY2MJCwvD0dHR6LgicglffPEFp0+fNjqGyGW98sorHDx4kL/97W9GR2nyFi9ezJw5c67oAx39+vXj3nvv5S9/+csFHZF/b59Ibe3bt48dO3YYHaPecMFFHd+kUVvFKlrRikACjY4iIiIiIiIiDYwK30TqMUdHR8xmM7GxsRQVFbFx40YCAwN59913GTRoEF5eXsyaNYuUlBT9YUEavClTpmCz2S54ODk5Va/x8fG56JqLcXFx4d133yU/P59Tp06xceNGBg0axJYtW6qPe/nll6vXt2vXjn/+85/s3buXM2fOUFhYyLp16wgM1C9dpeE7efIkVquViIgIOnbsSFBQECkpKUybNo0tW7ZUjzgNDAxUd0OReq5t27aEhoby3HPP4enpySOPPMLXX39tdCyRi7LZbLz33nvcfvvteHp6Gh2nybO3t78q5xk9ejQHDhzgk08+qdU+kcs5ffo0H330EYGBgXTr1o2dO3diNqv7E0Ab2qjjmzRqq1lNAAE4og9fiYiIiIiISO2o8E2kgbCzs8PX15fo6Ghyc3PZsmUL999/PykpKQQFBeHh4UFERAQWi+W8DlkiItI0FRYWEhsbi9lspl27dowePZqcnBxeeOEFcnNzyc7OZu7cuXh7exsdVURqwcXFhcTERA4dOsT8+fPJzMzk9ttvp1evXsyfP59Dhw4ZHVEaiCNHjvDEE0/QrVs3WrZsSdu2bQkODuazzz6rXpOYmIjJZKp+7Ny5k3HjxuHm5la9raio6JLX2LZtG4cOHaJfv37nbf/tefft28f48eNxdXXFzc2NkSNHsnfv3jplXrBgASaTiZMnT5Kenl59jZoUdt9yyy3YbDYmTJhQva28vJy//e1v9OzZEwcHB9q1a4fZbGbVqlVUVlZe9pwAhw8f5rHHHqNLly60bNmSDh06MGbMGL799ts6rT13jyaTic6dO7N582YCAgJwdnbGwcGBu+++m/T09Bplq81rcU7//v0BWLduXa32iVxKVlZWdTfi+++/H5PJxMcff8zPP/9MVFSU0fHqBXV8k8bsNKdJJplQQo2OIiIiIiIiIg2QCt9EGqBmzZrh7e3N3Llzyc7OZu/evTz//PPk5OQwfvx43N3dMZvNxMTEUFhYaHRcERG5Ts51bvP19cXDw4NHHnkEgHfffZeioiLS0tKYNWsWnTt3NjipiFyptm3bEhkZydatW9myZQvDhg3j1Vdf5YYbbiAoKAiLxcLZs2eNjin11MGDBxk8eDDx8fFER0dTVFTEV199hYODAwEBAbz33nsAjBo1CpvNRmjoL3+Inj59Oo8++ii5ublkZmbSvHnz373ODz/8AHDB/+/89rxRUVFERUWRl5dHQkICGzZsYOLEiXXK/OSTT2Kz2XB0dOSOO+6o7vRb1w7ZM2bM4I033uDNN9/kyJEj7Nixg549exIaGsrGjRsve3xBQQGDBw9m2bJlvPPOOxw9epTPP/+co0ePMnToUDIyMmq99tw99uvXj+LiYmbNmsW8efM4ePAgX375JUePHsXf358vvviiTvd8OTfccAPwf1/fmu4T+bVjx44RExPDgAEDGDRoEOvXr+epp54iLy+P5ORkwsLCaNGihdEx6w0XXNTxTRqt9aynjDJGMtLoKCIiIiIiItIAmWyXmhEnIg3S4cOHWbNmDRaLhfXr11NZWYmPjw9ms5mxY8dyyy23GB1RRESukqqqKrZu3YrVamXZsmXs2LGD9u3bExwcjNlsZvjw4Tg6alSMSFNRXl7OqlWriI2NZc2aNXTo0IFx48bx4IMPXtBxS5q2Bx54gCVLlrB06dILupt17dqVY8eO8dNPP9GxY0fgl0K1pKQkPv30U4KDg2t8nVdffZWnn36at99+m0cfffSC/efOa7VaGTny//7YHRYWxvLlyzl8+DDt27evU2YnJyf69+9PWlpa7V6c3+jatSudOnW6oIParbfeyqJFi/Dz86ve1r9/f4qKijhw4ED1tilTpvDhhx/y0UcfMWnSpOrtBw8epEuXLtx2221s2bKl1mvPXW/btm1s3bq1utMawPfff88f/vAH+vXrd9GucvBLMeLBgwfrXBDYrFkzunXrxu7du2u1T5q2yspKPvvsM2JiYkhMTMTBwYGQkBAiIiIIDAw0Ol69NprROODAR3xkdBSRq+5BHmQnO0nnyrqVioiIiIiISNOkjm8ijUyHDh2IiIjAarVy9OhRVq5cSdeuXXnppZfo3r07ffr0Ye7cuWRlZRkdVURE6qCsrIyUlJTqcVCDBg0iNjaWoKAgkpOTKSgoIDY2lrCwMBW9iTQxrVq1IiwsDKvVyr59+4iKimL16tX079+fQYMGER0dzdGjR42OKfXAypUrARgxYsR521u1akVAQACnT5++6KjKIUOG1Oo6ZWVlAJft2jR48ODznt94440A5OfnX3HmK3XPPfewadMmIiMjyczMrB5vunPnzvOK3i4lMTGRZs2anVfYB+Dh4UGfPn3IysqqLpSrzdpzHB0dzyt6A+jbty+enp5s27aNgoKC2t5yjdjZ2XH69Ola75Om6ccff2TOnDl07tyZP//5z+Tn5/PWW2+Rl5dHbGysit5qwAknTnLS6BgiV10VVXzKpxpzKiIiIiIiInWmwjeRRszR0RGz2UxsbCxFRUVs3LiRwMBA3n33XQYNGoSXlxezZs0iJSWlzp/0FxGRa6+4uBiLxUJERAQdO3YkKCiIlJQUpk2bxpYtW6pHnAYGBmJnZ2d0XBGpBzp37szs2bPZvXs3GzduxNvbm+eee44bbriBcePGkZKSgpp/N03l5eWUlJTQunVrnJ2dL9h/rmPawYMHL9hX24Lq1q1bA1x27K6Li8t5z1u2bAn80tn0SjNfqbfffpvY2FhycnIICAigTZs23HPPPdWFeL/nXO6qqipcXFwwmUznPb755hsAdu/eXau1v+bq6nrRa7u7uwNQWFh4Jbd/SRUVFdjb29d6nzQdpaWl1R/O6N27Nx999BH3338/u3fvJi0tjcjISH1IoxaccOIEJ4yOIXLVpZPOIQ6p8E1ERERERETqTIVvIk2EnZ0dvr6+REdHk5uby5YtW7j//vtJSUkhKCgIDw8PIiIisFgsnDihX6aKiBitsLCQ2NhYzGYzHTt2ZOLEieTk5PDCCy+Qm5tLdnY2c+fOxdvb2+ioIlKPNWvWDF9fXxYtWkR+fj6LFi3i2LFjBAUFcdNNNzFnzhxycnKMjinXUatWrXBxcaGsrIzjx49fsP/QoUPAL13GrlSnTp0AKCkpuaLz1CWzyWS6omv++jzh4eGkpKRQXFxMYmIiNpuNMWPG8Nprr102t6urK3Z2dpw9exabzXbRx913312rtb925MiRixaxnit4O1cAdzWVlpZis9mqv7413SeNn81mIy0tjenTp+Pp6cn06dNp27YtSUlJ7Nu3j5dffpmuXbsaHbNBUuGbNFZJJNGd7tzKrUZHERERERERkQZKhW8iTVCzZs3w9vZm7ty5ZGdns3fvXp5//nlycnKYMGEC7u7umM1mYmJirlmHABERudC5zm2+vr54eHjwyCOPAPDuu+9SVFREWloas2bNonPnzgYnFZGGqE2bNkRERJCcnMyOHTu47777WLJkCd27d8fX15eYmBhOntQYtaZg9OjRAHzyySfnbS8vLyc1NRV7e3v+/Oc/X/F1brvtNoALxnPWRW0zOzg4cObMmernt956KzExMbW+rqurKz/++CPwy8jWoKAgEhMTMZlMF2S5mDFjxlBRUUF6evoF++bPn89NN91U3X27NmvPKSsrY/Pmzedt+/7778nPz6dfv37XpAAtLy8P+L+vb033SeOVl5fH/Pnz6d69O3feeSdZWVm8+OKLHDhwgGXLlmE2m2nevLnRMRs0RxxV+CaNkhUroxltdAwRERERERFpwFT4JiJ07dqVWbNmkZaWxsGDB1m4cCEAM2fOxNPTE19fX+bPn8+ePXsMTioi0rhUVVWRlZXF3Llz6d27N926dWPevHl07dqVhIQECgsLsVqtREREXHKUmYhIXfTs2ZOXX36ZvLw81q1bh6enJzNmzOCGG25g+vTppKWlGR1RrqGXXnoJLy8voqKiWL16NcePH2fXrl1MmjSJgoICoqOjq8eHXol+/frh7u7Otm3brnvmgQMHsmvXLnJzc8nIyCAnJ4c777yzTtd++OGH+e677ygvL6ewsJBXXnkFm82Gv79/jXJ369aNBx98kDVr1lBSUsLRo0dZtGgRL7zwAgsWLKgeU16btee4uLjw7LPPkpGRwcmTJ9myZQuTJ0+mZcuWREdH1+l+L+fbb78FYNiwYbXaJ41LeXk5FosFs9nMzTffzCuvvEJAQABbt25ly5YtzJo1Czc3N6NjNhrq+CaN0Xa2s4tdGnMqIiIiIiIiV8Rku9hMDBER4OTJk2zYsAGLxcKqVasoKSmhd+/ehIWFYTabNV5PRKQOysrKSEtLw2q1snz5cvLz8/Hy8sJsNmM2m/Hz87vgj9oiItfD0aNHWb58Oe+88w7btm2jV69e3H///TzwwAPXZFyiGOvIkSPMmzePpKQkDhw4gIODAz4+Pjz99NPVBV2ZmZkMHTr0gmNr82uE5557jldeeYX9+/fj6el5yfM+99xzzJs374IRpSNGjGD16tU1znzOzp07mTZtGt988w3t2rVjzpw5PProozXOfc62bdv497//zZdffsn+/ftp3bo1PXr04KGHHuKhhx7CZDKxYMECnnrqqYveD/zy3nrxxRdJTEwkNzcXV1dXBgwYwFNPPUVgYOB5x9Vmbf/+/SkqKiI5OZnHH3+cTZs2UVFRwZAhQ3jxxRe54447zlu/evVqzGbzRe/z3XffZerUqTV6TcaNG8emTZv46aefaNGiRY33SeOQnZ1NXFwcixcv5tixY9x9991ERkYyatQofc2voX/zb57neYooMjqKyFXzEi/xOq+TTz7NUVdIERERERERqRsVvolIjVRUVJCZmYnFYmHFihXk5eXRpUsXQkJCVKghInIZxcXFJCcnY7VaSUpKorS0VIXEIlKvZWVlERsby0cffURxcbEKG6TOSkpK6NOnDyNHjqzuLC1Xx7nCt6sxSramtm3bxoABA4iPj2fChAk13icN27Fjx7BYLCxcuJCtW7fSs2dPpkyZwpQpU65Kd0i5vDjimMY0yigzOorIVeODD7dxG+/xntFRREREREREpAFT4ZuI1FpVVRVbt27FarVisVjYvn07bm5uDB8+HLPZTHBwME5OTkbHFBExVGFhIWvXrsVisbB+/XoqKyvx8fEhLCyMsWPH0rlzZ6MjiohcVllZGVarlZiYGFJTU+nYsSPjxo3joYce4g9/+IPR8aSB2Lp1K0FBQfzP//wP//Vf/2V0nEbjehe+5eTkEBQUxIQJE3jxxRdrvE8apqqqKjZs2EBMTAxJSUm0bt2a0NBQIiIiCAgIuKA7o1xbK1nJGMZwhjO0QAXo0vAd4hCeeJJIImYu3o1UREREREREpCZU+CYiVywnJ6e6CC4jI4NWrVoREBCA2Wxm1KhRGo0lIk3Gr78fbtq0CXt7e/z9/QkLCyMkJARXV1ejI4qI1NmBAwf46KOPiImJIScnB29vb8LDwwkPD6ddu3ZGx5N6bt++fcyYMYP4+HjatGljdJxG4XoXvs2ePZsBAwZctJvb7+2ThmXnzp0sXbqUDz74gAMHDjB06FAiIiK47777cHR0NDpek5VMMsMYxjGO4Yr+m0IavhhieJzHOcxhHHAwOo6IiIiIiIg0YCp8E5Gr6vDhw6xZswaLxUJycjIVFRX4+PhgNpsZM2YM3bt3NzqiiMhV8+sOmMuWLWPHjh20b9+e4OBgzGYzw4cP1x8IRaTRqaqqYtOmTcTFxfHRRx9RWVmJ2WwmMjJSXYBEroMFCxbw1FNPnbftueeeY968eQYlkoautLSUxMRE4uLiSE1NxdPTk8mTJzNt2jS6detmdDwBMsjgj/yRXHLpjDpHS8M3ghG0pCUrWWl0FBEREREREWngVPgmItfMqVOnSE1NxWKxsGrVKkpKSujduzdhYWGYzWa8vb2NjigiUmtlZWWkpaVhtVpZvnw5+fn5eHl5YTabMZvN+Pn5YWdnZ3RMEZHroqSkhISEBGJjY0lPT+fGG29k0qRJTJ8+HS8vL6PjiYjI78jKyiImJob4+HjOnj1LSEgI4eHhDB8+nObNmxsdT37lO76jH/3YwQ560tPoOCJX5AQn6EAH/s2/mcIUo+OIiIiIiIhIA6fCNxG5LioqKsjMzMRisbBixQry8vLo0qULISEhKhQRkXqvuLiY5ORkrFYrSUlJlJaWqpBXROQ3duzYwYcffsiSJUs4fPhw9Xi8yZMn4+CgEVYiIvVBXl4e//nPf3jvvffYs2cPvXv3JiIigoceeoj27dsbHU8uIYccutGNzWxmEIOMjiNyRVawgvGMp4ACOtDB6DgiIiIiIiLSwKnwTUSuu1+PBrRYLGzfvh03NzeGDx+O2WwmODgYJycno2OKSBNXWFjI2rVrsVgsrF+/nsrKSnx8fAgLC2Ps2LF07qwRQyIiF1NZWclnn31GTEwMiYmJODg4MH78eMLDw/H19TU6nohIk1NeXs6qVauIjY1l7dq1ODs7ExYWxiOPPEL//v2Njic1UEghHenIZ3yGH35GxxG5IhFEsI99fMmXRkcRERERERGRRkCFbyJiuJycnOoiuIyMDFq1akVAQABms5lRo0bh7u5udEQRaSJ+/f1o06ZN2Nvb4+/vT1hYGCEhIbi6uhodUUSkQTl48CAJCQm8//77fPfdd9WdhR544AH9jCcico1lZ2cTFxfH4sWLOXbsGHfffTeRkZGEhobSsmVLo+NJLZziFI44YsXKSEYaHUekziqpxAMP5jCHv/AXo+OIiIiIiIhII6DCNxGpVw4fPsyaNWuwWCwkJydTUVGBj48PZrOZMWPG0L17d6Mjikgj8usOlMuWLWPHjh20b9+e4OBgzGYzw4cPx9HR0eiYIiKNQlZWFrGxsfznP//hxIkTDBs2jIiICEaNGkWLFi2Mjici0igcO3YMi8XCwoUL2bp1K7feeisTJkzgwQcf5KabbjI6ntSRDRstaMFHfMR4xhsdR6TOPudz7uZudrKTHvQwOo6IiIiIiIg0Aip8E5F669SpU6SmpmKxWFi1ahUlJSX07t2bsLAwzGYz3t7eRkcUkQaorKyMtLQ0rFYry5cvJz8/Hy8vL8xmM2azGT8/P+zs7IyOKSLSaJWVlWG1WomJiSE1NRUPDw/CwsKYOnUqffv2NTqeiEiDU1VVxYYNG4iJiSEpKYnWrVsTGhpKREQEAQEBmEwmoyPKVdCGNvyLf/EQDxkdRaTOHudx1rOebLKNjiIiIiIiIiKNhArfRKRBqKioIDMzE4vFwooVK8jLy6NLly6EhISoUEVELuvYsWOkpKRgtVpJSkqitLRUhbQiIvVAbm4u8fHxLFq0iJ9++glvb28iIyOZOHEizs7ORscTEanXdu3aRXx8PEuWLGH//v3V30MnTZqEk5OT0fHkKvPEk9nMZhazjI4iUmfd6MZ4xvMP/mF0FBEREREREWkkVPgmIg1SdnY2FosFi8XC9u3bcXNzY/jw4ZjNZoKDg/VLfhGhsLCQtWvXYrFYWL9+PZWVlfj4+BAWFsbYsWPp3Lmz0RFFROT/q6qqYtOmTcTFxfGf//yHqqoqzGYzkZGR6lYkIvIrp0+fZvXq1dVdMz09PZk8eTJTp07llltuMTqeXEM96MH93M9zPGd0FJE6+Z7v+QN/IJNMbud2o+OIiIiIiIhII6HCNxFp8HJycrBarVgsFjIyMmjVqhUBAQGYzWZGjRqFu7u70RFF5Dr59feDTZs2YW9vj7+/P2FhYYSEhODq6mp0RBERuYySkhISEhKIjY0lPT2dG2+8kUmTJvHwww/TpUsXo+OJiBgiKyuLmJgY4uPjOXv2LCEhIYSHhxMcHKzu503EQAZyD/eoU5Y0WPOYx1u8RT75NKOZ0XFERERERESkkVDhm4g0KocPH2bNmjVYLBaSk5OpqKjAx8cHs9nMmDFj6N69u9ERReQqqqqqYuvWrVitVpYtW8aOHTto3749wcHBmM1mhg8fjqOjo9ExRUSkjrZv305sbCwffPABRUVF+Pv7Ex4ezr333ouDg4PR8URErqn8/Hzi4uJ477332LNnD7179yYiIoKHHnqI9u3bGx1PrrM/8Sf60583eMPoKCJ1MpjBDGQgi1hkdBQRERERERFpRFT4JiKN1qlTp0hNTcVisbBq1SpKSkro3bs3YWFhmM1mBg4cqLFZIg1QWVkZaWlp1Z3dCgoK8PLywmw2Yzab8fPzU9cLEZFG5syZM6xbt464uDgSExNxdHRk3LhxhIeH4+vra3Q8EZGrpry8nPXr1xMXF8fKlStxdnYmLCyMhx9+mAEDBhgdTwwUTDCd6MT7vG90FJFayyOPG7mR1axmOMONjiMiIiIiIiKNiArfRKRJqKioIDMzE4vFwooVK8jLy6NLly6EhISoUEakATh27BgpKSlYrVaSkpIoLS09r5DV29vb6IgiInKdFBQUsGzZMhYvXsz3339f3QHpwQcfpEOHDkbHExGpk+zsbOLi4nj//fc5cuQI/v7+REZGEhoaSsuWLY2OJ/VAGGGYMLGMZUZHEam1d3iH2czmMIdpTWuj44iIiIiIiEgjosI3EWmSsrOzsVgsWCwWtm/fjpubG8OHD8dsNhMcHIyTk5PREUWavMLCQtauXYvFYmH9+vVUVlbi4+NDWFgYY8eOpXPnzkZHFBERg2VlZRETE8PSpUspLy9n2LBhREREMHr0aH2oQUTqveLiYpYtW8aiRYv45ptv6NGjBxMnTuSBBx7g5ptvNjqe1DMP8ACHOMSnfGp0FJFa+zN/xhlnlrPc6CgiIiIiIiLSyKjwTUSavJycnOqRiRkZGbRq1YqAgADMZjOhoaF07NjR6IgiTcav34+bNm3C3t4ef39/wsLCCAkJwdXV1eiIIiJSD5WVlWG1WomJiSE1NRUPDw/CwsKYOnUqffv2NTqeiEi1qqoqNmzYQGxsLMuX/1IAMnLkSCIjIwkICMBkMhmcUOqrmczkO77jC74wOopIrRznOB3owLu8SzjhRscRERERERGRRkaFbyIiv3L48GHWrFmDxWIhOTmZiooKfHx8MJvNjBkzhu7duxsdUaRRqaqqYuvWrVitVhISEvjxxx9p3749wcHBhIWFMWzYMFq1amV0TBERaUByc3OJj49n4cKF7Nu3D29vbyIjI5k4cSLOzs5GxxORJmrXrl3Ex8ezZMkS9u/fX/29adKkSeo4LjXyDM+wnvVkkWV0FJFaSSCB+7iPQxzCDTej44iIiIiIiEgjo8I3EZFLOHXqFKmpqVgsFlatWkVJSQm9e/cmLCwMs9nMwIED9Wl8kTooKysjLS2turNbQUEBXl5emM1mzGYzfn5+Gk8nIiJX7NddlVasWIHNZlNXJRG5rk6fPs3q1auru1F26tSJ8PBwpk6dyi233GJ0PGlg5jGPOOLYyU6jo4jUyiQmcZCDbGCD0VFERERERESkEVLhm4hIDVRWVpKRkYHFYmHFihXk5eXRpUsXQkJCMJvN3HXXXbRo0cLomCL11rFjx0hJScFqtZKUlERpael5haTe3t5GRxQRkUasuLiYZcuWERsbS3p6Ot27d2fSpElMmTKFLl26GB1PRBqZrKwsYmJiWLp0KWfOnCEoKIiIiAhGjx6tD3hInS1gAW/yJvvZb3QUkRo7y1k60pH/5r+ZxSyj44iIiIiIiEgjpMI3EZE6yM7OxmKxYLFY2L59O25ubgwfPhyz2UxwcLBG1YgAhYWFrF27FovFwvr166msrMTHx4ewsDDGjh1L586djY4oIiJN0Pbt24mNjeX999/nyJEj+Pv7Ex4eTlhYGPb29kbHE5EGKj8/n7i4OBYvXszu3bvp3bs3ERERPPjgg3To0MHoeNIIvM3b/A//QyGFRkcRqbEUUggiiBxy8MLL6DgiIiIiIiLSCKnwTUTkCuXk5FSPbMzIyKBVq1YEBARgNpsJDQ2lY8eORkcUuW5+/X7YtGkT9vb2+Pv7ExYWRkhICK6urkZHFBERAeDMmTOsW7eOuLg4Vq5ciZOTE+PGjWP69OkMHDjQ6Hgi0gDo+4hcT4tZTBRRHOe40VFEamwmM/mSL9nGNqOjiIiIiIiISCMZ6zY6AAAgAElEQVSlwjcRkasoPz+fVatWkZiYyGeffUZVVRV33XUXISEhdOrUyeh4IteEzWZj8+bNJCYmsmfPHjw8PAgJCWHUqFH4+/vTqlUroyOKiIj8roKCApYtW8bixYv5/vvv1alJRH5XdnY2cXFx6hwp11U88UQQQQUVRkcRqTEvvAgnnBd4wegoIiIiIiIi0kip8E1E5BopKSlhzZo1JCYmsmbNGkpLS6/p9do7w2wzPLcMzuj34E3OX4bDuu/ghwPGXL9Hjx6MGjWK0NBQfHx8aNasmTFBRERErlBWVhYxMTEsXbqUM2fOEBQUREREBKNHj8bOzs7oeCJikOLiYpYtW0ZsbCzp6en06NGDiRMn8sADD3DzzTcbHU+agJWsZAxjOMMZWtDC6Dgil7WVrQxkIFvYgjfeRscRERERERGRRkqFbyIijcGZY5AaAGdLYFg6tPYwOpFcT1VnYUMgnPgJhmWAww1GJxIREWnwTp8+zerVq4mJiSE1NZVOnToRHh7OQw89RPfu3Y2OJyLXQVVVFRs2bCA2NpYVK1Zgs9kYOXIkkZGRBAQEYDKZjI4oTcha1hJMMKWU4oyz0XFELmsuc3mP98glFxP6fikiIiIiIiLXhgrfREQauoqT8Nk9cHIfBH4JTl5GJxIjnC2B5D+BrRKC0qClq9GJREREGo3du3fzxro3+I/tPxQ/Voy3tzeRkZFMmjQJJycno+OJyFWWm5tLfHw8CxcuZN++fdXv+YkTJ+LsrIIjMcbnfM7d3M0hDuGOu9FxRC5rAAP4I3/kbd42OoqIiIiIiIg0YppDJiLSkFWcgs9HwPFd4J+soremrIUL+H0KZ0th42ioKjc6kYiISKNxqPshls5YSq+ZvVi9YTW9e/cmKioKd3d3xo0bR0pKCvpMmUjDVlZWhsViISgoiJtvvpk33niD8ePHs2vXLrZs2UJkZKSK3sRQ9tgDcJrTBicRubyf+ZltbCOUUKOjiIiIiIiISCOnwjcRkYaq6gyk3Qsl2yFgA7TpaXQiMZrDDb8Uvx37FjKmgK3K6EQiIiIN3gpWMIxh3MmdpJDCiLtHEBsbS35+Pq+//jo5OTkEBQXRs2dP5s6dy/79+42OLCK1kJWVxfTp03F3d2fy5Mm0bt2ahIQE9u/fz8svv6zRxlJvnCt8K6PM4CQil5dEEs4444ef0VFERERERESkkdOoUxGRhqjqLGwcA4UbISAV2nkbnUjqk0OfwWfB0DMK+r9sdBoREZEGK5ponuAJZjCDf/Evml3is2PZ2dnExcXx/vvvc+TIEfz9/QkPDycsLAx7e/vrnFpELqegoIBly5axePFivv/+e3r37k1ERAQPPvggHTp0MDqeyEXtYhe3citb2Up/+hsdR+R3BRJIe9rzMR8bHUVEREREREQaORW+iYg0NLZK2HQf5K/5Zbyp2xCjE0l9tH8ppN8H3q/DrY8ZnUZERKRBqaSSKKJ4m7d5iZeYzewaHVdeXs769euJi4tj5cqVODs7ExYWxvTp0xk4cOA1Ti0iv+fMmTOsW7eu+v3p5OTEuHHjCA8Px9fX1+h4IpeVSy43cROb2MRQhhodR+SSSijBHXeWsISJTDQ6joiIiIiIiDRyKnwTEWlIbFWQEQEHVv4y0tL9LqMTSX2W/Q/47nnwtcCNY4xOIyIi0iCc4hQTmcg61vEhHzKe8XU6T35+PnFxcSxevJjdu3dXd5R66KGHaN++/VVOLSKXsn37dmJjY/nggw8oKiqq7sh477334uDgYHQ8kRoroogOdCCVVPzxNzqOyCXFE88UpnCIQ7SlrdFxREREREREpJFT4ZuISINhg68fhpwP4a5E6HSP0YGkIdgyE/Yu/qU7YIc7jE4jIiJSrxVSiBkzOeSQRBJ/5I9X5bxZWVnExMQQHx/P2bNnCQkJITw8nODgYOzs7K7KNUTk/5SUlJCQkEBsbCzp6encdNNNTJw4kYcffpguXboYHU+kTk5yEiec+IRPGM5wo+OIXNJ4xnOUoySTbHQUERERERERaQKaGR1ARERqwgabZ0DOErhzuYrepOa8XwfPe+DLUCjdaXQaERGReusAB7iLuzjCETax6aoVvQF4e3uzaNEiCgsLiYuL49ixY4SGhtKlSxfmzJnDnj17rtq1RJqqqqoqUlJSiIiIwNPTk1mzZuHp6UlycjL79u3j5ZdfVtGbNGitaQ3AaU4bnETk0sopZy1rCSXU6CgiIiIiIiLSRKjjm4hIQ/DtHNixAO6Ih5vGGZ1GGprK05AaCGUFMGwTtPYwOpGIiEi9so99BBJIS1qSTDI3cMM1v+auXbuIj49nyZIl7N+/H29vbyIjI5k0aRJOTk7X/PoijUVubi7x8fEsWrSIn376qfq9NHHiRJydnY2OJ3JVtaQl7/M+k5lsdBSRi1rLWoIJ5id+ogtdjI4jIiIiIiIiTYAK30RE6rvvnofsl2BoLHSZZHQaaajKiyDZF+ycIPDzX/5XRERE+JEfCSSQjnRkHetoT/vrev2qqio2bNhAbGwsy5cvp0WLFoSGhhIREUFAQAAmk+m65hFpCMrKyrBarcTExJCamoqHhwdhYWFMnTqVvn37Gh1P5JpxwYV/8k+mMtXoKCIX9QiP8BVf8Q3fGB1FREREREREmgiNOhURqc9+fA1+eBEG/1tFb3JlWrUHv0/h1AFIGwe2CqMTiYiIGO4bvuFP/AkvvNjAhute9AbQrFkzAgMDiY2NJS8vj1dffZXs7GyCgoLo1asXc+fO5eeff77uuUTqo6ysLGbNmsUNN9zA5MmTad26NQkJCfz8889ER0er6E0aPXvsNepU6i0bNlazWmNORURERERE5LpS4ZuISH218w345kkY/BbcMs3oNNIYOHUFv9VQuBG+ftjoNCIiIob6mq8JIojbuI01rMEFF6Mj0bZtWyIjI8nKyuKHH35g1KhRvP3223h5eREUFITFYuHMmTNGxxS5rgoKCoiOjqZfv34MGjSIlJQUnn76aXJzc7FarYSFhWFnZ2d0TJHrQoVvUp9tYQsHOKDCNxEREREREbmuNOpURKQ+2vs+fDUV+r8MvZ82Oo00NvmfwhehcNtfoe9/G51GROT/sXfnYVXXef/Hn+yKiqKCaCq4IMqi5Zpbbqi5L0mpuZUW3TXTak3dU07N/KbFynKmTWtuTWfK1FFALBfcFTUXUMEFN9RUFBdAVGQ7vz/IMzIugQKfc+D16OLKjPQJR887z/fN9yNS5taylsEMpjvdmc98KlHJdNJtZWVlERERwaxZs4iJiaFWrVqMGTOG8ePH07BhQ9N5IqXCYrGwdu1aZs2axbJly/Dw8GD06NE88cQTtG7d2nSeiDEtaMFIRvIn9Oc4sT1v8iZzmUsyyTigo9pFRERERESkbGjxTUTE1hydA1uegJZ/hqA/mq6R8urwN7D1aejwDTR50nSNiIhImYkiikd5lDDCmMUsnLGfO0WdOHGCb7/9ltmzZ3P48GHTOVIUnsAwYB5wxXCLnXF0dKR379488cQTDB06FDc3N9NJIsa1pjV96ct7vGc6ReQmIYTQgx78jb+ZThEREREREZEKRItvIiK25MS/YeNICHodWv7FdI2Ud7vfgsT3oOsiqD/YdI2IiEipW8pShjOcJ3iCL/gCRxxNJ90Vi8XCtm3byMjIMJ0iv+Gk+0kmdJrAZz9/RkBGgOkcuxIQEECDBg1MZ4jYlM50ph3t+JRPTaeIFJJMMo1oRAwx9KKX6RwRERERERGpQOznS9tFRMq7XyJg0yho9pyW3qRstPwzXDkJsaOg5yqo/aDpIhERkVITQwwjGMFoRtv10huAg4MD7du3N50hRZBPPs/xHJXbVyaUUNM5ImLnKlGJLLJMZ4jcJIIIalCDh3jIdIqIiIiIiIhUMPb7Sr+ISHmSsrLgTm+NxkGbT0zXSIXhAO1ngFdXWDcYLh0yHSQiIlIqNrGJYQxjMIP5hm/seulN7IsjjrSgBQkkmE4RkXKgMpW5ylXTGSI3WcxiBjIQF1xMp4iIiIiIiEgFo1f7RURMS90I64eB30hoPxNwMF0kFYmjC3RZAO71YW0/yDprukhERKREbWYz/ehHX/ryL/6FE06mk6SCCSGEPewxnSEi5YAW38QWnec8scQyhCGmU0RERERERKQC0uKbiIhJ5zbDmn5Qrx90+AYc9LQsBrhUg+5LIT8X1g2C3Cumi0REREpEHHEMYAC96MX3fI8zzqaTpAIKJlh3fBOREqHFN7FFUUThhBN96Ws6RURERERERCogbViIiJhyMQ7WDgCfUOj0HTjoQqwYVLku9Pix4LjTTSPBkme6SERE5J7sYhehhNKe9sxjno7eEmNCCCGFFFJJNZ0iInbOFVeyyTadIVJIJJGEEko1qplOERERERERkQpIi28iIiak7YbVvaFWO+gyr+C4SRHTPFoULL+dWQXbnjNdIyIictcSSCCUUNrQhggicMPNdJJUYCGEAOiubyJyz1xxJYcc0xkiVle4wkpW6phTERERERERMUaLbyIiZe1SEqzuC573w0MR4KgLsWJDanWATt/D4W9g71TTNSIiIsV2nOM8zMMEEUQEEVSikukkqeB88MELL/awx3SKiNg5F1x0xzexKctZThZZDGKQ6RQRERERERGpoLT4JiJSli4dgpgeULVRwdKbU2XTRSI3qz8Y2v4d4l+Ho3NM14iIiBRZOukMYhA1qEEEEbjjbjpJBIAggnTHNxG5Zy646I5vYlMiiaQjHfHBx3SKiIiIiIiIVFDOpgNERCqMKycKjjetVAe6LwXnqqaLRG7P/38g8zBsnQSV64JPb9NFIiIid5RNNo/wCOc5z2Y2U4MappNErEIIYRvbTGeIiJ3T4pvYkjzyWMpSXuM10ykiIiIiIiJSgemObyIiZeHKyYI7vbl4QK8YcPU0XSTy2x74EHxHwoYRcHGX6RoREZHbsmBhIhPZxjaWspQGNDCdJFJICCEkkIAFi+kUEbFjrrjqqFOxGRvYwDnOMYQhplNERERERESkAtPim4hIabuWCmv6gKMz9FwBrjVNF4kUkQN0+AZqtYO1/eHycdNBIiIitzSZycxnPv/m37SilekckZsEE0wmmSSTbDpFROyY7vgmtiSSSAIJpBnNTKeIiIiIiIhIBabFNxGR0pSdBqv7Qn429FpdcMypiD1xdIWui8CtdsHyW/ZF00UiIiKFfMmXfMInfMM3hBJqOkfkloIJxgEHEkgwnSIidkyLb2JLIolkKENNZ4iIiIiIiEgFp8U3EZHSkpMOq3tD9nnouRIq1zNdJHJ3XDyg+4+QkwHrh0H+NdNFIiIiAEQRxe/5PVOZyljGms4Rua1qVMMXX/awx3SKiNgxLb6JrYgnnqMc1TGnIiIiIiIiYpwW30RESkPuFVg3CLJOQ681UMXPdJHIvXG/r2D5LW0XbB4PlnzTRSIiUsFtZSuP8RjP8iyTmWw6R+Q3hRCixTcRuSeuuJJNtukMESKIoB71aEc70ykiIiIiIiJSwWnxTUSkpOVdhXUDIeNAwZ3eqjY2XSRSMmoEQ9fFcCICdr1hukZERCqwFFJ4hEfoRS8+5VPTOSJFEkKIjjoVkXuiO76Jrbh+zKkDDqZTREREREREpILT4puISEnKz4YNIyBtD/RcBR4tTBeJlKw63aHjbNj7IRyYbrpGREQqoBxyeIzHqEIV/sk/cdQfa8VOBBPMAQ7obk0icte0+Ca24BjH2MUuHXMqIiIiIiIiNsHZdICISLmRnwMbwyB1E/SKKbg7lkh55DsSMo/CzpfBvT40eMR0kYiIVCC/5/fsZCdb2EINapjOESmyEELIIYcDHCCEENM5ImKHXHDR8qwYF0EEHnjQne6mU0RERERERET0pfEiIiXCkgebx0HKKui2BGq2NV0kUrqC3gD/5yB2DKRuNF0jIiIVxLd8y0xmMotZBBFkOkekWAIIwBVX9rDHdIqI2ClXXHXHNzEukkj60x9XXE2niIiIiIiIiGjxTUTk3lng53A4GQXdosG7q+kgkbLR5lOo1x/WD4WM/aZrRESknNvCFsIJ5y3eYgQjTOeIFJsLLjSjGQkkmE4RETvlggsWLOSRZzpFKqgLXGADG3TMqYiIiIiIiNgMLb6JiNwTC2x7Fo7OhS4LoU5300EiZcfBETr9E6oFwNr+kJViukhERMqpFFIYwQi6050pTDGdI3LXQgjRHd9E5K654AKg407FmCUswQkn+tHPdIqIiIiIiIgIoMU3EZF7E/caHP4HdF0I9fSin1RATpWhWxQ4usLaAZCbabpIRETKmRxyeJRHqUIV5jEPJ5xMJ4ncNS2+ici9uH60pI47FVMiiaQnPfHAw3SKiIiIiIiICKDFNxGRuxf/Buz/BDrOgfsGma4RMcetFnT/Ca6chHVDIF93HxARkZIzmcnsYhcRRFCDGqZzRO5JMMEc5zjppJtOERE7dP2Ob1p8ExOucpUVrNAxpyIiIiIiImJTtPgmInI39rwN+6ZCx9ngO9J0jYh5VRtB96Vw/mfY8iRgMV0kIiLlwHKW83f+zpd8SQtamM4RuWchhGDBwl72mk4RETuko07FpBWs4CpXGcxg0ykiIiIiIiIiVlp8ExEprv2fwJ4/Q7svwG+M6RoR21GzDXSZD8d+gD3vmK4RERE7l0oqE5jAGMYwmtGmc0RKhC++eOCh405F5K7oqFMxKZJIOtCButQ1nSIiIiIiIiJipcU3EZHiSPoMdr4MD3wITcNN14jYnnr9oP1XBYtvB78wXSMiInbKgoUneZLKVOYzPjOdI1JiHHAgiCAtvonIXdFRp2JKHnlEE61jTkVERERERMTmOJsOEBGxG0dmwY4X4P73oMUrpmtEbFeTiXD5OGx/HirfB/X1wriIiBTP3/gby1jGetbjgYfpHJESFUwwCSSYzhARO6TFNzFlE5tIJVWLbyIiIiIiImJzdMc3EZGiODoXtk6CkD9B4Ouma0RsX8u3ofF4iB0N57aYrhERETuSSCJv8AZTmEJHOprOESlxIYSwm92mM0TEDl1ffMsm23CJVDSRROKPP81pbjpFREREREREpBAtvomI/JYTi2DLkxDwAgRPMV0jYiccoN1X4PUQrBsElw6aDhIRETuQRRajGU1rWvO//K/pHJFSEUIIF7jAaU6bThERO+OKK6A7vknZiyCCR3jEdIaIiIiIiIjITbT4JiJyJ6eXwabR4P8/0Hqa6RoR++LoAl3/DVWbwJp+kHXWdJGIiNi4yUzmGMf4J//ECSfTOSKlIphgAPawx3CJiNgbHXUqJuxmN0c4omNORURERERExCZp8U1E5HZSYmD9MGj0OLSdbrpGxD45u0P3JeDgAOsGQu5l00UiImKjlrOcL/iCr/gKP/xM54iUmtrUxgcfEkgwnSIidsYZZwByyTVcIhVJBBHUoQ7taW86RUREREREROQmWnwTEbmV1E2wfig0DIP2XwMOpotE7JebF3T/CTKTYdNIsOgijYiIFHaZyzzLszzKo4xkpOkckVIXQoju+CYixebw62sTFiyGS6QiiSSSYQzDUZcSRERERERExAbpT6siIv/t3BZY2w/q9oUH/w8c9FQpcs+qNYXu0XBmNWx7znSNiIjYmNd4jXTSmY7usisVgxbfRORuaPFNytpJThJHnI45FREREREREZvlbDpARMSmXIyHtf2hTk/oPA8c9DQpUmJqtS/4fbV+GFRtDIF/MF0kIiI2YDOb+YqvmMtc6lDHdI5ImQgmmC/5klhiSSSRBBKIJx4nnFjNatN5ImKjri++5ZNvuEQqikUsogpV6E530ykiIiIiIiIit6SNDhGR69L2wOpQqNm2YDnH0cV0kUj5c98gaPsZbHsWKteFRuNMF4mIiEHXuMYEJtCf/oxmtOkckVKRTz6Jv/61+9e/drCDq1ylM51xxhknnMgmm0d51HSuiNiw60dN6o5vUlYiiWQAA6hEJdMpIiIiIiIiIrekxTcREYBLB2FNX/BoDg8tBie9oCdSavyfgczDsHVSwfKbT2/TRSIiYshUpnKKU8QQYzpFpNRYsDCGMexmN264kU12oaWV3F//csONIIIMloqIrdMd36QspZHGetbzLd+aThERERERERG5LUfTASIixl0+Bqt7QxVf6P4TOFcxXSRS/j0wFXxHwoYRBUcMi4hIhXOMY7zP+0xhCg1oYDpHpNQ44cTHfAwU3OXwdndqyiabQALLMk1E7Mz1xTfd8U3KwhKWANCPfoZLRERERERERG5Pi28iUrFd+QVW9QBXT+j+I7hUM10kUkE4QIdvoFZ7WDugYAFVREQqlN/xOxrRiBd50XSKSKkLJZS+9MUFl9u+jwWLFt9E5I501KmUpUgi6UlPalDDdIqIiIiIiIjIbWnxTUQqrqwzBXd6c64KPWMKlt9EpOw4ukLXf0MlL1jbH7Ivmi4SEZEyspjFLGUpX/DFHReBRMqTT/mUPPJu+++dcKIpTcuwSETsjY46lbJyjWusYAVDGGI6RUREREREROSOtPgmIhXTtVRY1Qss+dBzBbjVMl0kUjG5eBTcbTE3E9YPhfxrpotERKSUXeMak5nMaEbzEA+ZzhEpM81pzlM8ddtlz8Y01iKoiNyR7vgmZWUlK8kkk0EMMp0iIiIiIiIickdafBORiic7DdY8DHlZELoGKvmYLhKp2CrXK1h+S9sDseMKFlJFRKTcms50TnOad3nXdIpImfsLf8EV15u+3xFH7ud+A0UiYk+u3/FNi29S2iKJpB3tqE990ykiIiIiIiIid6TFNxGpWHIyYE0fyEqFnisLFm5ExLzqQfDQYvglEuL/YLpGRERKSSqpvMu7vMqrNKSh6RyRMueFF3/kjzjhVOj7XXAhiCBDVSJiL3TUqZSFfPKJJlrHnIqIiIiIiIhd0OKbiFQcuVdg3SC4fLxg6a1qI9NFInIj727QcTbsnwb7P731++RegewLZZolIiIlZwpTqEIVXuM10ykixrzES9ShjvXIQoBssgkk0GCViNgDHXUqZSGWWFJIYShDTaeIiIiIiIiI/CYtvolIxZB3tWDpLX0f9FoNHgGmi0TkVnxHQqt3Ie4VOL6w8L+7lgox3SDpczNtIiJyT5JI4hu+4f/x/6hCFdM5IsZUohJTmVpoccWCRYtvIvKbdNSplIVIImlKU80lERERERERsQtafBOR8iP5O0hPvPn787NhQxhc3Ak9lkF1vXAnYtMC/wDNfgebx0LqxoLvu3QIlrWDCzsg6Quw5JltFBGRYpvCFJrQhLGMNZ0iYtxoRtOGNjjjDIATTvjjb7hKRGydjjqVshBFFMMZbjpDREREREREpEi0+CYi5YMlF+JegxVd4GL8Dd+fB7FjIHUD9FgBNVubaxSRomv9CdTrD+uGwPEFsLw9XD0FWODaGTi51HShiIgUwx72sIAF/JW/Whd9RCoyBxyYxjRyyQXAF19ccTVcJSK2TkedSmlLJJEkkhjCENMpIiIiIiIiIkWixTcRKR+OL4CrpyH3Eqx8CM5vLVh62zwOTi2FbkugVjvTlSJSVA6O0OmfUK1pwZ3fci5Bfs6v/9IJDn5mNE9ERIrnf/lfHuAB3T1E5AZd6WpdLLif+w3XiIg90FGnUtoiiMAbbx7kQdMpIiIiIiIiIkWiL7WXcu/SpUtcvHiRixcvkpaWZv321atXuXTpEleuXOHatWukp6eTnZ3NpUuXuHr1KllZWaSnp5OfX3B8REZGBnl5hY/Wu/5+t1K9enUcHQvvllauXJlKlSoV+raHhweurq54eHhQqVIlKleujIeHBy4uLlSvXp2qVavi6elJjRo18PT0tH7bzc2tFD5bdizxPXCgYNkt7wrEdAefUEhZBd2XgvdDpgtFpLiSv4fz23/9hxuO8rHkwumYguNPqzU1kmZKVlZWoVl2/duXL18mLS2NnJyc35xtcOv5lZeXR0ZGxi1/3hvn13XOzs5Uq1YNACcnJzw8PH5ztlWuXLnQLLv+7apVq5bCZ0tEbMUWthBNNMtYZr1gL1KR3Gl+BzgE4DjRkZQ1KTwf+bzmt4jckY46ldIWSSRDGGK9u6CIiIiIiIiIrdPim9gVi8XC2bNnSU1N5fTp06SkpJCamsrJkydJTU3l7NmzXLhwodBFhf9eVgOoWrUq7u7u1r+7ublRvXp1XFxc8PDwwNPT0/oiv5OTE4D1/W7k4uJyyxf78/PzSU9Pv+n7L126RG5uwVE2/72UcOTIEbKysrh69SoZGRnk5OSQnp5OZmYmOTk5N/1Y7u7uhS481KxZEx8fH3x8fPDy8qJevXrUqVMHb29v6tWrR5UqVe7qc24XUlZC2p7//LMlD/ItcHo5tHwH6vQw1yYid8ECe96GPX++/bs4OsPhf8D975VZVWnIzMy0zrCUlBROnz5Namoqp06dss60Gy+SX7169aYfw9XVlSpVqlCjRg1cXV1vmm1ubm54eXlZL2DD7edXjRo1cHC4eSnlxvl13fWZBZCTk0NmZqZ1tp04cYKcnBwyMjKs73d9Ie/y5cs3/fjOzs6FLqjXrFkTb29v6tSpQ926dfH29i4047y9ve/q8y0iZvyZP9ORjvSlr+kUkRJR0vO7umt1Ug6kEB8fr/ktIneko06lNJ3kJNvZzp/4k+kUERERERERkSJzsFgseqVEbEJ+fj4pKSkkJydz/Phxjh8/zokTJzh27BgnTpzgzJkzpKamFnrh/vrFgHr16uHt7Y23tzc1a9a0vvh+qzuleXp64uLiYvAjLb7MzMxb3iHgxn++cOGCdRnw+nLgjdzd3albty4+Pj40bNiw0Jufnx8NGzbEw8PD0Ed4j1b1hNQNkF/4og4OjoATdJ0P9YcaSRORYsrPga0T4ejc335fV08YfhocbfMOmBcvXrTOs2PHjhWabdefr2+8EO7g4IC3tzdeXl7W5+vrM+1Ws+z6m7u7u8GPsoBrlg0AACAASURBVPiys7NvO8uuf/vChQucPXuWM2fOcPr0ac6ePVtoCdzFxQUvLy98fHyoX7++dY41aNCAhg0b4uvri4+Pzy2XAESkbO1gB+1ox0/8pMU3sQsm5vcFLpBGGo1pbOJDLhLNbxHb4YAD85lPGGGmU6Sc+ZzPeZ3XSSWVSlT67f9ARERERERExAZo8U3KVEZGBgcPHrS+HTp0yLrY9ssvv5CdnQ0UfOV43bp18fX1xdfXl/r16+Pj42O9e9n1rxyvWbOm4Y/IduXk5HD27FlSUlKsy3CnTp3izJkzhS7gXLhwwfrfVK9e3XrBwc/Pj6ZNm9KsWTP8/f3x8/PD2dkGbxKZtht+vB9u99XODg6AE3T+HhqOKMsyEbkbeVlw4FNI+EvBElz+zXe8/A8H6Pwv8B1VZnk3ysnJ4ejRoyQlJZGUlMShQ4c4fvy4dYH70qVL1vetXbt2oYXj6xfGb5xr3t7etvk8ayPOnTvHmTNnCl1MP336NL/88ov1856SkmK906ubm5v1QnrDhg1p2rQp/v7+1jcdzyZSNgYxiFRS2cIW0ykigOZ3WdP8Fil5jjjyPd/zGI+ZTpFypg99qEEN5jPfdIqIiIiIiIhIkWnxTUpcdnY2Bw4cICkpqdCSW1JSEmfOnAEKvtLbz88Pf3//QhcSfH19adiwIfXq1dPFgzKSmZl5y7sZHDlyhIMHD3L27Fmg4DFr1KgR/v7+1mU4f39/AgICaNCggbkPYNNoOLHwN5ZjAAcn6DTX2IKMiBTTtfOQ8A4c+AIcHW6+oyMU/L6u3QF6byrVlOTkZOtMu3G2JScnW+9CWrduXeuSsK+vb6ELtn5+ftYjyqR05eTkcPLkyZvm2rFjx6zL9tcfs3r16hW6kH59pvn7+9vdnWFFbFUccbShDdFE05/+pnOkgtH8th+a3yLF44QT/+JfjGSk6RQpR9JJxxtv/o//43EeN50jIiIiIiIiUmRafJN7curUKfbu3UtiYiI7duywfjsrKwsAT09PAgMDCQoKonHjxta3oKAgKlXSLfPtQVZWFocPH2bv3r0cOXLE+rZnzx7rImP16tVp2rQpgYGBtGnThqCgIFq2bIm3t3fpxl0+DlGNwZJ3+/dxdC64GVyTJyHoj1ClYek2iUjJyjgAu/4XTiwqWHS71e/3/nugRvA9/1RpaWkkJCRYZ9nevXuJj4/n3LlzQMFMu3GWNW7cmMDAQFq2bGm/R0VXMDk5Odbl7iNHjlgf5yNHjpCcnEx+fj7Ozs40bNiw0EwLDAykRYsWODo6mv4QROzKEIbwC7+wne04oKMLpXRofpd/mt8ihTnjzFzmMgp9YZ+UnO/4jglM4Axn8MTTdI6IiIiIiIhIkWnxTYrk6tWrxMXFsWPHDnbv3s3u3bvZu3cvmZmZODg44OfnR3BwMMHBwYSEhBAUFESzZs203FbOpaamsnfvXhISEtizZw8JCQkkJCSQnp4OQP369a2/Jh544AHatm1L06ZNcXAooQufO16Eg1/c+m5vDi5APviNgpC3oWqTkvk5RcSMlFWw4wVI30fBNuuv//vi6AJNn4G2fyvyD5Wfn09SUhLbt28nLi7O+vx1+vRpoOACeUhIiPX5Kzg4mBYtWlCrVq2S/7jEZly5coWkpCTrLLv+6+L48eMAeHh4EBQUREhICK1ataJt27a0atUKNzc3w+UitimeeFrTmiiiGMhA0zlSDmh+y61ofktF5Iors5ilu3JJiXqMxzjPeWKIMZ0iIiIiIiIiUixafJObZGdns2vXLrZv325927t3L7m5uXh6evLAAw9YXzi+vuRWrVo109liQ44fP17oosOePXtITEwkNzeXGjVq0KZNG9q2bWt98/PzK/5Pkn0RFt8HeVcLf7+jC1h+XXgL/hNUa1oiH5OI2ABLPpz4d8ECXNbZ/9z9zbkKDD9T8PdbOHz4cKGZtnPnTjIyMnB1dS20sN2yZUuCg4O57777yvCDEluXnp5uvZi+e/duEhMTiY+PJz09HRcXF0JCQgrNtODgYB21JgIMZzjJJLODHbrbm9wVzW+5F5rfUp5VohLf8A1jGGM6RcqJa1zDCy/e532e5VnTOSIiIiIiIiLFosU34ciRI2zatInY2Fi2b9/O7t27yc7OxsPDg9atWxd6MbhJE901S+5OVlYW8fHxhS5e7d+/n7y8PGrXrk3btm1p3749nTt3pmPHjr+9TJn4V9j9NlhyC/7Z0aXg2w0egVbvQjX/Uv+YRMSQ3Muwdyrs+wDycwsW4Dp8DU0mkZaWRmxsLLGxsfz8889s376dixcv4uzsTGBgYKGZ1qpVK1xdXU1/NGKHLBYLBw8eLDTT4uLiyMzMpFKlStY7ynTq1IkuXbrQsKGO2ZaKJZFEWtKSRSxiCENM54gd0PyWsqD5LeWFjjqVkhZNNIMZzHGOU5/6pnNEREREREREikWLbxVMbm4u8fHxbNq0yfp26tQpXF1dadOmDe3bt7deUGjWrBmOjo6mk6Ucy8zMtB6hu337drZs2cLhw4dxcnKiZcuWdOnSxXrRoX79G154y8uCxfUh+/yvR5rmge+vR5rqDm8iFceVk2TGPk/Vs4s5kVmLAZ/VJTExkfz8fJo1a0aHDh2sM+3+++/H3d3ddLGUY3l5eezfv996IX3btm3s3LmTnJwcGjRoUGimhYSE4OTkZDpZpNSEEcZ+9rOLXTiiP0/IzZKTk9m4cSOxsbFs3LhR81uM0fwWe+SII9/zPY/xmOkUKScmMpFEEtnCFtMpIiIiIiIiIsWmxbdyLjs7m9jYWNauXcvGjRvZunUrmZmZeHp60rlzZ+sLuO3ataNSpUqmc0U4ffo0mzZtYuPGjWzatIn4+Hhyc3Px9fWlS5cudOnSheEtz+Od/CY4OELDx6Dl21Ctmel0ESkD+/btY9WqVWzcuJGNGzdy8uRJ2jV15otJ7mzMHIhfmzA6deqEt7e36VQRrly5ws8//2xd7oiNjSU9PR0PDw86duxI586d6dmzJx06dMDZ2dl0rkiJ2MteQghhAQsYznDTOWIjbjW/XVxcaNOmDZ06daJr166a32IzNL/FluWTjxNOLGABIxhhOkfKgTzyqEtdXuEV/sAfTOeIiIiIiIiIFJsW38qZ/Px8du3axapVq4iJiWHDhg1cuXKFRo0a0aVLFzp37kyXLl0IDAzEwcHBdK7Ib7p8+TJbt261LsJt2RzLlrcyOXi+Cj9feZigjo/Qs2dP6tSpYzpVRErBqVOniImJsc61U6dOUb16devydteuXWnXrh2VK1eGa+fBrZbpZJHbys/PJyEhgQ0bNhAbG8v69ev55ZdfqFatGt26daNXr16EhoYSFBSk/08TuzWSkSSQwG52625vFVix5reIjdP8FluSSy4uuLCIRQxjmOkcKQfWsY7udGc/+wkgwHSOiIiIiIiISLFp8a0cOHr0KDExMcTExLB69WrOnTuHl5cXPXv2pFevXvTq1YvGjRubzhQpETmXTrBnx3qi1h5k1apVbN26ldzcXEJCQqwXHB566CGqVq1qOlVE7kJGRgZr1qyxXijft28fbm5udOzYkdDQUHr16kW7du10zJSUG0lJSaxatYpVq1axZs0aLly4gI+Pj/X/4UJDQ2nQoIHpTJEi2cc+gglmHvMII8x0jpQhzW+paDS/xZRrXKMSlYgkksEMNp0j5cCLvMgKVrCXvaZTRERERERERO6KFt/sUF5eHvHx8SxZsoTo6Gh27NiBu7s7nTp1IjQ0lNDQUB544AEcHXWHBSn/rly5QmxsrHX5c+fOnTg5OdGhQwcGDRrEkCFDaN68uelMEbmDI0eOEBMTw5IlS1ixYgXZ2dk0btzYOtP69u2Lh4eH6UyRUpefn09cXBwxMTFs3LiRdevWcenSJRo3bszAgQMZNGgQ3bp1w8XFxXSqyC09zuPEEUcCCbrbWwWg+S1SQPNbytIVrlCFKkQTzQAGmM6RcqAxjRnFKP7KX02niIiIiIiIiNwVLb7ZiXPnzrFs2TKio6NZvnw5aWlpNG/enIEDBzJgwAA6deqEq6ur6UwR486cOcPy5ctZunQpy5cvJz09ncDAQAYMGMCAAQPo3Lkzzs7OpjNFKrTs7GzWr1/P0qVLiY6O5tChQ9SqVYu+ffsyaNAgevfuTa1aOrJUJCsriw0bNlh/rxw+fJhatWrRr18/Bg4cSN++falRo4bpTBEADnKQQAKZy1xGMtJ0jpQCzW+RotH8ltJ0iUt44MFP/MTDPGw6R+zcTnbShjZsYxttaWs6R0REREREROSuaPHNhh0+fJiFCxcSFRXF1q1bcXJyolu3bgwYMICBAwfSpEkT04kiNi0nJ6fQBYekpCQ8PT3p27cvw4YNY8CAAVSpUsV0pkiFkJGRQVRUFJGRkaxYsYKMjAyCg4OtM61jx446/kzkN+zfv5/o6GiWLl3Kxo0bAejSpQuDBg3ikUcewdfX13ChVGRP8ASb2UwiiTih5/PyQvNb5N5pfktJSiMNTzxZwQp609t0jti5KUzh//g/TnACBxxM54iIiIiIiIjcFS2+2ZiDBw+ycOFCFixYQFxcHLVr12bQoEEMGDCAPn36UK1aNdOJInbr4MGDREdHEx0dzbp163Bzc6Nfv36EhYUxYMAAqlatajpRpFxJT08nKiqKBQsWsGLFCiwWCz169LDONT8/P9OJInYrLS2N5cuXWy+kp6Wl0b59e0aMGMGIESP0+0vK1AlO0JSmzGAGE5hgOkfukea3SOnR/JZ7dZ7z1KY2q1hFT3qazhE7F0IIPejB3/ib6RQRERERERGRu6bFNxuQnJxMZGQkCxYsIDY2Fk9PTwYMGEBYWBgPP/wwLi4uphNFyp0LFy4QHR3NggULWL58OU5OToSGhhIWFsbQoUPx8PAwnShil9LS0qwXy1euXElubi4PPvggYWFhjBo1Cm9vb9OJIuVOXl4emzdvZsGCBcybN4+zZ88SGBhIWFgYo0ePplmzZqYTpZx7gRdYxCIOcxhXXE3nyF3Q/BYpe5rfcjfOcpY61GEta+lGN9M5YscOcQh//FnNanrQw3SOiIiIiIiIyF3T4pshJ0+e5LvvvuNf//oXu3btwtvbm+HDhxMWFka3bt10XIxIGTp//jyLFy9m4cKFrF69GicnJ/r168e4cePo378/rq66gCtyJ1lZWURFRTF37lxWrFiBg4MDvXv3JiwsjMGDB1OjRg3TiSIVRk5ODqtWrWLhwoVERERw/vx52rZty+OPP86oUaOoU6eO6UQpZ85zHj/8+Ct/5XmeN50jxaD5LWI7NL+lqE5zmnrUYwMb6EIX0zlixz7kQz7gA1JIwRln0zkiIiIiIiIid02Lb2Xo8uXLLFq0iLlz57J69Wo8PDx47LHHePTRR3nooYe07CZiAy5cuEBERATfffcda9aswdPTk5EjRzJmzBgefPBB03kiNsNisbBx40bmzJnDggULyMzMpE+fPowaNYrBgwdTvXp104kiFV5ubi6rV6/mhx9+YOHChVy5coW+ffsyduxYhgwZQqVKlUwnSjnwFm/xJV+STDJV0bHxtk7zW8T2aX7LnfzCLzSgAbHE0pGOpnPEjnWiEwEEMItZplNERERERERE7okW30pZfn4+sbGxzJ07l++//54rV67Qo0cPxo4dy4gRI3B3dzedKCK3cfLkSRYuXMjs2bOJj4/H19eXkSNH8tRTT9GkSRPTeSJGHD9+nO+//55vvvmGQ4cOERgYyLhx4xg/fjw+Pj6m80TkNrKysli5ciVz584lIiICd3d3Bg8ezLhx4+jVqxcODg6mE8UOXeISvvjyMi/zJm+azpE70PwWsU+a3/LfjnEMP/zYylba0950jtipM5yhHvVYzGIGM9h0joiIiIiIiMg90eJbKTlx4gRff/01s2bN4pdffqFDhw6MGTOGUaNGUatWLdN5IlJMO3bsYM6cOcybN49z587RrVs3nn76aYYPH66jUKXcu3r1KvPnz2fmzJnExsZSr149Ro8ezbhx4wgJCTGdJyLFlJKSwvfff8+cOXOIj4+nUaNGTJw4kYkTJ2oBRorlQz7kHd7hGMeohf6MY2s0v0XKF81vATjCEZrQhO1spw1tTOeInfqKr3iFV0glFXf0RdkiIiIiIiJi37T4VoLy8/NZtmwZX331FT/++CNeXl488cQTjB8/noCAANN5IlICcnJyWL58Of/4xz+Ijo6mZs2aPPHEE7oLnJRL+/fvZ8aMGXz77bdcvnyZYcOG8eSTT9KrVy8dzy1STuzZs4fZs2fz7bffkpGRwZAhQwgPD9ddZOQ3XeMajWnMaEbzIR+azpEbaH6LlH+a3xXXQQ7SjGbEEcf93G86R+xUX/pSjWosZKHpFBEREREREZF7psW3EnDmzBlmz57NjBkzOHr0KG3atOH5559n1KhRuLi4mM4TkVJy+vRp5syZw5dffsmJEyfo2bMnTz/9NEOHDtXvfbFb2dnZREZGMnPmTFatWkW9evWYNGkSzz77LN7e3qbzRKSUXLt2jaioKOvv/SZNmjBp0iSefPJJvLy8TOeJDZrBDF7gBY5whHrUM51T4Wl+i1RMmt8Vz37204IW7GY3IejunVJ86aTjjTf/4B+MYYzpHBEREREREZF7psW3exAbG8unn35KREQEHh4ejB8/nvDwcJo1a2Y6TUTKUF5eHtHR0cyYMYPly5fj4+NDeHg4zzzzjC40it04deoUn332Gf/4xz+4cOECAwcOJDw8nD59+uDo6Gg6T0TKUEJCAjNmzGDu3LlkZWURFhbGiy++SJs2Ok5LCuSRRwta0IMezGCG6ZwKTfNbRK7T/K4YEkkkmGASSSSQQNM5Yof+xb94gic4wxk88TSdIyIiIiIiInLPtPhWTLm5uSxatIhp06axdetWOnTowHPPPUdYWBiVKlUynScihh09epSvv/6amTNncvnyZcaOHctLL71EixYtTKeJ3FJ8fDzTpk3jhx9+oGbNmjzzzDNMmjSJ++67z3SaiBh2+fJl5s2bx2effUZ8fDzdunXj5ZdfZuDAgVqoqeC+53vGMpZ97MMff9M5FZLmt4jcjuZ3+bab3bSiFfvZTwABpnPEDo1gBBlksIIVplNERERERERESoRe8SqiS5cuMXPmTIKCghg1ahReXl6sXLmSLVu2MHbsWC29iQgAjRo14t133+XkyZPMmDGDTZs2ERgYSJcuXViyZAnaNRZbYLFYiImJYdCgQbRu3ZqtW7cydepUjhw5wp/+9CddNBcRAKpUqcLEiROJi4tjw4YNeHt7M3z4cJo1a8b06dO5fPmy6UQx5EM+JIwwLb2VMc1vESkKze/yLY88AJxwMlwi9iiLLFawgmEMM50iIiIiIiIiUmK0+PYbTpw4weTJk2nQoAGvvPIKffv2JSkpiSVLlhAaGmo6T0RslJubG+PGjWPPnj1ERUXh4uLC4MGDeeCBB5gzZw45OTmmE6UCunbtGjNnziQwMJA+ffqQk5PDsmXL2L9/Py+88AKVK1c2nSgiNqpLly7Mnz+fhIQEevXqxRtvvIGvry9//OMfOXPmjOk8KUM/8iNxxPEqr5pOqTA0v0Xkbml+lz9afJN7sYIVZJLJIAaZThEREREREREpMTrq9DaOHTvGe++9x6xZs/Dy8uL3v/89Tz/9NJ6enqbTRMRO7dy5k2nTpjF//nzq16/PG2+8wfjx43F1dTWdJuXc1atX+frrr5k6dSrnzp1jzJgxvPTSSwQFBZlOExE7lZqayldffcXnn39ORkYGTz/9NK+99hr16tUznSalrCtd8cCDpSw1nVLuaX6LSEnT/LZ/W9nKgzzIMY7RkIamc8TOPMmT7GMfm9lsOkVERERERESkxGjx7b8cO3aMadOmMWPGDHx8fHjppZcIDw/XUaYiUmKOHz/Oxx9/zMyZM/Hy8uKVV17h6aef1t06pMRdu3aNb7/9lj//+c+cO3eO8ePHM2XKFB2FJiIlJjs7m9mzZ/OXv/yFs2fPMmHCBN58800aNGhgOk1KQSyxdKYz61lPV7qazim3NL9FpLRpftuv67P4F37hPjQXpOjyyKMudZnMZF7jNdM5IiIiIiIiIiVGR53+Kjk5mfDwcPz9/YmKiuKDDz7gwIEDvPDCC1p6E5ES1bBhQ6ZPn05ycjKjR4/mjTfewM/Pjw8++ICrV6+azpNy4PLly0yfPp1GjRrx8ssv88gjj3DkyBFmzJihi+YiUqJcXV15+umnOXz4MF9//TWrVq2iadOmjBs3jkOHDpnOkxL2ER/RjnZaeislmt8iUlY0v+2XjjqVu7WBDaSSyhCGmE4RERERERERKVEVfvHt+PHjTJgwAX9/f9asWcPXX3/NwYMHeeGFF3BzczOdJyLlWJ06dXj//fc5dOgQo0aN4p133qFJkyZ8/vnn5OTkmM4TO5SVlcXHH3+Mn58fb775JmPHjuXIkSNMnz5dxxeJSKlydXVl3Lhx7N27l7///e9s2LCBwMBAnnnmGU6dOmU6T0rAUY4SRZTuEFIKNL9FxBTNb/tzffHNUS/pSjEtZjFBBBFAgOkUERERERERkRJVYV8luXDhApMnTyYgIICNGzcya9Ys9u3bx/jx43F2djadJyIVSL169fj00085cuQIjz32GK+88gqBgYHMnz8fnUYtRZGfn8+3335LQEAAU6ZMYdKkSRw9epQPPvgAb29v03kiUoFcv4NMUlISX375JT/++CPNmjXjzTffJCMjw3Se3IOP+ZiGNGQoQ02nlBua3yJiKzS/7UcWWQBUQqdTSPEsYQnDGGY6Q0RERERERKTEVbjFtytXrvDBBx/QpEkTZs+ezdtvv01iYiJjxozByUnHBIiIOT4+PnzyySccPHiQnj17Mnr0aNq3b8/q1atNp4kNi4mJoU2bNjz55JN06NCBxMRE3nvvPWrXrm06TUQqMBcXFyZOnMihQ4eYNm0aM2fOpHHjxnzwwQdkZWWZzpNiushFvuVbXuIlnNEXCZUEzW8RsUWa37bv+uKbGzqlQopuBzs4ylF9AYOIiIiIiIiUSxVm8S0/P58FCxYQFBTEX/7yF8LDwzl8+DB/+MMfdKSpiNiUBg0aMGPGDHbv3k2jRo3o1asXvXv3Ji4uznSa2JBt27bRs2dPevfuTe3atYmLi2P+/Pn4+fmZThMRsbp+B5kDBw4wadIk3nnnHQICApg5cyZ5eXmm86SIvuRLXHDhCZ4wnWL3NL9FxB5oftuuLLJwwAFXXE2niB1ZzGLqU5/WtDadIiIiIiIiIlLiKsTi24YNG3jggQd4/PHH6dOnDwcPHuT999+nevXqptNERG7r+nGnmzZt4urVq7Rt25Zx48aRmppqOk0MSklJYdy4cXTo0IGrV6+ybt06Vq5cScuWLU2niYjclqenJ++//z4HDx7k4Ycf5tlnn6VDhw5s2bLFdJr8hmyy+YzPCCecqlQ1nWO3NL9FxB5pftueLLKoRCUccDCdInZkMYsZznD9uhEREREREZFyqVwvvp0+fZoxY8bQrVs36taty549e5gxYwZ169Y1nSYiUmSdOnViw4YNzJkzh5iYGFq0aMGMGTPIz883nSZlKCcnh2nTphEQEMD69etZsGABmzdv5qGHHjKdJiJSZPfddx8zZswgLi6OqlWr0rlzZ8LDwzl37pzpNLmN7/iOc5zjOZ4znWKXNL9FpDzQ/LYd17hGJSqZzhA7cpCD7GUvwxhmOkVERERERESkVJTLxbfc3FymT59O8+bNWbduHbNnz2bZsmUEBASYThMRuSsODg48/vjjHDx4kN/97nc8//zztG3bltjYWNNpUgbWrVtHmzZteP3115kwYQIJCQk88sgjprNERO5aSEgIa9euJSIigmXLltGsWTOmT5+u49Ns0Kd8yihGUZ/6plPsjua3iJQ3mt/mXb/jm0hRLWIRtahFF7qYThEREREREREpFeVu8W316tW0atWK119/nRdffJGkpCTGjRtnOuuWDh06hIODA/Pmzbvlv9+2bRsTJkygUaNGVK5cmZo1axIcHMwjjzzCl19+yeHDh8u4uPypWrUqDg4ON705Ojri5eXF0KFD2bZtm+nMW9q4cSMODg6sXbvWdIpdu/Hz+Fu/J21BlSpVePvtt4mLi8PT05MuXbrw5JNPcvbsWdNpUgpOnjzJyJEj6d69O76+vuzbt4/p06dTtWrpHTWn2WSeZpOYYGoeDho0iISEBCZNmsSrr75Ku3bttNRtQ1awgl3s4iVeMp1iV0zMb5NM/j90REREoVmZlZVV5g32QPO55H300UfWX3f16xdeDLaHP1feK81vc7T4JsW1mMUMZjDOOJtOERERERERESkV5WbxLT09nfDwcEJDQ2ncuDGJiYm88847VK5c2XRaseXn5/Pqq6/SqVMnvL29+emnn0hLS2Pfvn188sknZGRk8Oyzz9K0aVNyc3NN55aYzMxM/P39GThwYJn+nHFxcQAMGTIEi8WCxWLh4sWLzJw5k82bN9O5c2diYmLKrKmooqKiqFmzJl262MZXbN7t42ficb+RrX0eiyowMJBVq1YRGRnJ6tWrCQgIYObMmaazpIRYLBbmzJlDSEgI27dvZ/78+SxZsoQmTZoYa9Js0mwqitJ8TjU9L0qb6Y/P5DysVq0aU6dOJTExkTp16tClSxfCw8O5dOlSmbdIYR/zMaGEcj/3m06xC7Y4v21ZSTzvDR06FIvFwpAhQ0qwrPy58Tk+JyeHli1b3tPzvemZZQsmT56MxWKhVatWplOM0fw2Q4tvUhynOMXP/KxjTkVERERERKRcKxeLbz/++CPBwcFERkZaLy40btzYdNZde+utt/joo4/44osvmDp1Ks2bN8fNzY06derQu3dvli1bRr9+/Uq9o2rVqmV68dNisZCfn09+fn6Z/Zy3U716dYYNG8a0adPIycnhxRdfNJ10k8jIe2N4tQAAIABJREFUSAYMGICzs218xeadHr87/Voy/bjb2uexuAYNGsTevXsJDw/nf/7nf+jfvz8nTpwwnSX3IDk5mT59+jBx4kTGjh3Lrl27CAsLM52l2aTZVCSl+Zxq6rEoyV9zmod35u/vz08//cQPP/zAokWLaNmyJStXrjTWU9ElkMBKVvIKr5hOsQu2Or9tmcnnvbL+/wnT/vs5/l4/7yX52FW0x6I80vwuW9e4psU3KbJIIqlCFUIJNZ0iIiIiIiIiUmrsevHt4sWLhIeHM2DAADp27EhCQgIjRowwnXVP9u/fz/vvv0+bNm146qmnbvk+Tk5OvPXWW2VcVvqqVavG4cOH+fHHH02nWPXo0QOAxMRE0tLSDNf8x/79+0lKSrKpOxvc7eNn8nG3xc/j3XB3d+f9999nw4YNHD16lJCQEGbOnInFYjGdJsVgsViYOXMmISEhnD59mk2bNjF9+nSqVKliOk2zSbOpSEr7OdUWH4uSpHn4H2FhYSQmJtKuXTv69OnDo48+yoULF0xnVTgf8zEBBNCXvqZTbJotz29bV96f123Ffz/Hu7i4kJCQcE/HUuqxk1vR/C4buuObFMdiFvMwD1MZ+zsRRURERERERKSo7Hbxbf78+TRv3pyffvqJpUuXMn/+fGrXrm06657NnDmT/Pz837w7QMeOHbFYLHZ7lyp7cePikIODg8GSwiIjI3Fzc6NvX12IvBfl7fPYqVMndu7cyVNPPcWzzz5L3759SU5ONp0lRZCUlETXrl353e9+x8svv8zOnTtp37696SwrzSbbotkkJc0WHztvb2/mz5/PggULWL9+PS1btmTp0qWmsyqMM5xhHvN4lVdxwHaeZ2yNrc9vEbDN53gpvzS/S58W36So0khjHesYylDTKSIiIiIiIiKlyu4W3y5dukR4eDgjR46kb9++xMfH079/f9NZd6Vp06ZYLBZGjhxp/b7169cD0LJly2L9WLm5ufzwww/07t0bHx8fKleuTEhICNOnTy90/EhERAQODg7WtwMHDvDoo49Sq1Yt6/e9/vrrODg4cPnyZTZt2mT9/v9eZEhNTeX555/Hz88PV1dXvLy8GD58OPHx8YXe79q1a0yZMoXmzZvj7u5OzZo1GTRoEFFRUeTl5d2yKysr654/tuTkZB577DFq1KhBrVq1GDhwIIcPHy7W53Xt2rUABAUFUb16dQDOnz/Pyy+/TJMmTXB1dcXT05N+/fqxZs2aYn/cxf1cXhcVFUXPnj2pWrUqH330kfVjrl+/Ptu2baNXr15Uq1YNd3d3evTowaZNm276MUry47jd43e97Xa/lu70uBe18V4e9xs/j3Dr35P2pnLlynz44Yds376d1NRUWrVqxT//+U/TWXIHc+bMoXXr1ly6dInNmzfzzjvv4OrqaqxHs0mzqbify+v++zm1qF1Fefy/+eabO86LorQW97H4rRkGRf91oHl490aMGMH+/fsZMGAAAwcOZNy4cVy+fNl0Vrn3OZ9TneqMZrTpFJtla/PbpP9+ziiJ5/X9+/czdOhQqlevjru7O+3btyc6OprQ0FDrfzNp0qSbWlJSUu75uf1WbOHPXNfdy3yOjo4u8Xlz/ccojTl7J8X9NVLUx6Kos/1ObGmOmqL5XXq0+CZFFU00Fiz0xz5fNxcREREREREpMosd2b59u8Xf39/i5eVliY6ONp1TKurWrWsBLFu3bi3Wf7dkyRILYHn33XctFy5csKSmplr+9re/WRwdHS2TJ0++6f2HDBliASzduv1/9u48Lsp6fx//NSzCgMhiCoiaG6hloRkVKS7ggrkgZGYu5bej0fGYW6Z2LPOczD6VZdaxY2oeyzKXclDcQj2oKViUW0ePgHbMDRRQWRRQ4PX7ox8kss0MM/OeGa7n48Hjkffcc7+v+55hrmbmzX33lsTERLlx44YcOnRIHB0dJSsrS0RE3N3dpUePHtWOd+nSJbn33nvF19dXtm3bJvn5+fKf//xHevfuLa6urpKUlFSx7oQJE8TT01MSEhLk5s2bkpmZKTNnzhQAkpiYWG2uwsLCeu9bVFSUJCUlSUFBgezatUu0Wq2EhIRUWf/IkSMV65fLzc2VTZs2SfPmzcXZ2Vl27dolIiIZGRnStm1b8fX1lfj4eMnNzZXU1FSJiYkRjUYjK1asMHi/DTmWIiKXL18WBwcHWbZsWaXlwcHB4u7uLqGhoRX7nZKSIg8++KA0atRI9u7dW7GuOfajpsdPpPbnUk33MyTjndvQ93Gv6Tjak6KiIpk9e7Y4ODjIuHHjJD8/X3UkukNubq4888wzotFoZMqUKVJcXKw6Uo3YTewmY7rJ2Nfx2h7/6h4LQ7Ma+ljU9pwz9HnAPqyfTZs2iY+Pj3Tu3FmOHj2qOo7dKpZi8RVfmSfzVEexSrbU36oZ+7qenp4uXl5eEhAQIAkJCRWv6/369ZNmzZqJi4tLjWPd+dq3Z88eadKkicGv7bVR/Z7LVO8dTdk3d7/3M2XP1sTQ54gh+2ZotwcHB0tAQIBB+Rsa9rdpPSPPSLREq45BNiBGYmSADFAdg4iIiIiIiMjsbGLiW1lZmXz44YfSqFEjCQ8Pl4sXL6qOZDblkwt+/PFHg+4XHx8vffr0qbJ87Nix4uzsLLm5uZWWl38YvX379hq3WdsH0M8995wAkK+++qrS8oyMDHFxcZHu3btXLGvbtq08/vjjVbYRFBSk9+QCY/YtPj6+0vIRI0YIgIovWcqVTy6480ej0UjTpk1l2LBhlR6L8ePHCwD5+uuvK22jqKhIWrRoIVqtVjIzMw3ab0OOpYjIypUrRaPRVPk9CA4OFgBy5MiRSsuPHz8uACQ4ONis+yFi2olvhmS8cxv6Pu41HUd7lJCQIH5+ftKmTZsqX4aRGj/88IO0a9dOfH19ZefOnarj1IndxG4qZ0g3Gfs6XtvjX91jYWhWQx+Luia+GfI8YB/W37lz5yQsLExcXV3lww8/lLKyMtWR7M4aWSNO4iTn5bzqKFbH1vpbNWNf15966ikBIN98802lda9cuSJubm61Tny7+7Vv9OjRBr+210b1ey5TvXc0Zd/UNPHNFD1bE0OfI4bsm6Hdzolv+mF/m060RMsoGaU6Blm5m3JT3MVd/in/VB2FiIiIiIiIyOys/lKnV65cwZAhQzBz5ky8+uqr2LVrF1q0aKE6ltmU71t2drZB9xsyZEiVS3QAQHBwMG7fvo0TJ05Ue79HHnnE8JD4/TImDg4OGDJkSKXlfn5+uP/++/Hzzz/jwoULAIDIyEgkJSXhhRdewKFDhyou1ZKamoo+ffrUOZax+xYSElLp361atQIAXLp0qdr1o6KiIL9PBkVZWRmys7OxefPmStvR6XQAgMGDB1e6r4uLCyIiIlBYWIjvvvvOoP025FgCwObNm/Hwww9X+3vg7u6Orl27Vlr2wAMPoEWLFjh27BgyMjLMth+mZkjGO+n7uNd2HO1N//79cfToUXTq1Am9evXC/Pnz9b5MD5mWiGDJkiXo2bMnOnTogKNHj2LgwIGqY9WJ3VQVu6nubjL2ddzQx9/QrOUMfSyqY+zzwBDsw8patWqFxMREzJ49Gy+//DKio6ORk5OjOpZd+Qf+gSfxJFqipeooVsNW+9taGPq6vnPnTgCocoybNWuGTp061Xrfu1/7AgICABj22l4Xle+5TPne8W7G9k1NTNGzNTH0OWLIvlmi2xsi9rfp8FKnpI8EJKAQhRiGYaqjEBEREREREZmdVU98O3DgAIKDg5GamoqkpCTMnz8fDg5WHbneevfuDQA4fvy4QffLzc3FvHnz8MADD8Db2xsajQYajQavvPIKAODmzZvV3s/d3d3gjMXFxcjNzUVZWRk8PT0rxir/OXz4MAAgPT0dALB06VJ88cUX+PXXXxEREYEmTZogMjKy4sNnc+2bp6dnpX83atQIAIye8FO+366urvDw8Khyu6+vLwAgMzMTgH77beixvHnzJnbv3o2oqKhqM3p5eVW7vHnz5gB+n0hqjv0wNUMz3kmfx72u42iPfH19sW3bNvz973/HW2+9heHDhyMvL091rAYlJycHAwYMwJw5c7Bo0SLs3LkTfn5+qmPphd1kun1rKN1Un9dxQx5/Q7PeyRSPhbHPA32xD6vn6OiI+fPnY8+ePfj555/RrVs3/Pzzz6pj2YXDOIwf8AP+gr+ojmI1bLm/rYWhr+v5+flwdXVF48aNq9zu7e1d6/3vfu0r//zAlH/0oeo9l6nfO96pPn1TE1P/P085Q58jhu6bubu9IWN/mwYnvpE+dNDhUTyKFrCNP24hIiIiIiIiqg+rnUX2z3/+ExEREXjsscdw+PDhKn8tbK9iY2Ph5OSEb775ptb1Zs2aBQcHB5w6dQoAMHToULz55puYOHEi0tLSUFZWBhHB4sWLAfx+lgJDaTSaape7uLjAy8sLTk5OuH37dsWZaO7+6du3b8V2xo0bh927d+P69euIi4uDiCAmJgYffPBBnTnMsW/GcHFxgaenJ4qKipCfn1/l9suXLwNAxRdh+uy3ocdy165dKCwsrPHLi5ycnGqPx5UrVwD8/mWMOfajLjU9l2piaEZD1XUc7ZWDgwNeffVV7N27Fz/99BMeffRRpKamqo7VIBw7dgwhISFIT09HUlISpkyZYvDvhUrspqrYTbV3k7lfx+8cx5Csxqjtd9XQ5wH70LR69+5dcUbTnj17Ys2aNaoj2bwlWIIu6IIwhKmOYhVsvb9tkYuLCzw8PFBUVISCgoIqt5e/r6mv+jyOqt5zmfq9450s1dvVMaYbDXmOGLpv1vL/ePaM/V0/nPhGdSlFKbZhG6IRrToKERERERERkUVY3cS34uJiTJw4EX/5y18wffp0fPvtt2jSpInqWBYTFBSEN954Az/99BNWrVpV7Tqpqan49NNPMXLkSHTq1AmlpaU4ePAg/Pz8MGXKFDRr1qziw+PCwkKjs7i5ueHWrVsV/+7YsSOWL18OAIiJiUFJSQkOHjxY5X7vvPMOWrdujZKSEgC//0V8+SQIZ2dn9O/fH3FxcdBoNNi2bVutGcy1b8aKjv79Q6O7cxcXF2PPnj3QarUVl1vRd78NOZabN29Gu3bt0KVLl2rzFRUVISUlpdKyX375BZcuXUJwcDD8/f3Nth+1qe25VBNDMhqqruNo73r06IGffvoJXl5eCAkJMevZ+whYv349evTogZYtW+KHH35At27dVEcyGLupMnaTft1kztfxOxmS1Rg1PeeMeR6wD02vadOm2LFjB6ZOnYrnnnsOsbGxuH37tupYNikb2diADZiKqaqjWAV76G9bNWjQIAB/XM6yXGZmJtLS0kwyhjGvx+VUvucy5XvHu1mqt+9mzGNh6HNE332ztv/Hs2fsb+Nx4hvVZR/2IRvZiIJt/nELERERERERkcHEily8eFFCQ0PFw8NDNm3apDqOUnPmzBFnZ2eZPXu2pKamSnFxsVy4cEFWrlwp/v7+0rNnTykoKKhYPzw8XADIu+++K1lZWXLz5k3597//La1btxYAsmvXrkrbj4qKEgBSWFhYY4bIyEjx9PSUc+fOSVJSkjg5OcnJkydFROTy5cvSvn17adeunWzfvl2uX78uOTk5smzZMnFzc5P169dXbMfT01N69+4tx44dk6KiIrl8+bLMnz9fAMiCBQvqzGWqfZs9e7YAkCNHjlRafuTIEQEgUVFRtT0kIiKSkZEhbdu2FV9fX4mPj5e8vDxJTU2VmJgY0Wg0snz5coP3W99jWVpaKs2aNZNp06ZVmy04OFg8PT0lIiJCkpKSpKCgQFJSUuTBBx+URo0ayd69e826H7Ud+9qeSzXdz5CMtY199+Ne13FsSIqKimTChAmi0Whk9uzZUlpaqjqSXSkpKZHZs2eLRqORF154QW7duqU6Ur2xm9hNhnSTqV7H61rHkMe9tnFqeixqe84Z+jxgH5rXunXrxN3dXXr16iWXL19WHcfmvCVviZd4SYEU1L2yHbPH/lbF2Nf106dPi4+PjwQEBEhCQoLk5+fLL7/8IpGRkXLvvfeKi4uL3mMZ89peG9XvuUz13tGcfWOJx8LQ54gh+2ZotwcHB0tAQECteal27G/DdJbO8oa8oToGWbGX5CXpIl1UxyAiIiIiIiKyGKuZ+JaSkiL+/v7SsWNH+e9//6s6jlX48ccfZdy4cdKqVStxdnYWDw8Peeyxx2TJkiVSXFxcad2srCyJjY2tWNfX11fGjx8vc+bMEQACQLp37y7JyckV/77zpzqnTp2SsLAwcXd3l1atWsnSpUsr3Z6TkyMzZsyQdu3aibOzszRr1kwGDBhQ5YPgo0ePSmxsrHTu3Fnc3NzEx8dHHnvsMVmxYoWUlZWJiIhOp6uSacyYMfXet7lz54qIVFk+ePBgERFxd3evclvHjh1rfVyys7Nl2rRp0rZtW3F2dhZPT08ZOHCg7Nmzx+D9NuRYHjhwQABIYmJitbnKP3A/efKkDBw4UDw8PESr1Urv3r3lwIEDZt2P2h4/kZqfS3XdT5+Mhj7udR3Hhugf//iHODs7y4gRI+TmzZuq49iFvLw8iYyMFFdXV/n8889VxzEpdhO7yZBuMvZ1/O7Hv66+0CerMY+FSO3POX2fB3Vti31oOocPH5Y2bdpI27Zt5cSJE6rj2IwSKZE20kZmykzVUZSy5/62JFO8rqempsrw4cOlSZMm4ubmJo8//rjs27dP+vTpI25ubrWOVd/X9tqofM9VzhT9XNPkNH3y1vTYWfqx0Pc5YuhjoW+3v/feezXuLxmO/a2/dtJO3pa3VccgK1UmZdJaWsvr8rrqKEREREREREQWoxERgWLfffcdRowYgZ49e2L9+vUN6tKmRPqaNWsWPvvsM1y+fBlOTk5Vbu/atSuys7Nx4cIFBelsR13HsaHav38/oqOjcd9992Hz5s3w8fFRHclmXb58GU888QQuXbqE+Ph4PPzww6ojEZkNX1Ntlz0/dtnZ2YiOjsbJkyexefNm9OzZU3Ukq/ctvsVIjEQ60tEO7VTHUYL9bRs6deqEwsJC/Pbbb0rGt5X3XHW9xg8dOhTbt29HcXGx3XWA6ucIGY/9rZ8ABOAVvIJpmKY6Clmhn/ATQhCCwziMbuBl2omIiIiIiKhhcFAd4Msvv8TQoUMRHR2NLVu2cNIbUQ02b96MJ554wu6+mLA0Hsfq9erVCwcOHMC5c+fQs2dPnDt3TnUkm/Trr78iLCwM169fx/79+/mlOdk9vqbaLnt+7O655x7s3r0b/fr1Q79+/bBhwwbVkazeP/APDMbgBjvpjf1tXTIzM+Hj44Pbt29XWn727FmcOXMG4eHhipLZjrtf47t06YKzZ89W3H7x4kW0bt3aZjuAzxH7xP7WTxGK4ApX1THISumgw724F13RVXUUIiIiIiIiIotROvFtyZIleO655/DnP/8Zq1evhrOzs8o4RFYtNTUVa9asUR3D5vE41qxz5844dOgQXFxc8Nhjj+Ho0aOqI9mUlJQUhIaGwsvLC8nJyQgMDFQdicjs+Jpqu+z9sXNxccHatWvxpz/9CaNHj8Ynn3yiOpLVOomT2Id9+Av+ojqKEuxv63Tt2jXExsbi/PnzuHnzJn788Uc8/fTTaNKkCV5//XXV8axeda/x7733HgoKCrBlyxYcPXoUL774oqJ0psHniH1if9eNE9+oNjroMBzDoYFGdRQiIiIiIiIii1Ey8a2srAxTp07FjBkzsHjxYixZsgQODspPPkdkkxYtWgSNRoNjx47h4sWL0Gg0eO2111THIhvl7++PxMREBAUFoW/fvti/f7/qSDZhx44dCA8PR/fu3ZGYmIjmzZurjkRE1OA5Ojpi6dKlmD9/PiZPnox58+apjmSVPsbHaI/26I/+qqNYHPvbOvn5+WH37t24fv06evXqBW9vbwwbNgyBgYH48ccf0a6d5c9MaOvvuT777DOcOHEC/v7+ePnll7Fw4ULMnDlTdSyjWeNzhEyH/V2zUpSiEIVojMaqo5AVSkc6/ov/IhrRqqMQERERERERWZRGRMSSA5aVlWHixIn46quv8MUXX2DkyJGWHJ6IiPRQVFSEsWPHYvv27YiPj0dERITqSFZry5YteOqpp/DMM89gxYoVPHspEZEVWrVqFWJjY/HSSy/hgw8+UB3HauQiFy3REguwAFMxVXUci2J/ExFZP/Z3ZbnIhRe8sBM7MRADVcchK/N/+D8swiJkIhNOsM1LWRMREREREREZw6LvgkUEkydPxpdffomNGzdi2LBhlhyeiIj05OrqivXr12P8+PEYNmwY4uPjER4erjqW1dmxYwdGjhyJcePGYfny5Tx7KRGRlXr++efh4eGB0aNHAwC/PP//fYWvUIYyPIfnVEexKPY3EZFtYH9Xloc8AEATNFGchKyRDjpEIYqT3oiIiIiIiKjBsdgn/OWT3j777DNOeiPSw7p166DRaKDRaODq6qo6DjVAjo6OWL16NaKjozF06FD8+9//Vh3JquzcuRMxMTEYM2YMvzQnqgM7jazBU089ha+++goff/wxXn75ZdVxrMJKrMRIjIQXvFRHsRj2N5H+2N9kDdjff8hHPgDAAx6Kk5C1uYiLSEEKhmO46ihEREREREREFmeRT/nLJ72tWLECGzZs4KQ3Ij2MGjUKIlLtJSYLCgoQGBiIIUOGGLRNY+9HDZejoyM+//xzDB8+HEOHDkViYqLqSFbhu+++Q3R0dMXl0filOVHt2GlkLUaOHImvvvoKH330UYP/8jwFKTiCI5iIiaqjWAz7m8gw7G+yFuzv3/GMb1STOMTBHe7oj/6qoxARERERERFZnEU+6X/ppZewYsUKbNy4EVFRUZYYkhRq3LgxevbsabfjWQMRQVlZGcrKyqrcVtvxqO1+RDUpn/z2xBNPYNiwYUhKSlIdSamEhARERUXhmWeewcqVK/mluZ1jp5kfO40sbeTIkVi1ahU+/PBDvP7666rjKLMCK9AZnfE4HlcdxSLY3w0L+9v82N9kaexvnvGNarYJmzAYg+EKnp2TiIiIiIiIGh4ncw/wf//3f1i2bBnWr1/PSW9EJuLh4YEzZ85Y7H5ETk5OWLt2LUaMGFEx+S0oKEh1LIs7evQoRowYgREjRvBLcyITYaeRCuPGjcPt27cxYcIEBAQE4MUXX1QdyaIKUIB1WIc38abqKBbB/iYyPfY3qdDQ+7v8jG+c+EZ3ykEO9mM/vsSXqqMQERERERERKWHWiW/r16/H3LlzsXjxYjz55JPmHIqIiMzM2dkZ69atQ0REBCIjI5GcnAxfX1/VsSzm4sWLGDZsGB566CF89tln/NKciMjGPf/887hw4QImT54Mf3//BvVHOmuxFrdxG+MwTnUUs2N/ExHZl4bc3/nIhxvc4GT+v2MmG7IZm+EIRwzCINVRiIiIiIiIiJQw26f+33//PZ577jlMnz4dU6ZMMdcwZCHFxcWYN28eOnXqBDc3N/j4+GDo0KHYsmULSktLAQCLFi2CRqPBjRs3cPDgQWg0Gmg0Gjg5/fGBXElJCdavX4/+/fvDz88PWq0WDzzwAJYsWVLpUidxcXEV99doNEhNTcXIkSPRtGnTimVz5sypczx95eTkYMaMGWjfvj1cXFzQsmVL9OvXD6tXr0ZhYWG16zVq1Aje3t4YNGgQEhMTa8x+9uxZPP300/Dy8kLTpk0xZMiQav/C/dSpUxg+fDg8PT3h7u6OsLAwHDhwoMp6d2+/qKhIr+Nf0/0ssW9kP7RaLbZs2QInJycMGTIEN27cUB3JIvLy8jB48GB4eHhAp9PBxcVFdSSqB3Za1fXYaey0hmrevHl44YUXMHr0aBw6dEh1HItZgRUYgRHwgY/qKGbF/rYv7O+q67G/2d8NVUPt7zzkoQmaqI5BVkYHHQZgAJ8bRERERERE1HCJGZw8eVJ8fHxkxIgRUlpaao4hyMImTJggnp6ekpCQIDdv3pTMzEyZOXOmAJDExMRK67q7u0uPHj2q3U58fLwAkIULF8rVq1clKytLPvroI3FwcJCZM2dWWT8qKkoASO/evSUxMVFu3Lghhw4dEkdHR8nKyqpzPH1kZGRI27Ztxc/PT+Lj4yUvL08yMzPlzTffFACyePHiSuv5+vpKfHy85ObmSmpqqsTExIhGo5EVK1ZUmz0qKkqSkpKkoKBAdu3aJVqtVkJCQiqtm56eLl5eXhIQECAJCQmSn58vx48flwEDBkibNm3ExcWlxmNTWFhYaXldx6O6+5lz30RE+vbtKz4+PpKcnFxjLrItp0+flubNm8vgwYOlpKREdRyzunXrlvTv31/8/f3l7NmzquOQCbDT2GnG7psIO80e3bp1SwYOHCjNmjWT9PR01XHM7pgcEwhkn+xTHcWs2N/2h/3N/jZ230TY3/aoofW3iMgCWSCBEqg6BlmRfMkXV3GVVbJKdRQiIiIiIiIiZUw+8S0nJ0fatm0rPXr0qPLhJ9mutm3byuOPP15leVBQkMFfMvTp06fK8rFjx4qzs7Pk5uZWWl7+Yfb27dtrzFbfLxnGjx8vAGT9+vVVbouMjKz4kqF8va+//rrSOkVFRdKiRQvRarWSmZlZJXt8fHyl9UeMGCEAKr4kERF56qmnBIB88803lda9ePGiuLi4mP1LBnPum4hI7969xdvbW5KSkmrMRbbn4MGDotVq5eWXX1YdxawmTpwoHh4ecuTIEdVRyETYaew0dhrdLS8vT7p27Sr33Xef5Ofnq45jVpNkknSUjlImZaqjmBX72/6wv9nf7G+6W0PqbxGR2TJbukt31THIinwtX4ujOEqWZNW9MhEREREREZGdMumlTkUEzz77LEpKSqDT6eDq6mrKzVuN//znP5UuraHRaDB58mS7XQ4AkZGRSEpKwgsvvIBDhw5VXEomNTUVffr00fvYDRkypNJlSsoFBwfj9u3bOHHiRLX3e+SRRwx/oPR+C5yIAAAgAElEQVSk0+kAAIMGDapy244dOzBt2rRK6w0ePLjSOi4uLoiIiEBhYSG+++67KtsICQmp9O9WrVoBAC5dulSxbOfOnQCAgQMHVlq3RYsWCAoKMmh/jGHOfQOAvXv34urVqwgNDQXQMH+H7NHjjz+O5cuX44MPPsCmTZtUxzGLzz//HCtXrsSaNWvQtWtX1XHMwtp+X9hp9cNOY6ex04zj4eGB+Ph4ZGVlITY2VnUcsylEIdZiLSZiIjTQqI5jNuxv+1sOsL/vXI/9/Qf2N/u7IfR3OV7qlO6mgw590Af34B7VUYiIiIiIiIiUcTLlxhYuXIiEhAQkJiaiWbNmpty0VenSpQtEpNrb7HX50qVLERoais8//xwREREAgLCwMMTGxiI6Orra+1QnNzcX77//PnQ6HS5cuIDr169Xuv3mzZvV3s/d3V3vMQxRXFyM3NxcuLq6wsPDw+j1fH19AQCZmZlVbvP09Kz070aNGgEAysrKKradn58PV1dXNG7cuMr9mzdvjrS0NP13ykDm3LeaNMTfIXs1duxYHDx4EOPHj8d9992HTp06qY5kMr/88gsmTZqEWbNmISoqSnUcs2mIv4/sNHYaO61+y+1Vy5YtsW7dOgwYMAA9evTApEmTVEcyuXVYh5u4iWfxrOooZsP+tr7XDPZ37djf7G9LLbdXDaG/y+UjHx6o+XWCGpYiFGEHduBtvK06ChEREREREZFSJjvj2969e/HGG29g0aJF6NGjh6k2S1ZCo9Fg3Lhx2L17N65fv464uDiICGJiYvDBBx9UWbcmQ4cOxZtvvomJEyciLS0NZWVlEBEsXrwYgHEf0NY2Xl1cXFzg6emJoqIi5OfnG73e5cuXAQB+fn5GZfDw8EBRUREKCgqq3H716lWDtmfo8TDnvlHD8OGHHyIoKAgjR46s8YtCW1NQUICRI0ciJCQECxYsUB2HTIydxk5jp1FNwsPD8frrr2PatGlITk5WHcfkVmAFYhCDZrDPP1Jif9s39jf7m/1NNbH3/i7HM77Rnb7DdyhAAaJgvxP9iYiIiIiIiPRhkolvly9fxujRo/Hkk09iypQpptgkWRkvLy+cOnUKAODs7Iz+/fsjLi4OGo0G27Ztq7Sum5sbbt26VfHvjh07Yvny5SgtLcXBgwfh5+eHKVOmoFmzZhUfiBcWFhqdrabx9FV+doDt27dXua1bt26YPn16pfXu3t/i4mLs2bMHWq22ymVh9FV+SZvyy8uUy87ORmpqqkHbMuZ4mHPfyP65uLjg22+/xaVLl+ymA/7f//t/uHbtGtauXQsnJ5OeHJWsADuNncZOo9q8/vrriIiIwKhRo5CTk6M6jsmcwAkkIxkTMEF1FLNhf9s39jf7m/1NtbHX/r4Tz/hGd9JBh8fwGFqipeooRERERERERErVe+KbiGDs2LHw8PDAihUrTJGJrNSLL76I48ePo7i4GFeuXMG7774LEUF4eHil9R566CGkpaXh/PnzSE5Oxq+//oqwsDA4OjqiT58+yMzMxHvvvYfs7GwUFhYiMTERy5YtMzpXTePp6+2330bbtm0xffp0bNu2Dfn5+bhw4QImTZqEjIyMii8ZytebNm0atm7divz8fKSlpWH06NHIyMjAkiVLKi7BYqiFCxfCx8cH06ZNw65du1BQUICTJ09i7Nix1V5qpjbGHA9z7hvw+19fN23aFIcOHTJ6G2Td7r33XqxatQqrVq3Chg0bVMepl+XLl0On02HdunVo0aKF6jhkJuw0dpqx2Gn2z8HBAWvWrEFZWRlefPFF1XFMZjVWox3aIRzhda9sg9jfDQP7m/1tLPa3/bPX/r4Tz/hG5UpQgm3YhhjEqI5CREREREREpJ7U06effioODg5y8ODB+m6KrNjRo0clNjZWOnfuLG5ubuLj4yOPPfaYrFixQsrKyiqte+rUKQkLCxN3d3dp1aqVLF26tOK2rKwsiY2NlVatWomzs7P4+vrK+PHjZc6cOQJAAEj37t0lOTm54t93/lSntvH0lZ2dLdOmTZO2bduKs7Oz+Pv7y6hRoyQtLa3W9Tw9PWXgwIGyZ8+einWqyz537lwRkSrLBw8eXHG/1NRUGT58uDRp0kS0Wq2EhITI1q1bJSIiomL9P/3pT6LT6apsZ8yYMXUej7ruZ859CwsLE29vb0lKSjL4sSHbEhsbK/fcc49cvnxZdRSjXLhwQby8vGTOnDmqo5AZsdOqX4+dxk6jyvbs2SMajUY2btyoOkq9lUqpBEiAvCFvqI5iFuzvhoH9Xf167G/2N1VmT/19tyAJkgWyQHUMsgIJkiAQyGk5rToKERERERERkXIaEZE65sbV6NKlS7j//vvxwgsv4J133jF2M0REZCfy8vLwwAMPoEePHli7dq3qOAaLiopCamoqjhw5Aq1WqzoOEREpNnHiRMTFxeHkyZNo1qyZ6jhG24mdGIRBSEUqghCkOo7Jsb+JiOhO9tLfd/OHP17Fq5iCKaqjkGKTMAnJSMYRHFEdhYiIiIiIiEi5el3qdNKkSWjevDnmz59vojhERGTLmjRpgs8++wzr1q2DTqdTHccgn3/+ObZu3YqVK1fyS3MiIgIAvP/++9BqtZgxY4bqKPWyBmvQAz3sctIb+5uIiO5mL/19t3zk81KnhDKUIQ5xiEa06ihEREREREREVsHoiW9r1qxBfHw8v2AgIqJK+vXrh2effRZ/+ctfcO3aNdVx9JKZmYkZM2ZgypQp6Nmzp+o4RERkJZo0aYJly5bhyy+/xObNm1XHMUoe8hCHOIzDONVRTI79TURE1bGH/r5bKUpxEzc58Y2QjGRkIAMxiFEdhYiIiIiIiMgqGDXxLTc3Fy+//DImTZqEsLAwU2ciMgmNRlPnD89WSGQeH3zwAUQEr7/+uuooepk5cyY8PT2xYMEC1VGIqsVOI1LniSeewJgxYzB16lQUFRWpjmOwb/ANSlCCERihOorJsb/J2rG/idSx9f6+Wz7yIRB4wEN1FFJMBx0CEYgu6KI6ChEREREREZFV0IiIGHqnOXPmYPny5Th9+jR8fHzMkYuIiGzcZ599hhdffBHHjx9H586dVcep0dGjR9G9e3ds3LgRMTH8i2kiIqrq8uXLCAwMxGuvvYZZs2apjmOQvuiLe3APNmKj6igmxf4mIqK62HJ/3+08zqM1WuMQDuFRPKo6DinUHu0xEiPxNt5WHYWIiIiIiIjIKhg88e3ChQvo2LEjFi5ciKlTp5orFxER2bjS0lJ069YNHTp0wKZNm1THqVG/fv1w48YNJCUlQaPRqI5DRERW6o033sBHH32E9PR03HPPParj6OU3/IZ2aAcddBiGYarjmBT7m4iI9GGL/V2dX/ALHsSD+C/+i07opDoOKXIER/AQHsIP+AGP4BHVcYiIiIiIiIisgsGXOn311Vfh6+uLF1980Rx5iMyua9euel1ypvyHl04iMo6joyPeeecd6HQ6HDhwQHWcasXHx2PPnj1YtGgRvzQnm8ROI7KcV155BVqt1qZ+j77El/CGNyIRqTqKSbG/yZqcPn0aGo0G69atM+h+5c9fjUaDli1bmild/Vy7dg3Lli1DeHg4fHx8oNVqERgYiDFjxuDYsWNV1jf2WBCZky32d3WykAUAuAe2O3mP6k8HHQIQgBCEqI5CREREREREZDUMmvh27NgxrF27Fu+88w5cXFzMlYnI7DZu3AgRqfiJjY0FAOzYsaPS8qefflpxUiLbNmjQIPTr1w8vv/wyjLiytlmVlpbi1VdfxYgRI9CjRw/VcYiMxk4jsozGjRtj3rx5+OSTT5Cenq46jl6+xJcYgzFohEaqo5gM+5vsxcyZMyEiCA4OVh2lRq+88gpeeuklREVF4eTJk8jJycGqVasqLjUcFxenOiJRnWyxv6uTjWw4whHe8FYdhRTahE14Ek9CA078JyIiIiIiIipn0MS3uXPnIiQkBCNGjDBXHiIisjPvvPMOUlJSsHXrVtVRKvnqq6+QlpaGhQsXqo5CREQ2YsKECWjfvj3efPNN1VHq9AN+wCmcwjiMUx3FpNjfRJb1/PPPY+rUqfDz84ObmxvCwsKwdu1alJaWYtasWarjEenFlvq7JtnIhg984AhH1VFIkXSk4wROIBrRqqMQERERERERWRUnfVdMTU3Fjh07EBcXx8vJkE07evSo3uvyEi1E9ffQQw/hiSeewKJFizB06FDVcSosXrwYo0aNQmBgoOooREZjpxFZlpOTE2bPno0XXngBb731Flq1aqU6Uo3WYA06ozMexsOqo5gU+5vIclauXFnt8uDgYGi1Wpw5cwYiws+IyOrZUn/XJAtZvMxpA/cNvsE9uAc90VN1FCIiIiIiIiKrovcZ395//320b98egwcPNmceIiKyQzNmzMD+/fvx448/qo4CANi1axeOHj2Kl156SXUUIiKyMWPGjIGvry+WLl2qOkqNbuEW1mGd3Z3tjf1NZB1u3LiBwsJCdOnShZPeyGbYQn/XJgc5nPjWwOmgw3AMh5P+f8dORERERERE1CDoNfEtKysLX375JaZPnw4HB4Oujkpk88rPclj+k5qaipEjR6Jp06YVy6ZNm1bx3z17/vGXlzt37qxYfs89VT+gzMrKwpQpU9CmTRs0atQIzZo1Q0xMjEFn8CGyBeHh4ejWrRs+/PBD1VEA/H62mL59+yIkJER1FCKLYqcR1Z+zszP+/Oc/45///Cfy8vJUx6nWbuzGVVzFaIxWHcWk2N9kjTp06AARwahRoyqWFRcXY968eejUqRPc3Nzg4+ODoUOHYsuWLSgtLdVru4b0qj7rLlq0qKLHW7ZsiZSUFERERMDDwwNubm7o27cvDh48qFe2jRs3AgDmzp1b57Egsha20N+1yUY2J741YBdwAT/hJ8QgRnUUIiIiIiIiIquj1yy2Tz75BFqtFs8++6y58xBZneHDh0NEEBUVBQCIjY3FpEmTcP78eRw6dAiOjo547bXXICJwd3evdN/IyEiICLp3715luxkZGQgJCcGGDRvwySef4OrVq9i7dy+uXr2K0NBQJCcnW2T/iCxl+vTp2LhxI86dO6c0R2pqKr777jtMnz5daQ4iFdhpRKbx5z//GaWlpVi9erXqKNXagA14DI/hXtyrOorJsL/JlkyePBkfffQRPv74Y+Tk5OC///0vOnXqhKioKHz//fd13t+QXtV33ZkzZ0JEEBwcjOvXr2Pq1KlYsGABMjMzsX//fly9ehXh4eHYt29frdkuX76MOXPmYMKECRg5cmT9DhSRhVl7f9eGE98atm/xLRqjMcIRrjoKERERERERkdWpc+JbSUkJli1bhtjY2CpfgBI1RLNnz0afPn3g5uaGRx99FCUlJdWe+aYur776Kn777Td88MEHeOKJJ9C4cWPcf//9WLduHUSEl3AiuzNq1Cj4+vrik08+UZrjo48+QocOHXjpbiKw04iM5e3tjeeeew4ff/wxRER1nEpu4Ra2YAuewlOqo5gU+5tsyZ49e3D//fejf//+0Gq18PX1xXvvvYegoCC97m9IrxrTwTdu3MAnn3yC0NBQuLu74+GHH8aXX36JW7duYerUqTXmysnJQWRkJPr06YNly5YZfmCIFLPm/q5LFrI48a0B00GHYRgGF7iojkJERERERERkdeqc+LZ7925kZmbi+eeft0QeIqv3yCOPmGQ7cXFxcHBwwJAhQyot9/Pzw/3334+ff/4ZFy5cMMlYRNbA2dkZzz77LNauXavsS4bbt29j/fr1eP7553npbiKw04jqY8KECTh9+jR++OEH1VEq+Q7f4Tqu29WlsNjfZGsiIyORlJSEF154AYcOHaq4vGlqair69OlT5/0N6VVjOtjd3R1du3attOyBBx5AixYtcOzYMWRkZFTJdOPGDQwcOBD33XcfvvrqKzg6Ota5H0TWyFr7uy4841vDlY1sHMRBRCNadRQiIiIiIiIiq1TntwZff/01Hn30UXTo0MESeYisninOfFhcXIzc3FyUlZXB09MTGo2m0s/hw4cBAOnp6fUei8iajBo1CufPn0dSUpKS8RMSEnD16lU8/fTTSsYnsjbsNCLjdevWDZ07d8a6detUR6lkIzYiFKF2dZlT9jfZmqVLl+KLL77Ar7/+ioiICDRp0gSRkZHQ6XR13teQXjW2g728vKodu3nz5gCAK1euVFpeUlKCp556CgEBAfj888856Y1smrX2d1048a3h0kEHZzgjEpGqoxARERERERFZpVonvhUVFWHz5s0YNWqUpfIQ2TQHBwfcunWryvLr169X+reLiwu8vLzg5OSE27dvQ0Sq/enbt6+lohNZxIMPPoj7778fX3/9tZLx161bh9DQULRp00bJ+ES2hJ1GVLeRI0di/fr1FWdzUq0YxXZ5mVP2N9kajUaDcePGYffu3bh+/Tri4uIgIoiJicEHH3xQ630N6VVjOzgnJ6faMzCXT3grnwBXLjY2FsXFxdiwYQOcnJwqlnfo0AGHDh0y9jARKWNt/V2XAhSgCEWc+NZA6aBDJCLhjvr/0RIRERERERGRPap14tv27duRn5+Pp56yry9OiMzF398fFy9erLQsMzMT586dq7JuTEwMSkpKcPDgwSq3vfPOO2jdujVKSkrMlpVIlaeffhobNmyw+PO7qKgIW7Zs4WRuIj2x04jq9swzzyAzMxP79u1THQXA75c5zUOeXV3mlP1NtsjLywunTp0CADg7O6N///6Ii4uDRqPBtm3b6ry/Ib1qTAcXFRUhJSWl0rJffvkFly5dQnBwMPz9/SuWz58/HydOnMDmzZvh4uJS984T2QBr6++6ZCMbADjxrQHKRS72YA8vc0pERERERERUi1onvq1fvx69evVCQECApfIQ2bQBAwbg0qVL+Mc//oGCggKcOXMGU6dOrfIX8wDw9ttvo3379nj++eexY8cO5Obm4urVq/j000/x97//HYsWLar01/RE9mLUqFHIysrC3r17LTrutm3bcOPGDU7mJtITO42obh07dkTXrl2xfv161VEA/H6Z08fxOFqjteooJsP+Jlv14osv4vjx4yguLsaVK1fw7rvvQkQQHh5e530N6VVjOtjT0xN//etfkZycjBs3buCnn37C2LFj0ahRIyxZsqRivdWrV+Nvf/sbfvjhB3h4eFS5lOqZM2dMe9CILMTa+rsunPjWcG3FVggEQzBEdRQiIiIiIiIiq1XjxLeysjLs3r0bUVFRlsxDZFGrV6+GRqPBp59+CgAYNGgQNBoNCgoKKtY5dOgQNBoNNm/eDADQarXQaDTVbm/BggWYMGECFi5ciObNm2P8+PF45ZVX4Ofnh5ycHGg0GsyZMwfA75eP+fHHHzF8+HBMnjwZzZo1Q6dOnbBp0yZs3rwZI0eONPPeE6kRGBiI++67DwkJCRYdNyEhAY888gj8/PwsOi6RpbDTiNSIioqyeKdVpxjFiEe83V3mlP1Ntmjfvn3o1KkTRo0aBR8fH3Tu3Bk7d+7EihUr8Ne//hUAsGjRImg0Ghw7dgwXL16ERqPBa6+9BsCwXjWmgxs3boyPP/4Yf/vb3+Dv749evXrB29sb//73v9G7d++K9b755hszHykidaylv/WRhSwAnPjWEG3CJoQjHN7wVh2FiIiIiIiIyGppRESqu+H48eMIDg7G4cOH0a1bN0vnIiIiOzZp0iQcPnwYhw4dstiYnTp1QnR0NN5++22LjUlERPYvMTER4eHh+O2339C6tbozrcUhDk/iSZzDOQTAfs7Yzf4mMq2uXbsiOzsbFy5cUB2FSClr6W99rMEaTMAEFKEIGlT/Rytkf27iJpqjOd7H+4hFrOo4RERERERERFarxjO+7du3D56ennjwwQctmYeIiBqA3r174+eff0Z+fr5Fxrty5QrS0tIqncGCiIjIFEJDQ+Hq6or9+/crzbERG9EDPexq0hv7m4iIzMVa+lsf2chGMzTjpLcGZid2ohCFGIZhqqMQERERERERWbUaJ77t378fvXr1gqOjoyXzEBFRA9C7d2+UlJQgOTnZIuPt3bsXjo6O6NGjh0XGIyKihsPV1RUPP/ww9u3bpyxDEYqwFVvt7jKn7G8iIjIXa+hvfeUgh5c5bYB00KEHesAf/qqjEBEREREREVm1aie+iQi+//57/mU9ERGZhZ+fHzp27GixLxn279+Phx56CB4eHhYZj4iIGpY+ffoo/eI8AQkoQAGexJPKMpgD+5vIdBYtWgSNRoNjx47h4sWL0Gg0eO2111THIlJKdX/rKxvZnPjWwNzGbWzDNkQjWnUUIiIiIiIiIqtX7cS3c+fO4fLlywgNDbV0HiIiaiAef/xxpKSkWGSsn376iZ1GRERm8/jjjyM9PR3Xr19XMv4WbEEIQtACLZSMby7sbyLTmTlzJkSk0s+CBQtUxyJSSnV/6ysLWZz41sDswR5cwzUMx3DVUYiIiIiIiIisXrUT31JTUwEAnTp1smgYIiJqODp27Ii0tDSLjJWWlsZOIyIis+nYsSMAWKzX7lSGMmzDNgzFUIuPbW7sbyIiMieV/W0InvGt4dFBh+7ojrZoqzoKERERERERkdWrduJbWloamjZtCh8fH0vnISsTFxcHjUZT8VNUVGSybZdfakWj0aBly5Z1rr9u3bqK9V1dXU2WQzV73S+iugQFBeH8+fMoLCw06zhXrlzBtWvXEBQUZNZxyDaw18zPXveLqDZt2rSBi4uLki/OU5CCTGRiGIZZfGxzYn/Tndjf5mev+0VUG5X9bYhsZKMpmqqOQRZShjJswRbEIEZ1FCIiIiIiIiKbUO3Et/T0dH7BQACA4cOHQ0QQFRVl8m2XX2olODhYr/VHjRoFEUFERITJs6hU234VFBQgMDAQQ4YMMWibxt6PyJICAwNRVlaGM2fOmHWc9PT0ivGI2Gvmx16jhsjBwQHt2rWr6BxLikc8WqM1HsADFh/bnNjfdCf2t/mxv6khUtnfhshABvzhrzoGWcgBHEAmMjnxjYiIiIiIiEhPNU584xcMROqJCMrKylBWVlbltsaNG6Nnz54G34/IWgQGBsLBwcHsf12flpYGrVaLgIAAs45DRHVjr5E9CwwMVDbxLQqmnwykGvubyHqwv8meqepvfRWiENdwDS3QQnUUshAddLgP96ETeLl3IiIiIiIiIn04Vbfw9OnTCA0NtXQWIrqLh4eHUWfDMvZ+RJbk4uKCVq1a4fTp02Yd58yZM+jQoQMcHKqd601EFsReI3sWGBiIffv2WXTMcziH4ziORVhk0XEtgf1NZD3Y32TPVPS3IS7hEgBw4lsDshmbMQZjVMcgIiIiIiIishnVfotw7do1NG3a1NJZiIiogfHx8cG1a9fMOgY7jYiILKFp06Zm77S7bcEWNEZj9EIvi45rCexvIiKyBBX9bYgMZAAAL3XaQPyEn/A//A/RiFYdhYiIiIiIiMhmVDvxLT8/Hx4eHpbOQjYgMzMTTz/9NLy8vNC0aVMMGTKk2r/gzsnJwYwZM9C+fXs0atQI3t7eGDRoEBITE/Ue69SpUxg+fDg8PT3h7u6OsLAwHDhwoF7578zl4uKCli1bol+/fli9ejUKCwsNyh8XFweNRlPxc/bsWb2Ojb77dff2i4qKAACLFi2CRqPBjRs3cPDgwYrbnZycar2fJfaNyFAeHh4oKCgw6xj5+flo3LixWccg28VeY6+x18hULNFpd4tHPAZhEFzgYtFxLYH9TbVhf7O/2d9kKir62xCXcAkOcIAvfFVHIQvQQYc2aINu6KY6ChEREREREZHtkLvcvn1bAMimTZvuvokasKioKAEgUVFRkpSUJAUFBbJnzx5p0qSJhISEVFo3IyND2rZtK76+vhIfHy+5ubmSmpoqMTExotFoZMWKFZXWDw4OloCAgErL0tPTxcvLSwICAiQhIUHy8/Pl+PHjMmDAAGnTpo24uLgYvA/lufz8/CQ+Pl7y8vIkMzNT3nzzTQEgixcvNip/dcdm165dotVqqxwbY/arfPuFhYWVlru7u0uPHj1q3N/q7mfOfRMR6du3r/j4+EhycnKNuYjuNHjwYHnuuefMOkZ0dLQ888wzZh2DbA97jb3GXiNT+9e//iVubm4WGy9f8sVFXOQL+cJiY1oS+5uqw/5mf7O/ydQs3d+GWiyLxU/8VMcgC+kknWSGzFAdg4iIiIiIiMimVJn4dvXqVQEgCQkJKvKQlSr/oDk+Pr7S8tGjRwsAycrKqlg2fvx4ASBff/11pXWLioqkRYsWotVqJTMzs2J5dV8wPPXUUwJAvvnmm0rLL168KC4uLkZ9wVCea/369VVui4yMrPiCwdD8NR2bESNGVDk2xuyXKb9gMOe+iYj07t1bvL29JSkpqcZcRHd6+umnJSYmxqxj9O/fXyZOnGjWMcj2sNfYa3Xtmwh7jQzzzTffCAC5ffu2RcbbKBvFURwlS7LqXtkGsb+pOuxv9ndd+ybC/ibDWLq/DTVLZslD8pDqGGQBJ+SEQCDfy/eqoxARERERERHZlCqXOi0/vT8vdVq9//znP5UutaHRaDB58mS7XX63kJCQSv8OCAgAAFy6dKlimU6nAwAMHjy40rouLi6IiIhAYWEhvvvuu1qP886dOwEAAwcOrLS8RYsWCAoK0vPRqqw816BBg6rctmPHDkybNq1e+e8+Nq1atQJQ+diYY78MYc59A4C9e/fi6tWrCA0NBdDwfl/0/T2iP3h4eCA/P9+sY/BSabWztt8X9pr+2GvsNWv5PaLflb9/unHjhkXGi0c8QhGKe3CPRcazNPZ37aztdYH9rT/2N/vbWn6P6HeW7m9DZSAD/vBXHYMsYBM2wRe+CEWo6ihERERERERENsXp7gWlpaUAAAeHKnPiCECXLl0gItXeZq/L7+Tp6Vnp3+XPk7KyMgBAcXExcnNz4erqWu3kSV9fXwBAZmZmjWMUFxcjPz8frq6u1X7Z1c6S4sMAACAASURBVLx5c6SlpdWZ9e5t1pZL3/Vqy3/3sWnUqBGAysfG1PtlCHPuW00a4u+LPr9H9AcnJ6eK3jGXsrIyODo6mnUMW9YQf0/vxF5jrwHsNWOWU1XlXVNSUmL2scpQhh3YgZmYafaxVGF/164hvh7dif3N/gbY38Ysp6os2d/GuIRLaId2qmOQBeigQzSi4Qj+/w8RERERERGRIarMbiv/4NNa/9KRrJuLiws8PT1RVFRU7VmcLl++DADw8/OrdRseHh4oKiqqOAPhna5evWryXKbMX9u2TblfGo3G4PHNtW9ExsrPzzf7GUbd3d2r/Z0j0gd7rfYM7DWiP5Q/Dy1x5uwjOIIsZGEQqp4xyl6wv6k+2N+1Z2B/E/3Bkv1tjAxkwA/8fbB3Z3EWR3AE0YhWHYWIiIiIiIjI5tQ48c3cl54j+xUd/fuHNNu2bau0vLi4GHv27IFWq61ySZW7lV/2pfwSLOWys7ORmppar1zbt2+vclu3bt0wffp0k+WviSn3y83NDbdu3ar4d8eOHbF8+fJa72POfSMyhiUuY+bh4cEvzqle2Gs1Y68R/aGgoACNGjWqOAOROe3CLvjCF13QxexjqcL+pvpif9eM/U30B0v2tzEu4AJaoZXqGGRmm7AJnvBEH/RRHYWIiIiIiIjI5lSZ+Obq6gpnZ2d+yUBGe/vtt9G2bVtMmzYNW7duRX5+PtLS0jB69GhkZGRgyZIlFZcvqcnChQvh4+ODadOmYdeuXSgoKMDJkycxduxYoyfJlOeaPn06tm3bhvz8fFy4cAGTJk1CRkZGxRcMpshvif166KGHkJaWhvPnzyM5ORm//vorwsLC9DoG5tg3AAgPD0fTpk1x6NAho7dBDYslzvjWuHFjdhrVC3vNMvvFXiNbZ4lOK7cbu9Ef/aGBYWdasiXsb6ov9rdl9ov9TbbOkv1tqOu4jjzkceJbA6CDDkMxFI1gnRMwiYiIiIiIiKyaVMPb21s+/fTT6m6iBiY5OVkAVPqZO3euiEiV5YMHD664X3Z2tkybNk3atm0rzs7O4unpKQMHDpQ9e/ZUrPPee+/VuG0RkdTUVBk+fLg0adJEtFqthISEyNatWyUiIqJi/T/96U8G7c/dufz9/WXUqFGSlpZW63rV5Tf22Oi7Xzqdrsp2xowZU7GdU6dOSVhYmLi7u0urVq1k6dKlIiJ13s+c+xYWFibe3t6SlJRk0ONCDdfDDz8sr7zyilnHiI2NlYiICLOOQbaDvcZeY6+RubzzzjvSpk0bs49TKIWiFa38S/5l9rFUYn/Tndjf7G/2N5mLpfrbGMfkmEAgJ+SE6ihkRpfkkjiIg+hEpzoKERERERERkU3SiIjgLm3atMGkSZMwa9asu28iIiIymY4dO2LcuHF47bXXzDbGrFmzkJiYiJSUFLONQURENHfuXGzduhXHjh0z6zgJSMBADMQ5nLPrM8Cwv4mIyBIs1d/G2IZtGIIhyEMePGCdZ6Wj+luKpZiDObiCK9BCqzoOERERERERkc2pcqlT4PeJb//73/8snYWIiBqQsrIy/Pbbb2jTpo1Zx7n33ntx5swZs45BRET066+/om3btmYfZzd2ozM62/WkN4D9TURElmGp/jbGOZyDD3w46c3OfYtvMQRDOOmNiIiIiIiIyEjVTnwLCgpCenq6pbMQEVEDcvbsWRQXFyMoKMis4wQFBeHatWvIyckx6zhERNSwpaenm73TgN8nvvVDP7OPoxr7m4iILMFS/W2M8zhv9xPdG7psZON7fI8n8aTqKEREREREREQ2q9qJb4GBgUhLS7N0FiKjaDSaOn/mz5+vOiYR3aW8ZwIDA806TvmXGOw1shXsNSLblJ6ebvZOy0EOjuFYg5n4BrC/yXawv4lskyX621jncA6t0Vp1DDKjTdiERmiEQRikOgoRERERERGRzXKqbmFQUBAuXLiAGzduwN3d3dKZiAwiIqojEJER0tPT0axZM3h7e5t1nFatWkGr1SI9PR2hoaFmHYvIFNhrRLYnMzMTeXl5Zj9jzG7shgMc0Bu9zTqONWB/k61hfxPZHkv1t7HO4zwewAOqY5AZfYtvMQiD4A5+/k5ERERERERkrBovdSoiOH36tKXzEBFRA2GpS8o4ODigQ4cOPGMMERGZjaXOYrobu/EIHoEnPM06jjVgfxMRkblZqr+NdQ7neKlTO3Yd17EXe3mZUyIiIiIiIqJ6qnbiW4cOHeDu7o6UlBRL56F6+O233zBs2DDk5eWpjlKj06dPQ6PRYN26dTWuk56eDo1Gg8cee6za2xctWlRxqZiWLVuaKyrd4aOPPkLLli2h1WoxaNAgnDt3rtr1Ro0ahb59+xq07WvXrmHZsmUIDw+Hj48PtFotAgMDMWbMGBw7dqzK+tU9h+bMmYP169cbtlOkXEpKCoKDgy0yVnBwMDvNxrDTyFzYaWQOKSkpaN68Ofz9/c06zh7sQX/0N+sY1oT9TfaocePGel0WVaPRYOXKlXptk/8/QWQcS/W3McpQhou4yIlvdkwHHTTQYDAGq45CREREREREZNOqnfjm7OyM0NBQ7N+/39J5yEhHjx7Fww8/jAEDBqBJkyaq49TLv/71LwDADz/8gJMnT1a5febMmRARi02Yaei2bt2K6dOnY8mSJfjtt99QWFiIESNGVFkvISEBOp0O//znPw3a/iuvvIKXXnoJUVFROHnyJHJycrBq1SocPXoU3bt3R1xcXJ3bmDhxIl599VW8/vrrBo1N6hQUFODnn39G796WuVRbr169kJSUhNu3b1tkPKofdhqZCzuNzGXfvn3o1asXNBqN2cY4jdP4H/6HCESYbQxrw/4me1RQUIAjR44AAKKioiAi1f4Y8v/J/P8JIuNYor+NdREXcRu30QZtVEchM/kW32IgBqIJbPs9LxEREREREZFq1U58A37/kmHv3r0WjELGysvLw9ChQ/Hkk09i8uTJFhu3cePG6Nmzp0m3WVZWhi+++ALdunUD8MeEAdW5VLGGfVmyZAn69OmDJ598Es2bN8ff/vY3pKSk4ODBgxXrFBUVYdKkSZg1axY6depk8BjPP/88pk6dCj8/P7i5uSEsLAxr165FaWkpZs2aVef927dvD51Oh7feegsbNmwweHyyvIMHD+L27dsWe3736tULBQUFOHz4sEXGI+Ox08yfSxVr2Bd2GplDWVkZvv/+e7NP5t6P/dBCi0fxqFnHsSbsbyIiMhdL9bexzuAMAKAd2ilOQuaQj3zswR5e5pSIiIiIiIjIBGqc+Na7d2+cP38eZ8+etWAcMsa7776LzMxMzJs3T3WUektISICTkxOWL18OAFizZg1KSkoUp2rYTp06hfvuu6/i3/fff3/F8nJvvfUWAGDu3LkGb3/lypX49NNPqywPDg6GVqvFmTP/H3t3HhdVvf8P/DXsi4rggksuuKQGikvumqIs+hUDye2auaS5ZNdwq7QySzPXTM1uLpVpXvdcUFzQ0KuomYLicgG3XEERFEEWQd6/P/zBjQCFYWY+w/B6Ph48HjFzzvm8zozMa5rzmXOuQEReuB13d3f07dsXkyZN4r+ZUuDw4cNo1KgRatSoYZDxcsY6fPiwQcYj7bHTSJ/YaaQPZ8+excOHD/V+4PwojqIN2sAKVnodx5iwv6ksO3ToEEaOHKk6BpHJMlR/a+sqrsIOdnCGs+oopAc7sANP8RS+8FUdhYiIiIiIiKjUK3TiW9u2bWFjY8ODDEZORLBq1Sq0bdvWYBNI9OnHH3/EsGHD8Oqrr6JZs2a4e/cugoODVccq0wo7QJ9zKZCoqCjMmzcP3333HWxsbHQ27uPHj5GWlgY3N7ciX3akT58+uHXrFnbv3q2zHKQfhw8fNvgBhk6dOrHTjBw7jfSNnUb6cPjwYTg5OeVOpNSXMIShIzrqdQxjxP6msua9995DYGCg6hhEJs9Q/a2tq7iK+qgPDYzvMqxUcluxFZ7whBOcVEchIiIiIiIiKvUKnfhmbW2Njh07Ys+ePYbMQ8V09uxZ3L17F+7u7nlu3759OzQaTe7Pn3/+iQEDBqBixYqoVKkSfH19ceXKlXzbS0hIwMSJE1G/fn1YWVnB0dERPXv2RGhoaO4yCxYsgEajwePHjxEWFpY7hoWFxQvzNmjQACKCgQMH5rsvMTERQUFBGDp0KABg+PDhAJ5NHCiKouaKj4/H+PHjUbduXVhZWaFKlSoICAjAmTNnCn38oqOj0b9/f1SqVCn3tlWrVhX7Mc7KysLGjRvh5eWFatWqwdbWFk2bNsXixYuRnZ1d7H0pyvNVlH25f/9+oY9r48aNcf78+dzfL1y4AODZGTgAYOzYsQgICIC3t3eRnqei2rx5M4D8Z9x53r+h5s2bAwD27dun0yykWwkJCfjjjz/g4eFh0HG7deuGw4cPIzU11aDjUtGx0/6HncZOY6eVHnv37kXXrl1hZlbo/1qV2H3cxyVcKpMT39jfVJYVtWufJyMjA9OnT0fjxo1hZ2cHJycn9O7dGzt37sTTp0/zLFuU9xVEpsIQ/V0SV3CFlzk1UalIxX7s52VOiYiIiIiIiHRFnuNf//qX2NnZSXJy8vMWI4XWrl0rAGT27NkF3u/n5ycAxM/PT44dOyYpKSkSEhIitra20rp16zzLxsbGiouLizg7O0tQUJAkJSVJdHS0BAQEiEajkZUrV+ZZ3t7eXjp27KizfVm6dKl4eHjk/h4fHy+WlpZiYWEhd+/ezbe8u7u71KxZM9/tz8t1584dqVOnjjg7O8vu3bslOTlZzp8/L126dBEbGxs5duxYnuVzHr8uXbpIaGioPH78WE6cOCHm5uYSHx+fZ5miPMZBQUG5z1diYqLEx8fLkiVLxMzMTCZPnlysfSnu81WUfSnIjh07xMzMTDZt2iR3796VLl26SKtWrUREZPXq1eLg4CCxsbFy584d6d27t9ja2kr16tVlzpw5hW7zReLi4sTZ2VlGjhxZrPWSkpIEgHTu3FnrsUn/vv/+eyXdcu/ePbGwsJANGzYYdFwqOnYaO42d9j/stNLBUN2yQ3aIRjSSIAl6HccYsb/JFEVERAiAQn/ef/99ESl+1xb0fmLkyJHi4OAg+/fvl9TUVImLi5PJkycLAAkNDc1drrjvK4hKs9LQLW2kjUyUiapjkB5slI1iLuZyT+6pjkJERERERERkEp478S3nIO26desMlYeKad68eQJAli1bVuD9OQeGg4KC8tzet29fAZDn4PCwYcMEgKxfvz7Psunp6VKjRg2xtbWVuLi43Nt1PUmgZcuWsmbNmjy39enTRwDIggUL8i2vzSSBoUOHCoB8/6ZjY2PF2to69+B3jpzHLzg4uNDcxXmMg4KCpGvXrvm2MXjwYLG0tJSkpKQi70txn6+i7EthFi5cKDVq1BBra2vx8vKSa9euSUJCglSpUiX3356Hh4e0bt1a7ty5Izt37hQLC4t82Yri/v370rx5cxkwYIBkZWUVe32NRiMNGjQo9npkOF27dpX+/fsrGdvb21v8/f2VjE0vxk5jp7HT8mKnGb9ly5aJnZ2dpKSk6HWcD+QDcRVXvY5hzNjfZGpyJr75+fnlu2/cuHF5Jr4Vp2sLej/h4uIiHTp0yLeNl19+Oc/Et+K+ryAqzQzV3yVRWSrLUlmqOgbpQX/pL92lu+oYRERERERERCbjuefzr1y5Mjw9PbFhwwatzyhH+pWeng4AsLS0fO5yrVu3zvN7rVq1AAB37tzJvW3btm0AgF69euVZ1traGt27d0daWpreLrcVGRmJS5cu4Y038p7mP+fScD/99JNOxtm+fTvMzMzg6+ub5/Zq1arB1dUVp0+fxq1bt/Kt16ZNmxduuyiPsa+vb55LtuVwd3dHZmZm7iXXikLb56so+/J3EydOxO3bt5Geno79+/ejbt26+OCDD+Di4oIxY8bg/PnzCA0Nxaefforq1aujd+/e8Pb2xuLFi4s1zuPHj+Hj44NXXnkF69atg7m5ebGzWlhYIC0trdjrkWHExsbiyJEjBV7WzxD+8Y9/IDg4GImJiUrGp+djpxUPO42dRupt2LABfn5+sLe31+s4YQgrk5c5zcH+prJKF13bo0cPHDt2DKNGjcKJEydyL28aHR2Nrl275i6n7fsKotLIUP2trUd4hPu4j/qorzoK6Vga0hCMYF7mlIiIiIiIiEiHnjvxDQAGDhyIvXv3IiEhwRB5qJhsbGwAAJmZmc9dzsHBIc/vVlZWAIDs7GwAQEZGBpKSkmBjY4Py5cvnW9/Z2RkAEBcXV+LMBfnxxx+RnJwMe3t7aDSa3J/XX38dAHDhwgWcPHmyRGPk7GN2djYcHBzyjKPRaBAeHg4AuHTpUr51i/Jh6IseYwBISkrC9OnT0bRpUzg6OuaOPWXKFABAampqsfZFm+dLFx/shoWF4eeff8by5cthZmaG6OhoAMArr7ySu4ybmxuioqKKvM2srCz069cPNWvWxM8//6zVBIGc7dja2mq1Lunfxo0bYW9vjx49eigZPyAgAGZmZtixY4eS8en52GlFx04r+r68CDuNtHXz5k2EhYXpfTJ3BjJwGqfRAR30Oo4xY39TWfLtt9/im2++AaCbrl22bBnWrFmDq1evonv37qhQoQJ69OiRO+kcKNn7CqLSxlD9XRJXcAUAUA/1FCchXduLvUhFKvzhrzoKERERERERkcl44cQ3f39/WFhYYOPGjYbIQ8VUvXp1AM8+EC8Ja2trODg4ID09HcnJyfnuv3v3LoBn3/bOodFoSjRmjszMTKxbtw5hYWGQZ5ffzfMTGBgIoOhnyCksl7W1NSpWrAgLCwtkZmYWOJaIwMPDQyf7VZDevXtj5syZeOeddxATE4Ps7GyICBYtWgQAEJEi70txny9dyczMxJgxY/DPf/4TzZs3B/C/3H/Na2ZmVqx/I6NHj0ZGRgY2bdoECwuL3NsbNGiAEydOFGkbjx49gojk/l2Q8Vm7di369OmjbCJHhQoV0LNnT6xZs0bJ+PR87LT82GnsNHaa8frll1/g4OAAHx8fvY5zGqeRjvQyfcY39jeVVcXt2oJoNBq89dZbOHDgAB4+fIjt27dDRBAQEICvv/4agHG8ryAyFEP1d0lcxVWYwQx1UVd1FNKxrdiKTuiE6uB7fCIiIiIiIiJdeeHEtwoVKmDw4MH45ptv8pzlg4yDm5sbAOjkkiN9+vQBAOzevTvP7RkZGTh48CBsbW3zfDBoZ2eHJ0+e5P7eqFEjrFixotjjBgUFoXLlyujQoeCzWIwYMQIAsH79+iJd7ut5uQICApCVlYWwsLB8682dOxe1a9dGVlZWsfehKJ4+fYqwsDBUq1YN48ePR5UqVXIPohe2X8/bl+I+X7qycOFCPHz4EF988UXubY0bNwaAPJfauXjxIho1alSkbc6YMQMXLlzAjh07YG1trXW227dvA/jf3wUZl0OHDiE8PBxjx45VmmPs2LE4dOgQIiIilOag/Nhp+bHT2GnsNOOUmZmJ7777DiNHjizR81wUx3AMVVEVDdBAr+MYO/Y3lTXadG1BKlasmHvWUktLS3h5eWH79u3QaDR5elfl+woiQzFkf5dEDGJQG7VhDePNSMWXgQzswi5e5pSIiIiIiIhIx1448Q0AJk2ahCtXruQ7GEnqubu7o2rVqjh79myJt/XVV1/BxcUFgYGB2LVrF5KTkxETE4NBgwYhNjYWixcvzr3cGAC0bNkSMTExuHnzJo4fP46rV6+ic+fOxR73p59+wttvv13o/W5ubmjTpg2SkpLw66+/vnB7z8v11VdfoX79+nj77bexZ88eJCUlITExEcuXL8cXX3yBBQsW5Dkziy6Zm5uja9euiIuLw/z583H//n2kpaUhNDQU33//vVb7UpznSxf+/PNPzJw5E0uWLEG5cuVyb3dzc4OHhwdmzZqF2NhY7NmzB3v27MGECRNeuM3Vq1fj888/x++//47y5cvnu6zOlStXipzvzJkzAABvb+/i7xzp3cKFC9G5c2e0bdtWaQ4vLy+4u7vnnimDjAc7LT92GjuNnWac1q9fj7i4OLz33nt6HysMYWX6bG852N9U1mjTtYUZM2YMIiMjkZGRgXv37mHevHkQEXTr1i13GZXvK4gMxZD9XRLRiEYjFO1LF1R6hCAEj/AIfdBHdRQiIiIiIiIi0yJF1LNnT+natWtRFycDmjZtmlhYWMjt27dzbzt+/LgAyPPz8ccfi4jku71Xr165692/f18CAwPFxcVFLC0txcHBQXx8fOTgwYP5xo2KipLOnTuLvb291KpVS5YtW1as3Ddv3syTo23btvmWuXbtWr68Bf3k7FtRciUkJMjEiROlXr16YmlpKVWqVBFvb28JCQl57uP39z8XbR7j+Ph4GT16tNSqVUssLS3F2dlZhg0bJh999FHusq1atSryvhTl+SrKvhRVr169xNfXt8D7bt++Lb6+vmJjYyPVqlWTOXPmFHmbL3p+jx8/XqRt9evXT2rWrClPnjwp8j6RYURHR4uZmZls27ZNdRQREfnpp5/E0tJSbty4oToK/Q07jZ3GTnuGnWbcmjdvLoMGDTLIWM7iLPNlvkHGMnbsbzIF9vb2+brB2dm5wGWL2rXz588vtMfPnDkjo0ePliZNmoidnZ04OTlJu3btZOXKlZKdnZ1nvKK8ryAqzQzZ3yXRVtrK+/K+6hikY8NkmLSX9qpjEBEREREREZkcjYhIYZPi/urAgQPw8vLCyZMn0bp166KsQgaSlJQEV1dX+Pr6Fvub30Sm4uzZs2jRogX+/e9/Y+DAgarj0N+MHj0aBw4cQExMDMzNzVXHwZMnT1C3bl0MHToUX331leo49BfsNCJ2mrHL+f+i33//HW3atNHrWDdxE7VRG4dxGK/hNb2OVRqwv4mISFuG7O+SqoRKmIVZGIuxqqOQjmQiE9VQDdMwDZMwSXUcIiIiIiIiIpNSpEudAoCnpyeaNWuGhQsX6jMPacHBwQFBQUHYsmULli1bpjoOkcFdvXoVAQEBmDp1KicIGKHY2FisXbsWEydONIpJbwBgZWWFcePGYfny5Xj48KHqOPQX7DQq69hpxm/evHno0qWLQQ6ahyMcGmjQHM31PlZpwP4mIiJtGbK/S+Ie7iERibzUqYn5Db8hEYm8zCkRERERERGRHhR54hsAfPbZZ9i0aRNOnTqlrzykpRYtWuDUqVPYs2cPHj16pDoOkUEtX74cX375Jb788kvVUagAn332GZycnDB8+HDVUfIYN24czM3NMWfOHNVR6G/YaVSWsdOMW2hoKEJCQvDpp58aZLwIRKABGqACKhhkvNKA/U1ERMVl6P4uiWhEAwAnvpmYrdiKV/Eq6qGe6ihEREREREREJqfIlzrN0blzZ5ibm+PQoUN6ikRERKYiKioKTZs2xQ8//IAhQ4aojpPP4sWL8dFHHyEqKgp16tRRHYeIiIxYdnY2WrdujZo1a2Lnzp0GGdMPfrCBDTZio0HGKy3Y30REVFQq+rskVmEVJmACHuERNNCojkM68BRPUQM1MAET8BE+Uh2HiIiIiIiIyOQU64xvALBgwQL85z//wa5du/SRh4iITMiUKVPg6uqKwYMHq45SoHfffRe1atUqFd/8JyIitdauXYuzZ8/iq6++MtiY4QhHC7Qw2HilBfubiIiKSkV/l0Q0otEIjTjpzYQcxmHcwz1e5pSIiIiIiIhIT4p9xjcA6NevH86fP49z587BwsJCH7mIiKiUO3z4MLp27Yr9+/fDy8tLdZxCbd68GQMHDsTJkyfRqlUr1XGIiMgIpaeno1GjRujRoweWL19ukDETkIDKqIx92AdveBtkzNKE/U1ERC+ior9L6nW8jvIoj3VYpzoK6cg4jEMYwnAGZ1RHISIiIiIiIjJJxT7jGwB89dVXuHr1KlasWKHrPESF2rBhAzQaDTQaDWxsbFTH0RlT3S8q27KysjBx4kT4+PgY9aQ3AOjbty/atGmDyZMnQ4u54ERaM9XXf1PdLyrbFi5ciISEBMyYMcNgY4YjHADgDneDjVmasL9JFVPtOVPdLyrbVPR3Sf0X/0VjNFYdg3QkG9nYhm14A2+ojkJERERERERksrSa+NagQQNMmjQJU6dOxY0bN3SdiahAAwcOhIige/fuqqPo1PP2KyUlBQ0bNoSvr2+xtqntekS68vXXX+PixYv45ptvVEd5IY1Gg6VLl+Lo0aNYuXKl6jhUhrDXio69Rir997//xaxZs/DZZ5+hevXqBhs3HOGoiZpwhrPBxixN2N+kCvu76NjfpJKq/i6JVKTiKq7CDW6qo5COhCEMsYhFX/RVHYWIiIiIiIjIZGk18Q0APvvsM9SqVQtvv/02v2FPpCciguzsbGRnZ+e7r1y5cujUqVOx1yPSt+joaMyYMQOfffYZGjcuHd9Uf/XVVzFp0iRMmTKFE7qJ9Ii9RqVNdnY2Ro0ahSZNmmDChAkGHTsCEWiJlgYds7RhfxMZBvubShuV/V0SF3AB2chGUzRVHYV0ZCu2ohEaoQmaqI5CREREREREZLIstF3R2toaP/zwAzp27IjVq1dj+PDhusxFRADKly+PK1euGGw9opLKzs7GyJEj0ahRI0yaNEl1nGL5/PPPERQUhDFjxiA4OFh1HCKTxF6j0mbRokU4efIkTp8+DQsLrf/XSSsRiMBADDTomKUR+5tI/9jfVNqo7O+SOIdzsIMd6qGe6iikAwLBNmzDMAxTHYWIiIiIiIjIpGl9xjcAaNu2LcaPH48JEybg1q1buspERESl1JIlS3DixAn8+OOPsLS0VB2nWHImdO/fvx8///yz6jhERKTYtWvX8Nlnn+GTTz6Bm5thLzmWghRcxmW0QAuDjlsasb+JiOivVPZ3SZ3DObjCFWYl+7iWjMTv+B03cANv4A3VUYiIiIiIiIhMWok/SZk1axYqV66M0aNH85KnZVB8fDzG5UNP5wAAIABJREFUjx+PunXrwsrKClWqVEFAQADOnDmTu8z27duh0Whyf/78808MGDAAFStWRKVKleDr61vgt8CjoqLg7+8PBwcH2Nvbo3Pnzjh69GiJ8iYkJGDixImoX78+rK2t8dJLL8HT0xOrV69GWlpagctZWVnB0dERPXv2RGhoqMH26+/bT09PBwAsWLAAGo0Gjx8/RlhYWO79Od9iLmw9Q+wblW1RUVH45JNPMG3aNLRoUToP1Ldr1w7jxo3DxIkTecm0Moq9xl4jAoCsrCwMGTIEDRo0wEcffWTw8SMRiWxkozmaG3zs0oj9Texv9jcRoL6/S+o8zsMNpWuyHhVuK7aiIRqiGZqpjkJERERERERk2kQHjh07JpaWljJ79mxdbI5KiTt37kidOnXE2dlZdu/eLcnJyXL+/Hnp0qWL2NjYyLFjx/Is7+fnJwDEz89Pjh07JikpKRISEiK2trbSunXrPMteunRJKlasKDVr1pT9+/dLcnKyREZGire3t9StW1esra2LnTc2NlZcXFykWrVqEhQUJI8ePZK4uDiZOXOmAJBFixblWc7Z2VmCgoIkKSlJoqOjJSAgQDQajaxcudKg+5Wz/bS0tDy329vbS8eOHQvd34LW0+e+iYh4eHiIk5OTHD9+vNBcZJpSUlLEzc1N2rVrJxkZGarjlMjjx4/Fzc1N2rZtW+r3hYqHvWaY/WKvUWnwwQcfiJ2dnURGRioZf5WsEnuxl2zJVjJ+acT+LrvY34bZL/Y3lQaq+7uknMVZFspC1TFIR+pLfZkqU1XHICIiIiIiIjJ5Opn4JiKyaNEiMTMzk5CQEF1tkozc0KFDBYCsW7cuz+2xsbFibW0trVq1ynN7zofVQUFBeW7v27evAJD4+Pjc2/r16ycAZMuWLXmWvX37tlhbW2t1gGHYsGECQDZu3Jjvvh49euQeYMhZbv369XmWSU9Plxo1aoitra3ExcUZbL90eYBBn/smItKlSxdxdHTMd3CJTN/QoUPF0dFRrl27pjqKTsTExEiFChXkn//8p+ooZEDsNcPsF3uNjF1QUJBoNBr56aeflGX4QD6QFtJC2filFfu7bGJ/G2a/2N9k7Iyhv0siXuIFAtkv+1VHIR04JacEAjklp1RHISIiIiIiIjJ5Jb7UaY7AwEAEBARg8ODBuHPnjq42a3TOnz+f51IbGo0G7733Xpm7HXh22REzMzP4+vrmeYyqVasGV1dXnD59Grdu3cr3GLZu3TrP77Vq1QKAPP9u9u7dCwDw8fHJs2yNGjXw8ssva/Xcbdu2DQDQs2fPfPft2bMHgYGBeZbr1atXnmWsra3RvXt3pKWlYd++ffm2oWq/ikOf+wYAhw4dQmJiItq3bw+Afy9//XsxZStWrMDatWuxbt061K1bV3UcnWjYsCFWrlyJpUuX4pdfflEdR6+M7e+FvVZ07DX2GntN965fv45hw4ZhxIgRGDZsmLIc0YhGIzRSNn5pxf42vtcL9nd+7G/2N/tb94ylv0siEpEAgKZoqjgJ6cJWbEVd1EVLtFQdhYiIiIiIiMjkWehyYz/99BNat26NQYMG4cCBA7Cw0OnmjYKbmxtEpMD7ytLtGRkZSEpKAgA4ODgUuB4AXLp0CS+99FKe2/6+vJWVFQAgOzs7d9vJycmwsbFBuXLl8m2zatWqiImJKXTMguTktbGxQfny5bVeztnZGQAQFxeX7z4V+1Uc+ty3wvDvxfRFRkYiMDAQ06ZNK/DgXWnWv39/HD16FGPHjkWrVq3QpEkT1ZH0gn+nz7DX2GsAe604t5uijIwMvPHGG6hRowYWL16sNEs0otEf/ZVmKK3Y38b3esH+zp+X/c3+Zn/rjjH1d0mcwzlURmVUQzXVUUgHtmEb3sAb0ECjOgoRERERERGRydPZGd8AoFy5ctiwYQNOnjyJiRMn6nLTZGSsra1RsWJFWFhYIDMzE/Lssrn5fjw8PLTadvny5ZGeno6UlJR89ycmJmq1TQcHB6SnpyM5OVnr5e7evQvg2dkDtMmgy/3SaIr34Zk+943Kprt378Lf3x/t27fHjBkzVMfRiwULFsDV1RVvvPEGHjx4oDoO6RF7jb1GZZuIYPTo0bh8+TJ+/fVX2NnZKcuShSxcxVWe8a0E2N9lB/ub/U1lmzH1d0mdxmm0QivVMUgHIhGJKEThDbyhOgoRERERERFRmaDTiW8A4O7ujjVr1mDZsmX4+uuvdb15MiIBAQHIyspCWFhYvvvmzp2L2rVrIysrS6tt55w5KucSLDnu37+P6OhorbbZp08fAEBwcHC++1q0aIEJEybkWW737t15lsnIyMDBgwdha2ub75IwRaXL/bKzs8OTJ09yf2/UqBFWrFjx3HX0uW9UtqSmpsLf3x9mZmZYv349zM3NVUfSCysrK2zbtg2pqanw8/NDenq66kikR+y14mOvkan47LPP8Msvv2Dt2rVo0KCB0izXcA1P8IQT30qA/V22sL+Lj/1NpsKY+rukwhHOy2KaiK3YipqoiXZopzoKERERERERUZmg84lvANC3b1/MmzcPkydPxrp16/QxBBmBr776CvXr18fbb7+NPXv2ICkpCYmJiVi+fDm++OILLFiwQOvL3c6ePRtOTk4IDAxESEgIUlJScPHiRQwePLjAy7EUNa+LiwsmTJiA3bt3Izk5Gbdu3cK7776L2NjY3AMMOcsFBgZi165dSE5ORkxMDAYNGoTY2FgsXrw49/IrKverZcuWiImJwc2bN3H8+HFcvXoVnTt3LtJjoI99A4Bu3bqhUqVKOHHihNbbIOP39OlTDBo0CJcvX0ZwcDCqVq2qOpJeVa9eHcHBwTh//jyGDh36wkspUenFXlO7X+w1UuWHH37AzJkzsXTpUvTu3Vt1HETj2aSThmioOEnpxv4uO9jfaveL/U2qGFt/l0QqUhGNaE58MxFbsZWXOSUiIiIiIiIyJNGj8ePHi42NjRw5ckSfw5BCCQkJMnHiRKlXr55YWlpKlSpVxNvbW0JCQnKXOX78uADI8/Pxxx+LiOS7vVevXrnrRUdHi7+/v1SoUEFsbW2ldevWsmvXLunevXvu8iNGjChW3vv370tgYKC4uLiIpaWlVK9eXQYOHCgxMTHPXc7BwUF8fHzk4MGDBtuvbdu25dvOm2++mbudqKgo6dy5s9jb20utWrVk2bJlIiIvXE+f+9a5c2dxdHSUY8eOFet5odJl3LhxYmtrW+ae50OHDom1tbV88MEHqqOQHrHX2GvstbJlz549YmFhIdOnT1cdJdcCWSA1pIbqGCaD/V02sL/Z3+zvssUY+7skwiRMIJArckV1FCqhKIkSCOSwHFYdhYiIiIiIiKjM0IiIFDwlruSePn2Kvn374siRIwgLC0OjRrxcDxFRaTZ79mxMnz4dW7duhZ+fn+o4Brd27VoMHToUS5cuxbhx41THISKiEggPD0fXrl3Rp08frF69GhqNcZyVYxRG4TIu4zf8pjqKyWB/ExGZDmPt75L4Ft9iOqYjAQk8S1gpNwuz8C2+xW3chjnMVcchIiIiIiIiKhO0u95HEZmbm2PdunXw9PRE9+7dERoaioYNeckeIqLSaPHixfjkk0+wdOnSMjnpDQDeeust3Lx5E+PHj4ednR2GDx+uOhIREWkhMjISPj4+aNeuHVatWmVUB81jEIMmaKI6hklhfxMRmQZj7u+SCEc4WqIlJ72ZgK3YigAEcNIbERERERERkQHpdeIbANjZ2WHPnj3w8fFBt27dEBoaigYNGuh7WCIi0qEVK1ZgwoQJ+PLLL8v8mVKmTZuG9PR0jBgxApmZmRg1apTqSEREVAxRUVHw8fFB48aN8euvv8LS0lJ1pDyiEQ1/+KuOYXLY30REpZux93dJhCMc3vBWHYNK6Bqu4QzOYAEWqI5CREREREREVKaYGWIQBwcH7Nu3DzVq1ICHhweuXLliiGGpjNBoNC/8mTFjhuqYRKXWypUrMWbMGMyaNQtTp05VHccofPHFF/j4448xduxYrFmzRnUcMjHsNSL9iYqKgoeHBxo0aIA9e/agXLlyqiPl8RiPEYc4NAC/KKQP7G/SJ/Y3kf4Ye3+XRAYycBEX0RItVUehEtqETaiESuiCLqqjEBEREREREZUpej/jWw4HBwfs378f3t7e8PDwQGhoKOrXr2+o4cmEiYjqCEQma9WqVRg9ejRmzpyJadOmqY5jVGbOnAkAePvtt6HRaPDWW28pTkSmgr1GpB/R0dHo1q0b6tevb7QHzW/gBgCgNmorTmK62N+kL+xvIv0oDf1dEmdwBpnI5MQ3E7AVW9EHfWBhuI/biYiIiIiIiAgGnPgGPJv8tnfvXnh6eqJ79+7Yt28fGjVqZMgIRERUREuWLEFgYCC+/PJLnumtEDNnzkRmZiaGDx+OrKwsDB8+XHUkIiIqwNmzZ+Hj44OXX34ZwcHBRnvQ/BZuAQBqoZbiJKaN/U1EVDqUlv4uiTCEoTIqoyEaqo5CJXATN3EKp/AFvlAdhYiIiIiIiKjMMcilTv/K0dERISEhqF69Ojp16oTff//d0BFIxy5fvgyNRoMNGzbk3lauXLkCL+1iZmaGKlWqwN/fH3/88YfC1HkVllej0cDGxgbNmjXDsmXLjOpb/Nu3b8+TMz09Xe9jbtiwIc/j8lcF/Tug0klEMHXqVAQGBmLu3Lmc9PYCc+bMwdSpUzFixAh89dVXquNQCbHT1GCnkT799ttv6NKlC9zc3Iz+oPlN3IQ97OEIR9VRTB77W/9Uvpaq6BXSL75XKHtKU3+XxHEcR3u0hwYa1VGoBDZjMxzggG7opjoKERERERERUZlj8IlvAODk5ITQ0FB06dIF3bp1w65du1TEID1KSUlBREQEAMDPzw8iAhHBgwcPsGLFChw/fhwdO3bEgQMHFCd9prC8GRkZOHHiBCpUqID33nsPH374oeKk/+Pv7w8RgZ+fn8HGHDhwIEQE3bt3N9iYZFhZWVkYNWoUFixYgJUrV2LKlCmqI5UKM2fOxKpVqzB9+nS89957yM7OVh2JdIidpn/sNNKXX3/9Fb169YKnpyd27dpl9AfNb+Imz/ZmQOxv45SSkoKGDRvC19dX622o6BXSL75XKFtKW3+XxAmcQHu0Vx2DSmgrtsIPfrCCleooRERERERERGWOkolvAGBjY4ONGzfirbfegr+/P1asWKEqChmQg4MD+vTpg6+//hqZmZkIDAxUHem5rKys0Lx5c6xfvx5mZmZYtGgREhMTVcci0ovHjx/Dz88P69evx86dOzFixAjVkUqVt99+G1u2bMGPP/6IN954A2lpaaojkZ6x04iM25IlS9CvXz+MGjUKmzZtyne2HmN0C7fwEl5SHaNMYX8bHxFBdna2komI5cqVQ6dOnQw+LhH9T2nsb23dwA3cwi10QAfVUagE4hCHEziBN/CG6ihEREREREREZZKyiW8AYG5ujn/961+YNm0axowZg1mzZqmMQwbk4eEBALhw4QIePnyoOM2L1apVC9WrV0dWVhbOnj2rOg6Rzt29exceHh44ffo0Dh8+jJ49e6qOVCr5+flh3759uY/hgwcPVEciA2CnERmX7OxsTJkyBYGBgZg3bx4WL14MMzOl/9tTZDzjmxrsb+NSvnx5XLlyBcHBwaqjEJEBleb+1tZxHIcFLNAKrVRHoRLYgi2whz284KU6ChEREREREVGZpPwTJI1Ggy+++ALfffcdPv/8cwwaNAipqamqY5GeiUjuf2s0GoVJii4nsyl/25jKptOnT6N169Z48OABwsLC0KoVP3Qvic6dO+PIkSO4evUq2rZtiwsXLqiORHrGTiMyHo8ePYK/vz+WLl2KX375BZMmTVIdqVg48U0d9jcRkTqlvb+1dRzH4Q53lIPpXsq1LNiCLfCFL2zA/7ciIiIiIiIiUkH5xLccY8aMwcGDB3Hw4EF06NAB165dUx2JiqhBgwYQEQwcOLDI6xw6dAgA4OrqCgcHBwBAQkICJk6ciPr168PKygqOjo7o2bMnQkND86ybkZGB6dOno3HjxrCzs4OTkxN69+6NnTt34unTp3mWjY+Px/jx41G3bl1YWVmhSpUqCAgIwJkzZ4q1jzdu3EBsbCwqVKgAV1dXrcbIysrCxo0b4eXlhWrVqsHW1hZNmzbF4sWLC7yMz18fD2tra7z00kvw9PTE6tWrC7wEU1xcHAYMGICKFSuiUqVK8PX1xZUrV/ItV5zHJCoqCv7+/nBwcIC9vT06d+6Mo0ePFvgYafPvgNRbv349XnvtNbzyyis4efIk6tevrzqSSXB1dUV4eDheeukltGvXDlu3blUdiYqIncZOA9hppdWlS5fQvn17nDhxAvv27cOgQYNURyo2XupULfa3bv39tXT79u3QaDS5P9HR0ejfvz8qVaqUe9uqVavyLJOenp5nm399Lbezs0ObNm2wa9cueHp65q4zcuTIfFle1CsLFiyARqPB48ePERYWlrstCwuL5+5jznoajQYvvfQS/vjjD3Tv3h3ly5eHnZ0dPDw8EBYWlm89Y3ufUJTn5v79+8Uah+8VqKhMob+1dRzH0R7tVcegEohDHI7iKPqjv+ooRERERERERGWXGJkbN25Iq1atpFKlShISEqI6DpVARESEABA/P7/c25KSkuTXX3+VqlWriqWlZe5zHBsbKy4uLuLs7CxBQUGSlJQk0dHREhAQIBqNRlauXJm7jZEjR4qDg4Ps379fUlNTJS4uTiZPniwAJDQ0NHe5O3fuSJ06dcTZ2Vl2794tycnJcv78eenSpYvY2NjIsWPHXpj3yZMnEhERIR07dhQrKytZs2ZNnnWKM0ZQUJAAkNmzZ0tiYqLEx8fLkiVLxMzMTCZPnpxnuzmPR7Vq1SQoKEgePXokcXFxMnPmTAEgixYtyl3Wz88vN/exY8ckJSVFDh48KBUqVJDWrVtrnffSpUtSsWJFqVmzpuzfv1+Sk5MlMjJSvL29pW7dumJtbf3CfwNkvLKysuTDDz8UADJq1CjJzMxUHckkZWZmyocffigajUY+/PBDefr0qepIpCV2GjuNjFtwcLBUrFhRWrZsKdevX1cdRyuP5JFAIHtkj+ooZR77W79yXuu7dOkioaGh8vjxYzlx4oSYm5tLfHx8nmXS0tJy1yvotfz8+fPi6ekpVapUKfC1vDi9IiJib28vHTt2LPY+ubu7i729vbRv3z53nD/++EOaNWsmVlZWcujQodxljeF9QmFe9NzwvQLpmin0t7ZSJVWsxEp+kV9UR6ESWCJLpLyUl1RJVR2FiIiIiIiIqMwyuolvIiJpaWny1ltvibm5ucyZM0d1HNJSzkH3v/5oNBqpVKmSvP7663Ly5MncZYcNGyYAZP369Xm2kZ6eLjVq1BBbW1uJi4sTEREXFxfp0KFDvvFefvnlPB/+Dx06VADIunXr8iwXGxsr1tbW0qpVqxfmzfnp06ePXL58Od+YxRkjKChIunbtmm8bgwcPFktLS0lKSsr3eGzcuDHf8j169Cjwg/+goKA8yw0aNEgA5B48Km7efv36CQDZsmVLnmVv374t1tbW/OC/FEtISBBPT0+xsbGR1atXq45TJixfvlysrKzk//7v/+TBgweq45AW2GnsNDJO2dnZMmfOHDEzM5PBgwdLamrpPeh4Xs4LBHJOzqmOQv8f+1s/cl7rg4ODX7jMXye+FfZafu/ePbGzs3vuxLei9IpIySa+AZCIiIg8t0dGRgoAcXd3z73NGN4nFOZFzw3fK5CumFJ/a+uAHBAI5LqUrQl/pqazdJY35U3VMYiIiIiIiIjKNKOc+Cby7EOw2bNni5mZmfTv318ePnyoOhIVU0FnmymMg4ODAJBHjx7lu++tt94SAPLzzz+LiMjYsWMFgLzzzjty/PhxycrKKnSbZmZmeT5Qz9GyZUsBIDdv3nxu3lu3bsmAAQMEgHzwwQclHqMg8+fPFwB5vm3+vMfj73I++M85OJJjypQpAkDOnj2rVd7y5csLAElOTs63bNOmTfnBfyl19OhRqVOnjtSpU0fCw8NVxylTwsLCpFq1atKwYUM5deqU6jhUTOw0dhoZn/j4eOndu7dYWlrK0qVLVccpsb2yVyCQB8IJVsaE/a17Oa/19+/ff+Eyf5349rzX8pYtWz534ltRekWk5Gd8K0iNGjUEgNy5c0dEjON9QmFe9NzwvQLpgqn1t7Y+kU+kvtRXHYNKIFZixVzMZbtsVx2FiIiIiIiIqEwzg5HSaDSYOnUq9u7di//85z9o3rw5jh8/rjoW6UFGRgaSkpJgY2OD8uXL57vf2dkZABAXFwcAWLZsGdasWYOrV6+ie/fuqFChAnr06IFt27bl22Z2djYcHByg0Wjy/ISHhwMALl269NxsNWvWxOrVq1G/fn3Mnz8fp06d0nqMpKQkTJ8+HU2bNoWjo2PuclOmTAEApKamFunxKIyDg0Oe383Mnv15Z2dnFztvRkYGkpOTYWNjg3LlyuUbq2rVqkXORcbh6dOnmDlzJrp27YqmTZvi1KlTaNGihepYZUqHDh1w+vRp1KpVCx06dMDChQshIqpjkY6x09hpZBi//fYb3N3dERkZidDQULz33nuqI5XYPdyDFaxQERVVR6G/YH/rj729fZGXfdFruaOj43PXf1Gv6ELFigX/7eb0zL1794z6fcJfFfTc8L0C6YIp9re2DuEQPOChOgaVwGZshh3s4A1v1VGIiIiIiIiIyjSjnfiWw8vLC5GRkXBzc8Nrr72GGTNm4OnTp6pjkQ5ZW1vDwcEB6enpSE5Oznf/3bt3AQDVqlUD8GxS5FtvvYUDBw7g4cOH2L59O0QEAQEB+Prrr3O3WbFiRVhYWCAzMxPy7OyG+X48PF78IaONjQ1mz54NEcFHH32UJ3dxxujduzdmzpyJd955BzExMcjOzoaIYNGiRQCQewDtRY+HtoqT19raGuXLl0d6ejpSUlLybSsxMVFnuUj/bt26he7du+PLL7/EggULsHPnTlSuXFl1rDKpRo0aOHDgAObNm4dp06bB29sbsbGxqmORDrHT2GmkX1lZWZgxYwa8vb3Rrl07hIeHo2PHjqpj6UQiElEJlVTHoAKwv9V70Wv5vXv3dDKORqPRet2EhIQCJ0XmZKtatarRv094Hr5XoJIw5f7WRipS8Qf+QFd0VR2FSmAzNuN1vA5b2KqOQkRERERERFSmGf3ENwCoUqUKdu7ciQULFmDOnDnw9PTE7du3VcciHerTpw8AYPfu3Xluz8jIwMGDB2FrawsfHx8Az75JHxUVBQCwtLSEl5cXtm/fDo1Gk2f9gIAAZGVlISwsLN94c+fORe3atZGVlVWkfP369UOLFi1w8OBBhISEFHuMp0+fIiwsDNWqVcP48eNRpUqV3IMqaWlphT4ewcHB+e5r0aIFJkyYUKTcf1ecx6Rnz54AgL179+ZZ7v79+4iOjtZqfDK87du3o3nz5rh79y5OnDiB999/v0QH9KjkNBoN3n//fRw9ehR//vkn3N3dC/xbp9KLnVbw48FOo5K6fv06unbtinnz5mHhwoXYunUrnJycVMfSmQd4ACeYzv6YGva3eoW9lsfFxSEmJkYnY9jZ2eHJkye5vzdq1AgrVqwo0rrp6en4448/8tx27tw53LlzB+7u7qhevToA43+f8Dx8r0DaMPX+1kYYwpCBDE58K8ViEYswhKEf+qmOQkREREREREQlu1Kq4YWHh0ujRo2kUqVKsn79etVx6DkiIiIEgPj5+b1w2djYWHFxcRFnZ2cJCgqSR48eSXR0tAQEBIhGo5EVK1bkLuvg4CBdunSRs2fPSnp6uty9e1dmzJghAGTWrFm5y929e1fq168v9erVk+DgYHn48KEkJCTI999/L3Z2drJx48Zi5d29e7cAkJYtW0p2dnaxx+jWrZsAkHnz5kl8fLykpqbKb7/9JrVr1xYAEhISku/xqF69uuzatUsePXokN2/elLFjx4qzs7Ncv349d1k/Pz8BIGlpaXnyfvjhhwJAIiIitHpMLl++LE5OTlKzZk3Zv3+/JCcny4ULF8THx0eqVq0q1tbWL3xeSZ2HDx/KyJEjBYC888478vjxY9WRqABJSUnyj3/8QzQajbz//vuSkpKiOhIVgp3GTiN1srOzZdWqVeLg4CDu7u5y8eJF1ZH04p/yT+ksnVXHoCJgf5dMYa/1L1qmoNfyc+fOSY8ePaROnToFvpYXp1dERHr06CEODg5y48YNOXbsmFhYWBTpNcfd3V0cHByke/fucuzYMUlJSZE//vhDmjVrJlZWVnLo0KHcZY3hfUJhXvTc8L0CFUdZ6W9tTJNp0lAaqo5BJbBYFkt5KS9pUniXEREREREREZFhlLqJbyIiKSkpMnbsWNFoNOLn5yd37txRHYn+xt7eXgDk+WnUqNFz17l//74EBgaKi4uLWFpaioODg/j4+MjBgwfzLHfmzBkZPXq0NGnSROzs7MTJyUnatWsnK1euzD14nyMhIUEmTpwo9erVE0tLS6lSpYp4e3vn+ZC9sLwDBgzIl7FTp06593fs2LFYY8THx8vo0aOlVq1aYmlpKc7OzjJs2DD56KOPcrfZqlWrQh+P6tWry8CBAyUmJkZERI4fP54v88cffywiku/2Xr16FfsxERGJjo4Wf39/qVChgtja2krr1q1l165d0r1799xtjxgx4rnPKxnerl275KWXXhJnZ2fZunWr6jhUBGvWrBFHR0epV6+e/Pbbb6rj0N+w09hppM6ff/4pXl5eYm5uLpMmTXruRJnS7k15U/zkxZNryXiwv4unoNf6v38Xb9u2bfnuf/PNN3Pv/+truZ2dnXTo0EEOHz4sXbt2FTs7u+eOVZReiYqKks6dO4u9vb3UqlVLli1bVqR9c3d3l5o1a8rFixfFx8dHypcvL7a2ttKlSxc5evRovuVVvk8oSFGem+KOw/cKZVtZ6m8IrgCZAAAgAElEQVRtdJAOMkpGqY5BJdBJOslgGaw6BhERERERERGJiEZEpNDTwRm5o0ePYuTIkYiLi8O8efPwzjvv8BJ+RFRmPXz4EB9++CFWrFiBfv364bvvvkPlypVVx6Iiunv3LsaNG4dff/0VgwcPxuLFi+Ho6Kg6FhGREiKClStXYvLkyahduzZ++OEHtG3bVnUsvfo//B+qoRp+xI+qo1AxsL+NQ+PGjZGWlobr168rGb958+a4f/8+bt26pWR8ImNRFvu7uFKQAic4YTVWYxAGqY5DWohFLF7CS9iGbXgdr6uOQ0RERERERFTmmakOUBKdOnVCREQExowZg3fffRc9e/bEjRs3VMciIjK4Xbt2wc3NDTt37sSvv/6KTZs2cdJbKePs7IwtW7Zg48aN2Lt3L1xdXbFjxw7VsYiIDO7q1avw9PTEuHHj8O677+L06dNl4qB5IhLhBCfVMaiY2N+GExcXBycnJ2RmZua5/c8//8SVK1fQrVs3RcmICCi7/V1coQhFFrLQHd1VRyEtbcIm2MMe3vBWHYWIiIiIiIiIUMonvgGAra0t5syZgyNHjuD69etwc3PDokWLkJWVpToaEZHeXb9+HQEBAXj99dfRo0cP/Pe//0WfPn1Ux6IS6NevHy5cuIAuXbrA398fgwcPRmxsrOpYRER6l5GRgdmzZ8PNzQ2JiYk4efIk5syZA2tra9XRDCIRiXAEzxRWWrG/DePBgwcYPXo0bt68idTUVJw8eRIDBgxAhQoV8Omnn6qOR1QmlfX+Lq492IOWaAlnOKuOQlrajM3wgx9sYKM6ChERERERERHBBCa+5Wjfvj0iIiIQGBiIadOmoUWLFjh06JDqWEREepGeno5Zs2bhlVdewYULF7B//36sWrUKFStWVB2NdKBKlSpYv349duzYgbCwMDRu3Bhff/11vjOcEBGZiuDgYDRt2hSzZ8/Gp59+ipMnT6JFixaqYxkUz/hW+rG/9atatWo4cOAAHj58iNdeew2Ojo54/fXX0bBhQ5w8eRL16tUzeKYFCxZAo9Hg7NmzuH37NjQaDT755BOD5yBShf1dfPuwDz3RU3UM0lIsYnEcx9EP/VRHISIiIiIiIqL/TyMiojqErl25cgWBgYHYtWsXfH19sWzZMtSuXVt1LCIinThw4ADGjx+P69evY8qUKZg6dSq/TW/C0tLSMHfuXMydOxe1a9fGkiVL4OPjozoWEZFO3Lp1C9OmTcPatWvh6+uLb7/9FnXq1FEdy+AEAktYYh3WYQAGqI5DOsD+JiJTxv7WThSi0ARNEIYwdEAH1XFIC4uxGJ/iU9zDPZ7xjYiIiIiIiMhImMwZ3/6qfv36CAoKQkhICC5fvowmTZpgxowZyMjIUB2NiEhrV69eRf/+/eHl5YX69evj4sWLmDFjBie9mThbW1vMmDEDMTExaNu2LXr06IHevXvj+vXrqqMREWktZ1JQ48aN8fvvv2PPnj0ICgoqswfNH+IhnuIpz/hmQtjfRGSK2N8lswd74AhHtEEb1VFIS5uxGf7w56Q3IiIiIiIiIiNikhPfcnh6eiIiIgIfffQR5s+fj2bNmmHLli0wwZPcEZEJS0xMxJQpU+Dq6oqLFy/it99+48GFMqhWrVpYs2YNdu3ahaioKLi6umL69OlITk5WHY2IqMiys7Oxdu1aNGnSBLNnz8bnn3+O8+fPo0ePHqqjKZWMZ6/lDnBQnIR0jf1NRKaA/a0be7EX3vCGBSxURyEt3MZtXuaUiIiIiIiIyAiZ9MQ3ALCxscGnn36KixcvonXr1hgwYADat2+Pw4cPq45GRPRc6enpmD9/Pho0aICff/4Z8+fPR0REBDw8PFRHI4V69eqF8+fPY/r06fj222/RoEEDLF26FE+ePFEdjYjoufbt24eWLVti+PDh8PLyQlRUFCZNmgRLS0vV0ZRLRzoA8OwhJoz9TUSlFftbN9KQhiM4gp7oqToKaWkzNqMcysELXqqjEBEREREREdFfmPzEtxx16tTBL7/8gsjISNSuXRtdu3aFl5cXzpw5ozoaEVEe2dnZ2Lx5M1555RXMmDEDo0aNwqVLl/Dee+/x4AIBAKytrfHBBx/gypUrGD58OD788EM0bNgQK1asQHZ2tup4RER5nD59Gp6enujRoweqVKmC8PBwrFy5EtWrV1cdzWhkIAMAYA1evtyUsb+JqDRhf+vWQRxEOtLhAx/VUUhLm7EZfvDjFxWIiIiIiIiIjEyZmfiWw9XVFZs2bUJISAgSExPx6quvYvjw4bhx44bqaERE2L17N5o3b45BgwbBy8sLly9fxpw5c+DgwEufUX6Ojo6YM2cOoqKi0LVrV4wdOxZt27bFgQMHVEcjIsKVK1fwj3/8A61bt0ZqaiqOHDmCkJAQNGvWTHU0o5NzxjdOfCsb2N9EZMzY3/qxDdvQDu1QDdVURyEt3MItnMAJXuaUiIiIiIiIyAiVuYlvOTw9PXHq1CmsX78eR44cQYMGDTBkyBBcunRJdTQiKoNOrFyJ2fXqYYGvL9wcHBB++jSWL1/Ob9NTkdSuXRs///wzzp07BxcXF3h5eaFjx44ICgpSHY2IyqBr165h9OjRaNy4McLDw7Fx40aEhYWhU6dOqqMZrZwzvvEMImUL+5uIjAn7W3+e4imCEIQ+6KM6CmlpC7bwMqdERERERERERqrMTnwDAI1Gg379+uG///0vVq1ahRMnTsDV1RVDhgxBdHS06nhEZOJEBEFBQWjTpg06jhqF1unpCAXw76NH0bR1a6BhQ+D114HJk4F//QsICQGuXQOePlUdnYzUK6+8gk2bNiEsLAxOTk7w8/NDixYtsHnzZoiI6nhEZOIuXryIIUOG4OWXX8aBAwewbNkyXLhwAf369YNGo1Edz6jxUqdlG/ubiFRif+vfYRxGPOLhBz/VUUhLm7EZ/vDnlxSIiIiIiIiIjFCZnviWw9LSEkOGDEFUVBTWrVuHkydP4pVXXkH//v0RFRWlOh4RmZjs7GwEBQXh1VdfhZ+fH5ydnfH7H3/A68YNwN//2UJPngCXLwNBQcA33wD//Cfg7Q3UqwfY2AB16gA+PsD48cDSpUBw8LN1iAB06NABQUFBCA8PR8OGDTFgwAA0b96cB9CJSC/Onz+PIUOGoFmzZjh9+jR++OEHREdHY9SoUbCwsFAdr1TgpU4JYH8TkWGxvw1nG7ahGZrhZbysOgpp4RZu4TiO8zKnREREREREREaKE9/+wszMDP369cOFCxdyLznj6uqKAQMG4OTJk6rjEVEpl56ejlWrVsHNzQ3+/v54+eWXERkZmTsJDhYWwMaNgJfXs//O8fRp3rO8ZWUBN24A+/cDy5cD778PTJsGWFoafqfIqDVv3hybNm3CqVOn4OLiggEDBqBFixb45ZdfkJmZqToeEZVyR44cgb+/P5o1a4bIyEhs2LAB586dw5AhQ3jAvJh4xjf6K/Y3EekT+9uwBIId2MHLnJZim7EZ5VEenvBUHYWIiIiIiIiICsCJbwUwNzfH4MGDceHCBfz73//G5cuX0bZtW3Tu3Bnbtm1Ddna26ohEVIrEx8fjiy++QJ06dTBu3Di0bdsWFy5cwPr16+Hm5pZ3YSsrYMcOoG3bvJPfCvPkCSACzJwJ8DI0VIiWLVti+/btiIiIQJMmTTB8+HC4uLhg7ty5ePDggep4RFSKZGVlYcOGDWjTpg1ee+013Lt3D9u2bUNERAT69u0LMzP+74U2MpABC1jAHOaqo5ARYX8Tka6wv9X5Hb/jJm5y4lspxsucEhERERERERk3frL1HGZmZhgwYABOnz6NI0eOoHr16ujXrx8aNmyIuXPnIikpSXVEIjJily9fxvvvv4+6devi66+/xsCBA3HlyhX89NNPaNy4ceEr2to+u3Rp06YvPoubuTnQvDng66vb8GSS3N3dsX79ety4cQMjR47E3LlzUbt2bYwePZqX9iai50pOTsbixYvRoEEDvPnmm3B2dsbRo0dx7Ngx+Pn5QcPJ1yWSjnSe7Y0Kxf4mIm2xv9Xbju2oh3pwh7vqKKSFW7iFEzjBy5wSERERERERGTGNiIjqEKVJTEwMFi1ahDVr1sDa2hqjR4/GmDFjUKdOHdXRiMgIZGdn48CBA1i8eDH27NmDhg0bIjAwEEOHDoWdnV3xNvbwIdCpExATAzzvslb79z+7PCpRMT169Ag//PADlixZghs3bsDf3x/jx49Hly5dVEcjIiNx+fJlfPfdd/jhhx8gIhgxYgTGjx8PFxcX1dFMyvf4Hh/jYyQgQXUUKgXY30T0Iuxv4yAQuMAFAzAAczFXdRzSwiIswhf44v+xd+dxVdf528dfIIgC7gtu4L7hUhYlhqMmuJ+Dmh6tqbxnaiZn+zX3r+aemrFmyvaamaa6pxnrzrap1COmnGMugJoL1iSaC5K5BSqrKYiyL/cf58cJ0zYFPudwrqcPHiSgXDwMPnC+1/f9Jpdc3aQgIiIiIiIi4qE08e0HGjRoEP/85z/Jysri/vvv580336Rfv35YLBacTifV1dWmI4qIAQUFBTz77LMMGjSIKVOmUFJSwurVq8nIyOCXv/zlDy+9AbRvD5s2QXj45Se/BQRAr16wYwecO3f1H4T4nLZt2/Lf//3fHDlyhGXLlpGdnc2ECROIjIzkhRde0Bo1ER9VWVlJQkICkydPZtCgQSQkJPDwww9z4sQJnn/+eV00bwQVVNCSlqZjiJfQ+S0il6Pz2/NsZSuZZHIHd5iOIlfIjp2ZzFTpTURERERERMSDqfh2hTp16sSiRYs4ceIEGzZswM/Pj/j4eCIiInjwwQfJysoyHVFEmkBaWhoLFy6kd+/ePPHEE8TGxrJ37142b95MfHw8/v5X+WW2a1fYssX1/Ovlt6oqsFrhhRegb194+mm4cOHq3p/4pBYtWmCz2di5cyfp6elMmjSJhx56iO7duzNv3jySk5NNRxSRJpCdnc0zzzxD//79mTdvHrW1tSxfvpyjR4/yu9/9jnbt2pmO2Gz54UctGsQtP4zObxEBnd+e7N/8m2u5lhGMMB1FroDWnIqIiIiIiIh4B606bUBHjhzhlVde4fXXX6ewsJD4+HgWLlxIXFzc1ZdfRMRjfPnll/z73/9myZIlZGRkcOONN/KLX/yC+fPnX9lkt+/jyBGIjoaiIlfhLTAQxo2D5GQoLoaXX4annnK9/He/g3vvhdatGyeL+ITi4mLeeecdlixZwqeffsq1117LwoULue2223TxTKQZqaqqYt26dSxZsoR169YRFhbGXXfdxc9//nN69+5tOp7PeJmX+TN/poAC01HEy+n8FvENOr89XxlldKc7D/Mw93Gf6ThyBf7G33iMx7TmVERERERERMTDqfjWCCoqKlizZg2vvPIKKSkpdO/enblz5/KTn/yEUaNGmY4nIlegurqazZs389Zbb7Fy5UoCAgK47bbb+MUvftF0n9f79sHYsa6pbrW18NFHcOONX73+yy/huefgpZcgNBTuuw/+9/+GID1AK1cnLS2NV155hXfeeYfq6mri4uJYsGABs2bNIvBya3hFxOOlp6fz9ttv8+abb5Kbm0tMTAy//e1v9XltyCu8wgM8wFm0olIajs5vkeZH57f3sGPnVm4liyx60tN0HLkCYxjDYAbzBm+YjiIiIiIiIiIi30LFt0aWmZnJsmXLePXVVzl69CiRkZEsWLCAn/zkJ4SFhZmOJyLfoe7Cwuuvv87p06cZM2YMCxYs4LbbbqNNmzZNH+jjj2HiRLj5ZnA6L/82BQXw17+6VqB27QqLFsFdd0FAQNNmlWanqKiINWvW8Pbbb5OSkkKHDh2YO3cud955J2PHjjUdT0S+Q05ODitWrOCtt95i9+7dREREcNttt/Gzn/2MAQMGmI7n05aylN/yW4opNh1FmiGd3yLeTee3d5rJTMopZz3rTUeRK3CCE/SmNw4czGCG6TgiIiIiIiIi8i1UfGsiNTU1bN26lbfeeouEhARKS0uZOnUqd955JxaLhdZaSSjiMb744gveffdd3n77bT777DOGDh3KnXfeyR133EF4eLjpeLB5M3TsCNdc8+1vd+IE/OUvsGQJ9OgBDz4Id98NLVo0TU5p1o4dO8bbb7/N22+/zdGjRxk5ciQLFixg/vz59OrVy3Q8Efkf58+fJzExkbfffpukpCTatm3LvHnzWLBgAWPGjMHPz890RAHe5E1+yS8pocR0FGnmdH6LeAed397tNKfpSU9e4zXu4A7TceQK1K05zSOPlrQ0HUdEREREREREvoWKbwaUlZXhcDh46623WL9+PYGBgcTGxmKz2Zg9e7aZKVIiPi4zM5PVq1djt9tJTU2lffv22Gw27rzzTmJiYrz7wkJmJjz5JLz2GgweDI88AnPngjd/TOJR0tLSeOutt3j33Xc5ffo0kZGR2Gw27rjjDk2hEDGgpKSElJQU7HY777//PqWlpdx8883ceeedzJ07l+DgYNMR5Wve4R1+yk+poMJ0FPEhOr9FPIvO7+bjr/yVx3iMU5wihBDTceQKjGEMQxjC67xuOoqIiIiIiIiIfAcV3wz78ssvWbt2LXa7nQ0bNtCiRQvi4uKw2WzMmjWLtm3bmo4o0mx98cUXrFmzxl1269ChAzNmzMBmszFlyhRatmxmd/VmZMBTT8E778CwYfDww2CzmU4lzUh5eTnbtm3D4XDw3nvvUVBQ4L6IfvvttzNw4EDTEUWarcLCQpKSknA4HKxatYqysjKio6Ox2WzceuuthIWFmY4o32IZy7id26mm2nQU8UE6v0XM0fnd/NRSyxCGMJnJvMRLpuPIFahbc+rEyXSmm44jIiIiIiIiIt9BxTcPUlBQwPvvv8/KlSvZvHkzgYGBTJ06lVmzZjFt2jS6dOliOqKIV6utreXTTz91X1TYu3cvXbp0Yfbs2dhsNiZMmEBAQIDpmI3vwAFYvBhWroTRo+GxxyAuznQqaWYqKipITk5m5cqVrFmzhjNnzhAVFcWcOXOwWCwMHz7cdEQRr5eTk8PatWtZvXo1SUlJAMTFxTF37lxmzpxJx44dDSeU72slK7Fho4Ya/NBEVjFH57dI49P53bwlk8wkJrGPfYxghOk4cgX+yl95nMe15lRERERERETES6j45qG+/PJL3n//fRISEti8eTOVlZWMHj0ai8XCjBkzuOaaa0xHFPEKdetinE4na9eu5dSpU/To0YOZM2cyd+5cxo8fT4sWLUzHNOPjj+Hxx8HphJgYeOIJGD/edCpphiorK0lJSWHlypU4HA7y8/Pp06cPM2bMwGq1Mn78eFq1amU6pojHq62tZffu3TidTpxOJ2lpabRq1cp9sTw+Pp727dubjilX4H3e5xZuoYIKAgk0HUcE0Pkt0lB0fvuWucwln3y2stV0FLlC0UQzlKFacyoiIiIiIiLiJVR88wIlJSWkpqbicDhISEjg1KlThIWFMXnyZKxWK9OmTSM0NNR0TBGPkZeXx4YNG3A6naxbt47z588TGRmJ1WrFYrEQExODn5+mqbilpsJDD8Hmza7Jb089BVFRplNJM1VTU8OePXtITk7G4XCQmppKq1atiImJwWKxMGfOHHr16mU6pojHKC0tZceOHe5ppSdPnqRr165MmTIFq9XK1KlTadOmjemYcpUcOIgnnlJKaYWKROJ5dH6L/DA6v31TDjn0pjdv8AY/5sem48gV0JpTEREREREREe+j4puXqa2tZdeuXaxduxan08nu3btp1aoVP/rRj4iNjSU2NpZRo0bh7+9vOqpIkzl37hxbtmwhJSWFlJQU0tPTCQ0NZfLkycyYMYPp06fTrVs30zE9X3IyLFoE//mPqwD37LMwapTpVNLMnTx50n2mbdq0idLSUkaOHElcXByxsbGMGzeOkJAQ0zFFmkx1dTW7du0iJSWF5ORkUlNTqays5IYbbsBqtTJjxgyuvfZa0zGlga1jHdOZzjnO0QYVIcTz6fwWuZjObwFYzGJe4iVOcEJFdi/1F/7CEzyhNaciIiIiIiIiXkTFNy+Xk5PDunXrSE5OZtOmTeTl5dGpUyduvvlmdxFu4MCBpmOKNKjy8nJ27tzpLrp98skn1NTUcM011xAbG8vkyZMZN24cQUFBpqN6p+RkeOAB+PRTmDMHHnsMBg82nUp8QGlpKZs3byYpKYnk5GTS09MJCAggOjqa2NhY4uLiGD16NAEBAaajijSojIwM94XyLVu2UFRURI8ePYiNjWXSpElMmTKFrl27mo4pjWgzm5nIRPLIoyv6txbvovNbfJXOb6mvkkr60Y/buZ2nedp0HLlCoxnNMIaxlKWmo4iIiIiIiIjI96TiWzNSW1vLgQMHSE5OJiUlhQ8//JDz588TERHBxIkTGTduHDfddBODVWARL1NWVsYnn3zCtm3b2Lp1K9u2baOkpIR+/fq5p0pMnDiRzp07m47afNTWgtMJDz8M+/e7CnBPPQX9+5tOJj4kNzfXXXBNSUkhKyuL0NBQxo8fz/jx44mJiSEqKoqWLXUnvniP2tpaMjIy2LFjB9u2bSMlJYXs7GzatWvHhAkT3CWRoUOHmo4qTSiNNKKI4jCHGcAA03FErorOb2mOdH7Ld3mTN/k5P+cIR4ggwnQcuQJ1a07XspZpTDMdR0RERERERES+JxXfmrHKyko+/vhjUlJS2LRpE5988gmlpaV07dqVmJgYxo4dS0xMDNdddx2BgYGm44q4ffnll+zYsYPt27ezY8cOdu3aRUVFBT169GDcuHFMnDiRuLg4+vbtazpq81dTAwkJrhWoX3wBP/0p/OlP0LOn6WTigz7//HP3RfTt27eTl5dHq1atuOGGG9xnWkxMDO3btzcdVcStoqKCXbt2uS+Up6am8uWXXxISEsLo0aOZOHEisbGx3HDDDbRo0cJ0XDHkCEcYyEDSSOM6rjMdR6RB6fwWb6TzW36IWmoZyUiu53re4A3TceQKac2piIiIiIiIiHdS8c2HVFRUkJaWdlGh6PTp0wQHB3PjjTcyduxYbrjhBqKioujRo4fpuOIjqqqqOHjwILt27eKjjz5ix44dZGRkABAZGem+GDZ27FgV3UyqrIT33oNHH4WTJ+EnP4FHHoHu3U0nEx92+PDhiy5GfvbZZ/j7+xMZGcmPfvQjRo8eTVRUFEOGDNEFSWkyJ06cIC0tjf/85z9s376dTz75hLKyMsLCwoiJieFHP/oRN910E9ddd53W/olbPvmEEcZmNjOBCabjiDQqnd/iiXR+y9Vw4GAmM9nHPoYz3HQcuUJacyoiIiIiIiLinVR882G1tbV89tlnpKamsm3bNnbu3Mnhw4epra2le/fuREVFuZ+uv/56wsLCTEcWL1ddXc1nn33Grl27SEtLY9euXXz66aeUlpYSHBzMdddd5y653XTTTXTs2NF0ZPm6igp44w1XAa6oCO6+2zUNrmtX08lEKCgocJ9pO3bsYM+ePZSXlxMSEsKoUaPc51lUVBSDBg3C39/fdGTxctnZ2e7zrO5sy8vLw9/fn8GDB3PTTTe5C9wDBw40HVc8WBlltKY1a1hDPPGm44g0KZ3f0tR0fktDG8tYOtABBw7TUeQKac2piIiIiIiIiPdS8U0uUlhYyO7du90PAO/atYvjx48DEB4eTlRUFNdeey3Dhw9n5MiR9OvXTxce5LLOnz/PwYMH2bdvH/v372f37t3s2bOHCxcuEBQUxDXXXHPRRazIyEjdOe9NSkrg1VfhqafgwgX49a/hwQdBK6rEg1RWVnLgwIGLzrT9+/dTWVlJ27ZtGTVqFNdffz3Dhw9nxIgRREZGEhwcbDq2eKDq6mqOHDnC/v372b9/P3v27CEtLY3s7Gz8/PwYMGCA+zyLiopi1KhRtG3b1nRs8TJBBPEar3EHd5iOImKUzm9pKDq/pSl8zMdEE802tjGWsabjyBV6jud4kie15lRERERERETEC6n4Jt/pzJkzF90JvXfvXo4fP05NTQ3BwcFERkYyYsQI94WH4cOH013rD31GVVUVn3/+OQcOHGDfvn0cOHCA/fv3c/z4cWprawkODmbYsGHuaQ1RUVEMHz6cwMBA09GlIZw/D//4Bzz9NPj7w3/9F9x3H+iCkXio8vJy9u3b5z7T9uzZw8GDBykrK6NFixb069ePkSNHMmzYMEaMGMGIESMYMGCAVq35kJMnT5Kenu4+0w4cOHDJ/yPXXnutu7x9/fXX016lX2kAXejCozzKr/iV6SgiHkfnt3wXnd9iSjzxnOY0qaSajiJX4UZuZAQjeI3XTEcRERERERERkR9IxTe5IhcuXHBP86orOu3fv5/8/HwAOnXqxKBBgxg8eDADBw686CkkJMRwerkS2dnZHD58+KKnzz//nMOHD1NRUUFAQAADBgxwX2iqK0JqKqCPKC6Gl1+GJ5+Eli3hd7+De++F1q1NJxP5TvWngdRdKN23bx/Hjh2jurqaVq1aMWjQoEvOs8GDB9NVa369UnFx8UXn2aFDh9zn2tmzZwHo0aPHRaX+uqlCrfV1TRpJf/rzc37OgzxoOoqIV9D57Xt0foun+ZiPGcMYHDiYwQzTceQKfcEX9KMfH/ABU5lqOo6IiIiIiIiI/EAqvkmDKigoYN++fRw8eND9IPSRI0fIzMykuroagJ49e7ovOgwYMIDevXsTERFB79696d69O35+foY/Ct9UVlZGZmYmWVlZZGVlcfz48YsuKpw/fx6A0NBQ97/dwIEDGTJkCMOHDycyMpKgoCDDH4UYd/o0/OUv8OKL0KmTqwD3i1+A/t8QL1RaWsrBgwfZv3+/+0yreyotLQWgXbt2F11M79u3LxEREURERBAeHq6vi4bU1NSQk5PDF198QVZWFpmZmRw5csR9cTw3NxeAgIAA+vTpc1EZom6SbadOnQx/FOJrRjGK6UznCZ4wHUXEq+n89l46v8XbxBJLOeVsZ7vpKHIhLfgAACAASURBVHIVnuM5nuIpcsnVmlMRERERERERL6TimzSJiooKjh07dtGFhyNHjnDkyBGys7OpqqoCoGXLloSHh7svOvTp04eIiAh69epF9+7d6dq1K127dlU57gcqKysjPz+f7Oxs8vLyyMzMvKjklpmZSV5envvtQ0JC6Nu370UFt4EDBzJo0CB69Ohh8CMRr5GfD3/7G7zwAoSFwR//CHfdBQEBppOJXLXa2lpOnjx5yRTMI0eOcPz4cfdFdT8/P7p16+YueNc/28LCwtznmi6u/zA1NTXk5+e7z7WTJ0+6z7K6s+3kyZNUVlYCEBgYSM+ePS86z+rOtL59+2r1tniM8YxnJCN5iZdMRxFplnR+m6XzW5qbjWxkClPYzGYmMMF0HLkKN3IjwxnOUpaajiIiIiIiIiIiV0DFNzGuqqqK7OxsMjMz3Xd213+qfxECoEWLFu4CXI8ePejatSvdunWjW7dudO3alQ4dOlz01L59e1q2bF53bJ4/f56zZ8+6nwoLCzlz5gzZ2dnk5+eTl5dHTk4O+fn55OTkUFRUdNGfDwsLc1/A6d27t/up7mW6S14aTFYWPPEELF0KAwbAH/4At98OLVqYTibSaAoKCi4qFn/9bCsoKLjo7Tt06OA+w+rOtboL6x07dqR9+/YXnWuNtjK8thYMFMvLy8spLCy86Fw7c+YMBQUF5OTkkJeXd9G5lp+fT01NjfvPh4SE0KdPn8sWFOqmybbQ1xzxAlasdKQjb/Km6SgiPslrz29DdH6LL6ulljGMoTOdceI0HUeuwlGOMpCBrGc9k5lsOo6IiIiIiIiIXAEV38QrnDlzhtzcXAoKCjh16hQFBQWXlLvy8vIoKChw3yFeX0hIyCWFuNatW9O2bVtatWpF69atadOmDYGBge6iXEhICCEhIe7SXN3L6rvcy8A1TaCwsPBbX3b+/HkqKys5e/YsFRUVXLhwgQsXLlBRUUFhYSGVlZUUFxdTXFx8Scntmz7Gr19wqV8K7NKlCz169CAsLIxWrVpd0b+DyBX74gt46il47TUYMgT+/GeYO9dIyUbEtNLSUnJzc8nJyaGgoMBdWq6bgJKfn09ubi65ubmUlJRc8udbtmzpLnbXnWmhoaG0bduWwMBA2rVrR1BQEMHBwZc92+p06NDhor+3y4oVVC1ceNnMdWfWN72svLyckpKSi862yspKzp8/T0lJCeXl5RQVFVFSUnLJRfJv+hi7dOlC9+7dCQsLu2ypoO717du3/8H/BiKeaAELOMtZHDhMRxGRy/DU8/ubXgbffX4HHDuG/4kTHO3XT+e3yA9gx8585pNGGqMYZTqOXIXHeZwXeZFssglAE+pFREREREREvJGKb9LsFBcXX/Kg/OV+X1paSlFREWVlZZSWllJcXExFRQVFRUXuC/hNoe5iRmhoKMHBwQQFBV30sjZt2lwywe5yv29uU+2kmcrIcJXeVq6EESPgoYfAZjOdSsRjlZeXX/Yc+/rLzp8/z7lz56isrPzGs+3bjAHsQDhwNd8Y1hXGv+lsa9269TeeY815Ko7I9/F7fs8mNrGLXaajiMhVaqrz+2r9L+AuYLrOb5HvrYIKRjKSUYziPd4zHUeu0ghGMI5x/IN/mI4iIiIiIiIiIldIxTeRb1FcXExVVRWA+473+kpLSykrK7vsn23btu0lq1nqv6z+NDkRn3PgACxe7CrARUfDY49BbKzpVCLNWv1Sd1VVFcXFxe7XdXngAdqsXMlnb73FhcjIS/5s69atL5kWWjcxFSAwMJDQ0NBGTC/S/D3P8/yFv3CKU6ajiIgH+bbz+5teVue7zu/Q++8n8PXXYetW+NGPGiG9SPPzxP/8SiedvvQ1HUeuQgYZRBLJh3zIOMaZjiMiIiIiIiIiV0jFNxERMeejj+CJJ8DphJgY13+PH286lYhvKS6Grl2hrAwWLYLHHzedSMQnvcd7LGAB5ZTjj7/pOCLiCwYPhs8/h4kTISXFdBoRj5dFFpFEsohF/IE/mI4jV+lhHmYpSznBCX3vJSIiIiIiIuLF9FO9iIiYEx0NDgds3w4tW8KECTBpEqSlmU4m4jveew8qK13/vWKF2SwiPqw73amiitOcNh1FRHxBYSEcPuz6702b4JNPzOYR8QK/4Tf0pCf3cZ/pKNIAlrOcW7lVpTcRERERERERL6ef7EVExLyYGNcFt6QkKCqCG24AqxU+/dR0MpHm75//hLoBwIcPf3URXESaVHe6A5BDjuEkIuITPvroq/M/MBAWLzabR8TDrWY1Dhz8k38SRJDpOHKVdrGLwxxmPvNNRxERERERERGRq6Tim4iIeI64OPjPf2DjRjh1Cq6/HubNc61gEpGGt3+/q2BaU+P6fWAgJCaazSTio7rRDVDxTUSayM6dronL4Jr8unYt7NtnNpOIhyqhhP/mv7mDO5jIRNNxpAEsZzn96McN3GA6ioiIiIiIiIhcJRXfRETE88TFudadLlvmugA3dKirAHf0qOlkIs3Lq6+6ym51qqpg5UpzeUR8WDvaEUywim8i0jS2bv1q1TlAQAA8/ri5PCIebDGLOcMZnuVZ01GkAdRSix07t3IrfviZjiMiIiIiIiIiV0nFNxER8Ux+fmCzwcGDrgLcnj2uAtzCha5pcCJydcrK4I03Lr7oXVvrmrpYUGAslogv60Y3Fd9EpPFVV7vO+7pVp+D6fiAhAQ4dMpdLxAMd5CB/4288xVPuteTi3Xawg0wyteZUREREREREpJlQ8U1ERDybv/9XBbj/9/8gKQn69XMV4HJzTacT8V4JCXD+/KUv9/MDp7Pp84gI3elOLjrbRKSR7d8PJSWXvrxFC3jyyabPI+KhqqjiLu7iWq5lIQtNx5EGspzlDGEIIxlpOoqIiIiIiIiINAAV30RExDsEBsKCBfDZZ/DSS+BwwIAB8OCDcPas6XQi3mfJElex9HJWrWraLCICuIpvmvgmIo0uNdW12vTrKivhnXfg+PGmzyTigR7jMfayl6UspQUtTMeRBlBDDQkkcBu3mY4iIiIiIiIiIg1ExTcREfEuLVvCPffAkSPwxBOuVY29e7sKcEVFptOJeIdjx2D7dteqs6+rroaNG+HChabPJeLjutOdbLJNxxCR5i419Ztf5+8PzzzTdFlEPFQaaTzFUzzHcwxnuOk40kA2sYkccrBhMx1FRERERERERBqIim8iIuKdgoPht791FeAWLXJNr+rf33Wh7nKrm0TkK6++evlJL3UqKyE5uenyiAgAfejDcTRpSUQa2YcfQlXV5V9XWQlLl8KpU02bScSDXOACP+bHTGACv+bXpuNIA1rOcq7jOoYy1HQUEREREREREWkgKr6JiIh3Cw2FBx6Ao0fhN7+BJ5+EPn1cBbiyMtPpRDxPVRW89prrwvY3CQiA1aubLpOIANCf/uSSywU0cVFEGkleHpw8+d1v99xzjZ9FxEPdx30UUMBrvIYffqbjSAOppJL3eZ/5zDcdRUREREREREQakIpvIiLSPHTsCI884irA3XUXPPooDBoEL7wA5eWm04l4jrVroaDg29+mstJVfLvcKlQRaTT96U8ttRzjmOkoItJcpaaC3zcUeVq0gKAg1/n/yiuQn9+02UQ8wHrW8yqv8i/+RTjhpuNIA9rABs5whnnMMx1FRERERERERBqQim8iItK8dO4MTz8NX3wBP/6xaxrc4MGui3fftNJJxJekp8OECTB8OAwdCj17QkgItG4NLVt+9XaFha6L4yLSZPrRDz/8OMpR01FEpLlKTYXa2q9+HxgI7dtDZCTcfjv8n/8DL78MK1e6XifiQwoo4Kf8lAUsUDmqGVrOcsYwhj70MR1FRERERERERBqQX21t/Uc8RUREmpmsLHjiCVi6FAYMgD/8Ae64A/zV/RZx69cP7rkHHnzQ9fsLF6CiwlWECwkxm03Ex/SkJ/dxH/dzv+koItIcOZ2um0F69YLwcAgLg+hoGDMGnn/edDoRY2qowYqVdNLZy17a0c50JGlAZZQRRhiP8Rj3cq/pOCIiIiIiIiLSgHTVX0REmreICFiyBD7/HMaNc61BveYasNsvnnYh4stKSyE4+Kvfh4RAhw4qvYkY0J/+mvgmIo3HYoFZsyAqylV6A1cB7sQJs7lEDFvMYpJJ5j3eU+mtGXLi5Dznmctc01FEREREREREpIGp+CYiIr6hb19XAW7fPtd6x/nzXdMtHA7TyUTMKy11rToVEeNUfBORJqfim/g4J04e4zFe5EXGMMZ0HGkEy1nOBCbQgx6mo4iIiIiIiIhIA1PxTUREfEtkJKxYAXv3Qu/eEB8PMTGwaZPpZCLmlJSo+CbiIVR8E5Emp+Kb+LDDHOZO7uR2bmchC03HkUZQTDFrWct85puOIiIiIiIiIiKNQMU3ERHxTSNGuApwO3e6VjzGxsLYsbB1q+lkIk2ruhoqK1V8E/EQ/elPJplUUmk6ioj4ivBwyM2F8nLTSUSa1HnOcwu30Je+LGGJ6TjSSNawhiqqmMMc01FEREREREREpBGo+CYiIr4tOhqSkmDbNggIgPHjYdIk2L3bdDKRplFa6noeHGw2h4gAruJbFVVkkWU6ioj4iogIqK2F7GzTSUSaTC213M3d5JBDAgm0RjeBNFfLWc4kJtGJTqajiIiIiIiIiEgjUPFNREQEXNPetmxxleAKCyEqCqxW10pUkeaspMT1XBPfRDzCAAYAcIQjhpOIiM8ID3c9z1LhVnzHczxHAgm8y7v0pa/pONJIznKWjWzkVm41HUVEREREREREGomKbyIiIvXFxcEnn8DGjXDqFFx3HcybB4cPm04m0jjqJr6p+CbiETrSkS50IYMM01FExFeEhUHLlnDihOkkIk1iPetZxCKe4RkmM9l0HGlECSTgjz/xxJuOIiIiIiIiIiKNRMU3ERGRy4mLg127YNky19S3YcNgwQI4dsx0MpGGpeKbiMcZwQj2s990DBHxFf7+0LOnim/iE3azGxs27uAO7ud+03GkkS1nOTOYQTvamY4iIiIiIiIiIo1ExTcREZFv4u8PNhtkZMA770BqKgwdCgsXQna26XQiDaOu+BYcbDaHiLiNZKSKbyLStMLDVXyTZu8LvmAGM7iBG1jCEtNxpJEVUMAWtjCf+aajiIiIiIiIiEgjUvFNRETku9QvwL30EqxdCwMHwm9/C3l5ptOJXJ2SEtdzTXwT8RgjGMEBDlBNtekoIuIrIiIgK8t0CpFGc4YzTGMaXejC+7xPS1qajiSNbDnLCSKI6Uw3HUVEREREREREGpGKbyIiIt9XYCDcc49r3enzz4PdDv37w4MPwtmzptOJXBmtOhXxOCMYQSmlHEPrtUWkiWjimzRjZZQxk5mc5zwf8IHWXvqI5SxnFrMIIcR0FBERERERERFpRCq+iYiI/FAtW7oKcIcPwxNPwOuvQ+/ergJcUZHpdCI/jIpvIh5nOMNpQQv2sc90FBHxFSq+STNVQw13cif72c8HfEAvepmOJE3gBCdIJVVrTkVERERERER8gIpvIiIiVyokxLXu9OhRWLQIlixxTYB75pmvykQinq60FPz8oFUr00lE5H+0pjX96c9+9puOIiK+IjzcNcG4uNh0EpEGdT/3k0giCSQwghGm40gTWc5y2tKWyUw2HUVEREREREREGpmKbyIiIlcrNBQeeMBVgPvNb+DJJ10T4J55BsrKTKcT+XYlJa7Sm5+f6SQiUs8IRqj4JiJNJzzc9fzkSbM5RBrQ4zzOi7zIW7xFLLGm40gTWs5y5jCHIIJMRxERERERERGRRqbim4iISEPp2BEeecRVgLvrLnj0URg0CF55BaqqTKcTubzSUq05FfFAIxihVaci0nQiIlzPte5Umom/8Tf+xJ94iZe07tLHHOUoaaTp311ERERERETER6j4JiIi0tA6d4ann4bPP4fZs+Hee2HgQFcBrrradDqRi5WWQnCw6RQi8jUjGckxjnGBC6ajiIgv6NDBNcU4K8t0EpGr9nf+zu/4HS/yIr/iV6bjSBN7j/foTGdu5mbTUURERERERESkCaj4JiIi0lh69YIXXoBDh2DyZPj1r2HECHjrLaipMZ1OxEUT30Q80ghGUEMN6aSbjiIiviI8XBPfxOu9yqvcx308zdP8ht+YjiMGLGc585hHAAGmo4iIiIiIiIhIE1DxTUREpLH17g1LlsD+/RAV5VqDes01YLdDba3pdOLrVHwT8Uj96Ecooexlr+koIuIrVHwTL/car7GQhTzBE/ye35uOIwZkkMEBDmjNqYiIiIiIiIgPUfFNRESkqQwZ4pr2tncvDB0K8+fDmDHgcJhOJr6spETFNxEP5I8/13M9/+E/pqOIiK9Q8U282Ou8zj3cw2IW8wf+YDqOGPIu79KLXsQQYzqKiIiIiIiIiDQRFd9ERESa2rBhsGIFfPopRERAfDyMHQubN5tOJr6otBSCg02nEJHLGM1oPuIj0zFExFeEh0NWlukUIj/YUpbyM37GwzzMQzxkOo4YtJzlzGc+/nrIW0RERERERMRn6FEAERERU0aOdBXgUlOhVSuYOBEmTYJPPjGdTHyJVp2KeKzRjOYgBznHOdNRRMQXRETAyZOmU4j8IM/zPD/jZzzEQzzCI6bjiEG72MVhDmvNqYiIiIiIiIiPUfFNRETEtDFjIDkZtm2Dykq48UZXAW73btPJxBeo+CbisaKJpoYa0kgzHUVEfEF4uGsF+unTppOIfC/P8Az3cz/P8iyP8qjpOGLYcpbTj35EEWU6ioiIiIiIiIg0IRXfREREPMXYsbBlCyQlwdmzEBUFVivs22c6mTRnKr6JeKwe9KAXvfiYj01HERFfEB7uen7ihNkcIt+hllru4z4WsYhXeIXf8TvTkcSwWmqxY+c2bsMPP9NxRERERERERKQJqfgmIiLiaeLiXOtO16xxrZsaNQrmzYMjR0wnk+aopASCg02nEJFvMJrRKr6JSNNQ8U28QDXV3M3d/IN/sIxl/IyfmY4kHmAHO8gkU2tORURERERERHyQim8iIiKeyM/PNe0tLQ2WLYO9eyEyEhYsgOPHTaeT5kQT30Q8mopvItJkgoOhUyfIyjKdROSyyilnHvNYwQocOJjLXNORxEMsZzlDGMIIRpiOIiIiIiIiIiJNTMU3ERERT+bvDzYbZGTAO+9AaioMGQILF0JOjul00hyo+Cbi0UYzmhxyyEJFFBFpAuHhmvgmHqmQQqYwhS1sIYUUJjPZdCTxEDXUkEACP+bHpqOIiIiIiIiIiAEqvomIiHiD+gW4l14CpxMGDIDf/hby8kynE2+m4puIR4siigACNPVNRJpGRISKb+JxjnGMm7iJIxzhQz5kNKNNRxIPspnN5JCjNaciIiIiIiIiPkrFNxEREW8SGAj33ONad/r887BihasA9+CDUFhoOp14o5ISFd9EPFgwwQxjmIpvItI0NPFNPMxHfMQYxhBIIKmkMpzhpiOJh3mXd4kiikEMMh1FRERERERERAxQ8U1ERMQbtWzpKsAdOQIPPQSvvAL9+8Mjj8C5c6bTiTcpLYXgYNMpRORbRBOt4puINA0V38SD2LEzkYlcx3VsYxsRRJiOJB6mnHJWsYrbuM10FBERERERERExRMU3ERERbxYSAg88AJmZ8Pvfw9//7irAPfOMq9Ak8l206lTE441hDLvYRRllpqOISHMXHg6nTkF1tekk4sNqqeUZnuFWbuXn/BwnTtrS1nQs8UBrWcs5zmnNqYiIiIiIiIgPU/FNRESkOWjTxlWAO3oU7r4bFi+GPn1cBbgyFSXkW5SVqfgm4uEmMpEyyviIj0xHEZHmLiICqqogN9d0EvFRFVTwE37CIhbxIi/yAi/QghamY4mHepd3uZmb6UlP01FERERERERExJAA0wFERESkAXXqBE8/DfffD3/9q2v16csvw6JFcNddEOCZR39NTQ1FRUWmY/ieigo6VFVxvrqayrNnTadp1oKDgwkKCjIdQ7xUOOH0pS+b2cwEJpiOI+JxiouLqaqqMh2jWfBv25Z2QHF6OlVahe4RAgMDCQ0NNR2jSeSRx1zmsp/9fMAHTGay6Ujiwc5xjg/4gJd4yXQUaWb0+IT4Oj1+ISIiIiLexq+2trbWdAgRERFpJCdOwF/+AkuWQPfu8Ic/uCbCtTA/NaG8vJzNmzezevVqEhMTycnJMR3J5/gB7YFyoMRwluYuODiYKVOmMHPmTCwWC506dTIdSbzM3dzNYQ6zla2mo4h4hH379rFmzRpWr17N7t27TcdpNvyBMCAX0INFnsHPz4+oqChmz57NzJkziYyMNB3pihRRRDvafePrd7ITGzZa05rVrGYYw5ownXij13mdX/JLcsmlPe1NxxEvd/78eTZu3MjatWtZu3YteXl5piOJGNO6dWtiY2OxWCxYLBZ69tRUTRERERHxbCq+iYiI+ILMTHjySVi6FAYNck2CmzsX/PyaNEZRURHr1q1j9erVrFu3juLiYq677jpmzZrFjTfeiL+/trBL83Ts2DFWr17Npk2bqKqqYty4ccycOZOZM2fSp08f0/HEC/ybf3M3d3OGM4QQYjqOSJOrrq5mx44d7rLbsWPH6NGjB/Hx8UydOpWQEH1eSPN07tw51q1bR2JiIvn5+QwcONBdgouOjvaK759LKCGKKP7FvxjHuEte/wqv8F/8F3HE8W/+TQc6GEgp3mYSk2hLWxJIMB1FvFRmZiZOpxOHw8GWLVuoqqoiOjoai8XC9ddfj18TP14i4ikyMzNZu3YtGzdupKSkhFGjRmGxWLBarfrcEBERERGPpOKbiIiIL/nsM1cB7p13YNgwePhhsNka9V0WFBSwbt067HY7SUlJ7geTrVYrt9xyCwMHDmzU9y/iSUpKSkhJScFut+NwOCgsLCQyMhKr1YrFYiEmJkYPIstlZZNNT3qSRBJxxJmOI9IkysrK2L59Ow6HA7vdTk5ODv369cNisWCz2bjpppu8ovQj0hBqamrYs2cPDoeDFStWkJGRQefOnZk2bRpWq5Xp06d7bAH0F/yCJSyhO905yEH3dK4yyvgNv2EpS/k9v+dJnsQffU7Ld8sll170YhnLmMtc03HES9T/Oup0Otm9ezetW7dm4sSJWK1WrFYr3bt3Nx1TxGPUfS+enJzM+++/z+eff06XLl2YOnUqVquVqVOn0qZNG9MxRURERERUfBMREfFJBw7A4sWwciWMHg1//CNYrQ321x87dsx9kXrnzp0EBQURGxuL1Wpl1qxZdO3atcHel4i3qq6uZufOndjtdlatWsXJkyfp3bs3U6ZMwWKxMHXqVAIDA03HFA8ykIHMZz6P87jpKCKN5uzZsyQnJ+NwOFi9ejXFxcVERkZis9mYN2+e1655FGlo9b/fTk1NdZc3bDYb8fHxtG/vGasf17Oe6UynlloCCMCChfd5nxOcYA5zOMQh3uRNZjHLdFTxIn/n7/yZP5NLLq1pbTqOeLC6G4+cTidOp5Ps7Gz69OnD5MmTsVgsTJ48maCgINMxRbxC3fceTqeTLVu2EBAQwNixY7FYLNxyyy2Eh4ebjigiIiIiPkrFNxEREV/2n//AY4+B0wkxMfD44zBhwhX9Venp6djtdux2OwcPHqRTp05Mnz4dq9XKtGnTCA0NbdjsIs1M3eeQ0+kkLS2Njh07Ehsbi8ViYfbs2bqTWriHe0gnnR3sMB1FpEFlZWWxfv16HA4HGzZsoKamhujoaGw2G3PnzqVnz56mI4p4tPz8fNavX4/dbmfjxo1UV1e7P4fmzJlDr169jOQqoIChDOUsZ6mhBgA//LiP+3id1wknnFWsoh/9jOQT73UjNzKc4Sxlqeko4oEyMzPZsGEDDoeDpKQkKisrL1nVKCJX5/Tp02zevBmHw0FiYiJFRUUXTbPXZGYRERERaUoqvomIiAikprrWnm7aBHFx8NRTEBX1rX+k/rSqhIQETp06RZ8+fYiPj8dqtTJhwgQCAgKa6AMQaV6OHz9OYmKi+07qwMBA99TE+Ph4unXrZjqiGPAe77GABZzhDG1QEVK8W3p6Ok6nE4fDccm0qpkzZ9KuXTvTEUW8UmFhIUlJSTgcDtasWcO5c+fcUxObsvBRSy0zmEEyyVRSedHrWtACCxbe4z1N65If7ChHGchANrCBSUwyHUc8wOVWmAYHB3PzzTfr5yeRJlBVVcVHH32E0+lk9erVHDp06KJ17FOmTKFt27amY4qIiIhIM6bim4iIiHxl+3ZYtAi2bnUV4J59FkaNcr+6bk2I3W6/6I7Opr6QJuJLTp8+zQcffIDdbicpKYmqqiqio6OxWq3Mnj2bQYMGmY4oTSSHHHrQg/WsZwpTTMcR+UHqX5RetmwZhw4dokuXLkydOhWbzaZVYyKNoKysjO3bt+NwOFi5ciXZ2dn07dsXq9Xa6Deq/IN/cC/3uie91RdAAMMYxid8QiBa6y4/zKM8ysu8zClOEYButPJV9VeYOhwOcnJy6Nu3L5MmTcJisTBlyhRatmxpOqaIT/q2laizZ88mIiLCdEQRERERaWZUfBMREZFLJSbCn/4E+/dTPmsWiRMm8NbGjZeUbm655RYGDhxoOq2Iz6hfPnU4HBQWFl60TiQmJgY/Pz/TMaURDWEIs5jF0zxtOorId6pfurHb7eTk5NCvXz8sFgs2m00rkESaUP3y6YoVK8jIyLhoGsv06dMJCQlpkPeVQQajGEU55d/4Ni1owR/5I4tZ3CDvU3zHEIYwjWk8z/Omo0gT++KLL9i4caN7hWlVVRXXXnutVpiKeLAvv/ySTZs2XXYlalxcnLZFiIiIiEiDUPFNRERELnHs2DGciYmc/te/mHLoEHNateKGuDisViuzZs2ia9eupiOK+Lz664ZXrVrFyZMn6d27N1OmTMFisTB16lQCAzVFpbn5Fb8ijTQ+5mPTUUQu6+zZsyQnJ+NwOFi9ejXFxcXu7cUhIQAAIABJREFU6bDz5s0jMjLSdEQR4atpLHa7/ZJ1w/Hx8bRv3/6K/t4KKogiis/47JIVp1/njz8f8iFjGXtF70t8zy52cQM38DEfcyM3mo4jjezrK0zT0tIICQnRClMRL1X3GIbT6WTNmjV89tlndO7cmZtvvhmLxcKsWbO0ElVEREREroiKbyIiIgJAeno6drsdu93OwYMH6dSpE9OnT8dqtTJt2jRCQ0NNRxSRb1H3OVx3Uahjx47Exsa614m0adPGdERpAKtYhQ0bOeTQFZWQxTNkZWWxfv16HA4HGzZsoKamhujoaGw2G3PnzqVnz56mI4rIt8jPz2f9+vXY7XY2btxIdXW1+3N4zpw59OrV63v/XQ/wAH/jb1RR9a1vF0gglVQygAEc4ABBaNWxfLf7uI9EEjnMYfzQlOPm6MKFC2zatAmn00liYiK5ubn069ePuLg4rTAVaWbqr0T98MMPqa2tZfTo0VitVmbPns2gQYNMRxQRERERL6Him4iIiI+qPy0qISGBU6dO0adPH+Lj47FarVo3IOLFjh8/TmJiIk6nky1bthAYGEhsbKwmIzQDxRTTmc4sZSm3c7vpOOLD0tPTcTqdOByOS6ZFzZw5k3bt2pmOKCJXoLCwkKSkJBwOB2vWrOHcuXPuqY3ftUpwG9uYwARqqLns6+vKbu1oxyQmYcVKPPG058qmy4lvqaGGCCL4GT/jER4xHUca0PHjx91fd+rKt1phKuJb6q9EdTgcFBYW0q9fP/fXAT1GKSIiIiLfRsU3ERERH1JSUkJKSgp2u53ExESKioq+94UsEfFOp0+f5oMPPsBut5OUlERVVRXR0dG6i9qLTWQiPejBv/m36SjiQ+qvG1u2bBmHDh2iS5cuTJ06FZvNxuTJkwkK0sQmkeakrKyM7du343A4WLlyJdnZ2fTt2xer1XrJRehCChnGMPLIo5pqAFrQgtr/+TWCEUxjGhYsxBCjaV3yg6WQQhxxpJNOJFqb7c2qq6v59NNPv3GF6cyZMwkLCzMdU0QMudxK1E6dOjFx4kQsFotushERERGRS6j4JiIi0swVFBSwbt26y5ZebrnlFgYOHGg6oog0kfrl17q7qCMjI7FarVgsFmJiYvDz04VoT/ccz/E0T5NPPi1oYTqONGP1Sy8rVqxwrxuzWCzYbDZuuukm/P39TccUkSZQv/y6YsUKMjIy6Ny5M9OmTcNms/HGjDdY5b8Kf/ypoYa2tGU607FgYQpT6Exn0x+CeLm7uZu97GUXu0xHkSvwTStM66Y5jRs3TitMReSyvm0l6qxZsxg8eLDpiCIiIiJimIpvIiIizVDdg0J2u52dO3cSFBTkXnM4a9YsunbtajqiiBhWf93xqlWrOHnyJL1792bKlClYLBamTp1KYGCg6ZhyGemkM5zhpJLKGMaYjiPNzNmzZ0lOTsbhcLB69WqKi4vd02HnzZtHZKSm7IjIxT9vpPZPpfaNWtpkteHmczfz676/JjY0VuVsaTDllNONbjzMw9zHfabjyPd0uRWmdTfhWa1WfU8hIj/YmTNnSElJ0UpUEREREbmIim8iIiLNRHp6Ona7HbvdzsGDB+nUqRPTp0/HarUybdo0QkNDTUcUEQ9W9zWkbt1Qx44diY2NxWKxMHv2bNq0aWM6otTTl77cyZ0sZrHpKNIMZGVlsX79ehwOBxs2bKCmpobo6GhsNhtz586lZ8+epiOKiIeqoYalRUspSSoh6c2ki8otNpuNOXPm0KtXL9MxxcutYhU2bGSRRU90Jnmqy60wrf8zhdVqpUOHDqZjikgzUX8lamJiIhkZGVqJKiIiIuKjVHwTERHxUvWnNSUkJHDq1Cn69OlDfHy87nIUkaty/PhxEhMTcTqdbNmyhcDAQPfUyPj4eLp162Y6os/7Fb/ik//5JXIl0tPTcTqdOBwOUlNTad26NRMnTsRms+kikYhcscLCQveEpzVr1nDu3Dn31Eir1cr1119vOqJ4IRs2znCGFFJMR5Gvqb/CdM2aNeTl5V00fWn8+PGaIi0iTeLrK1HrbuaxWq3MnDmTIUOGmI4oIiIiIo1ExTcREREvUlJSQkpKCna7ncTERIqKinQhSUQa1enTp/nggw+w2+0kJSVRVVXlfvB49uzZDBo0yHREn+TAwUxmcopTdKe76TjiBWpqatizZw8Oh4Nly5Zx6NAhunTpwtSpU7HZbEyePJmgoCDTMUWkGSkrK2P79u04HA5WrlxJdnY2ffv2da851I068n0UUkh3uvN/+b/czd2m4wiuckndWvSvrzCNj49n6NChpiOKiI/7rpWoKuWKiIiINC8qvomIiHi4goIC1q1bd9nSyS233MLAgQNNRxQRH1G/fFv34HFkZCRWqxWLxUJMTAx+fn6mY/qEC1ygM535F//if/G/TMcRD1W/dLJixQpyc3PdF3xsNhs33XQT/v7+pmOKiA+oX75dsWIFGRkZdO7cmWnTpql8K9/qVV7lXu4lhxza0950HJ9Uf51gcnLyJStM4+Pjad9e/zYi4pnqfw1zOBwcPHhQX8NEREREmhkV30RERDxQ3Xh+u93Ozp07CQoKcq8ZnDVrFl27djUdUUR8XP11y6tWreLkyZP07t2bKVOmYLFYmDp1qu6gbmRTmEIHOrCMZaajiAc5e/asewrL6tWrKS4udk+HnTdvHpGRkaYjiohc9PPO19ct6wK01DeBCYQRxnKWm47iU+p/P+F0Ojl79qymJYlIs1B/JerWrVs1tVJERESkGVDxTURExEOkp6djt9ux2+0cPHiQTp06MX36dKxWK9OmTSM0NNR0RBGRb1T3NczpdF4yBWL27Nm0adPGdMRm5+/8ncUsJp98AtCqOF+WlZXF+vXrcTgcbNiwgZqaGqKjo7HZbMydO5eePXuajigi8o3y8/NZv349drv9orWJNpuNOXPm0KtXL9MRxZAssuhLX1azGitW03GavfplkA8//ND9/YTKICLSXKnkKyIiItI8qPgmIiJiSP1pSQkJCZw6dYo+ffoQHx+P1WplwoQJBASoyCAi3uf48eMkJibidDrZsmUL/5+9e4+Lssz7B/4ZkPNhOIhAaII+ecwskUqFPICiBYJsqOspK0/1tIq+JN3WVTddz+lqWR56filtnqhEBs1E0lYFn7Q0V00wzVQEBREEBQz4/v7oYZZxBphB4B7g8369eL3ynmvu63PfQ3N9ueea+7KystLetXL48OHw8vJSOmKzcBEX0Qmd8C2+xQt4Qek41MjOnTunXa7n4bslRUREQK1WKx2RiMhk+fn5SE5OhkajwZ49e3D37l3tXSvDw8Ph7++vdERqREuwBO/hPWQhC9awVjpOs2No+T93d3cMGjSIy/8RUYtTXl6O06dPayfBcVlnIiIioqaDE9+IiIga0f3795GSkoL4+HgkJiaioKCAH+QQUbOWm5uLffv2IT4+HsnJySgrK9PeOWLEiBHo1KmT0hGbtG7ohlCEYg3WKB2FGlhFRQVSU1ORlJSEhIQEpKenw8PDA0OHDkV0dDSGDBkCGxsbpWMSEdWbkpISHD16FBqNBp9//jlu3LgBPz8/hIeH84tCLUQP9EB/9McH+EDpKM1GXl4eUlJSoNFooNFokJ+fz7sbEREZcPnyZe3d4KrekbayDunWrZvSEYmIiIjo/3DiGxERUQPLycnBV199ZXDSR1RUFJ544gmlIxIRNYqqk38rP2jr1q0bwsPDERYWhn79+kGlUikds0n5K/6KLdiCq7gKFXjumpuqkz527dqF7Oxs7YfT0dHR6Nu3LywsLJSOSUTU4CoqKnDq1Cnt++FPP/2E1q1bY9iwYZz820z9gB/gD3+kIQ3P43ml4zRpNS1hGhERgS5duigdkYjIrN27dw/ffPMNkpKSsGfPHty8eZOThomIiIjMCCe+ERERNYDKC8vx8fFIS0uDjY2Ndpm/yMhItGnTRumIRESKqrrc85dffonr16+jffv2CA0NRVhYGIYOHcoLx0Y4hVPohV74Dt8hAAFKx6F6cOfOHe2dBRISElBYWKi9O+zIkSN5ZwEiIuj+vfXwcs9ciqx5mIVZSEQiLuIiJ/ebqOoSpomJifjpp590ljDlkuhERHVnaElUV1dXhISEaCfCubq6Kh2TiIiIqEXhxDciIqJ6cu7cOcTHxyM+Ph7nz5+Hu7s7XnzxRYSHh2PYsGFwdHRUOiIRkdmqfA+tvHDs5uaG4OBghIWFYcSIEXByclI6otnqiI4YiZFYiqVKR6E6unr1Kvbv3w+NRoOvv/5aeyeW6OhovPzyy/Dx8VE6IhGR2bp16xb279+P+Ph4naXIoqOj8Yc//AFt27ZVOiKZqBzlaIu2mIqpWIiFSsdpEmpbwpRLAxMRNYxffvkFycnJXBKViIiISEGc+EZERFRHVe9W9MUXXyAzMxO+vr4YPnw4LywTET2CX375BYmJiUhKSsLhw4dhZWWlvWvm8OHD4eXlpXREszIbs5GIRGQgQ+koZIJz584hKSkJGo1G725FvBMLEVHd5Ofnaz983rNnD+7evau9a2Z4eDj8/f2VjkhG+BpfYyiGIh3p6IROSscxWw8vYSoieO6557R3mu/cubPSEYmIWpSqS6ImJiYiOzsbHTp00N4NLjQ0FNbW1krHJCIiImp2OPGNiIjIBPfv30dKSgri4+ORmJiIgoICfpBCRNSAcnNzsW/fPsTHxyM5ORllZWXab0+PGDECnTrxw9BUpKIf+uHf+DeexJNKx6FqVFRUIDU1FUlJSUhISEB6ejo8PDwwdOhQREdHY8iQIbCxsVE6JhFRs1FSUoKjR49Co9Hg888/x40bN+Dn56e9Awu/qGS+xmM8LuESUpGqdBSzUnUJ0z179uDChQto3bo1Bg4cyCVMiYjMjKElUR0cHDBw4ECEh4cjIiICnp6eSsckIiIiahY48Y2IiKgWOTk5+OqrrwxOuoiKisITTzyhdEQiohah6uTjyiWcunXrhvDwcISFhaFfv35QqVRKx2x0FahAO7TDFEzBAixQOg5VUXXSxa5du7Tf+A8LC0N0dDT69u0LCwsLpWMSETV7FRUVOHXqlPb9+KeffkLr1q0xbNgwTj42M/dwD17wwjIsw3/jv5WOo7jbt2/jm2++gUaj0X75jkuYEhE1PVWXRK28vvz0009r38/5ZWoiIiKiuuPENyIiIgMqlwyJj49HWloabGxstMvsRUZGok2bNkpHJCJq0aouN/3ll1/i+vXraN++PUJDQxEWFoahQ4fCyspK6ZiN5r/x3ziKo/gRPyodpcW7c+cODh48CI1Gg4SEBBQWFmrvDjty5Eh069ZN6YhERC1e1b/3Hl5uevjw4XBxcVE6Yov1T/wTr+E13MANtEZrpeMooqYlTHnHYyKipq/yS31JSUnQaDTIysrikqhEREREj4AT34iIiP7PuXPnEB8fj/j4eJw/fx7u7u548cUXER4ejmHDhsHR0VHpiEREVI3K9/DKJUTc3NwQHByMsLAwjBgxAk5OTkpHbFApSEEIQpCOdHQCPwxtbFevXsX+/fuh0Wjw9ddfo6KiAs8//zyio6Px8ssvw8fHR+mIRERUjVu3bmH//v2Ij4/HgQMHUF5ern0P/8Mf/oC2bdsqHbFFGYqhsIEN9mCP0lEaTVlZGY4fP66zHHrlHQnDw8MRGhoKZ2dnpWMSEVEDqHpX2qSkJPzwww+wt7fXLok6fPhweHl5KR2TiIiIyKxx4hsREbVYVe8W9MUXXyAzMxO+vr4YPnw4lwwhImrCfvnlFyQmJiIpKQmHDx9Gq1atEBIS0qwvGpejHF7wQixi8TbeVjpOi3Du3DntN/QfvltQREQE1Gq10hGJiMhE+fn52mXI9uzZg7t372rv2sllyBreLdyCD3zwGT7DSIxUOk6DMrSEabdu3RAeHo6wsDAuh05E1EJduXIFBw4c4JKoRERERCbgX89ERNSi3L9/HxqNBhMmTIC7uzuCgoJw8OBBTJo0CSdPnsQvv/yCtWvXIiQkhJPemqGff/4ZKpUKO3bs0G5zdHSESqXS+7GwsICHhwciIyNx4sQJBVPrqi6vSqWCra0tnnrqKaxfvx7m9N2GhIQEnZwlJSUN3ueOHTt0zktVhn4PqHnx8/PDjBkzkJycjKysLGzcuBEAMH36dLRt2xaBgYFYvnw5MjIyFE5afyxhiXCE40t8qXSUZquiogJHjx7F3Llz0aVLFzz55JN477330KFDB+zZswd5eXnaGoOT3hqPku/pSoxv1LBYs5CLiwuio6MRFxeHmzdvIjk5GSEhIdi8eTN69+6NDh06YMaMGTh48CDKysqUjtvsfIbPYA97hCNc6SgN4vLly1i7di0GDx4MLy8vTJgwAVlZWfjb3/6GX3/9FefOncOyZcsQGBjISW8mMvZv/VWrVimYsnqrVq3SZqx6l8mioiK9Y0hLS6t1f7GxsTrPWbx4cUPGbzZ4vcU4rF0alq+vL6ZMmQKNRoO8vDzs3r0b/v7+2LRpk7YWmTp1KjQaDR48eKB0XCIiIiKzwL+giYio2cvJyUFcXBzCw8Ph5uaGESNG4PLly/jzn/+MjIwMnDt3DgsXLuQ35lqooqIinDp1CgAQEREBEYGI4M6dO9i0aRPS0tLQr18/HDx4UOGkv6sub2lpKY4fPw5nZ2e89dZbmDNnjsJJ/yMyMhIigoiIiEbrc/To0RARBAcHN1qfZJ5at26NCRMm6Fw07tChA5YtW4bOnTuje/fumDt3Lo4ePWpWH2DUxR/wB3yH73AN15SO0myUlJTg4MGDmDFjBnx8fBAUFIT4+HiEhobiyJEjyM7O1tYYNjY2SsclExQVFeGJJ55AWFhYnfehxPhGDYs1C1Vla2uLkJAQrF27FteuXcPJkycxYcIEJCcnY/DgwfD29tbWGKWlpUrHbRb+iX8iGtGwg53SUepFWVmZzqT5jh07YvHixfD29sa2bdu0kytnzJiBxx9/XOm4zY6hv51nz56tcCrDZs+eDRFBz549dbY7OjpCRLTHAQCLFi2qcV+3b9/Ghg0bAABjx46FiGDevHkA6qf+qc/9mBtebzEOa5fGY29vj/DwcGzcuBHXr1/X1iLff/89IiIi4ObmhvDwcGzatAnZ2dlKxyUiIiJSDCe+ERFRs1T5TerAwEB4eXlh2rRpAIB169bhxo0bOHr0KObMmYMnnnhC4aRkrtRqNUaMGIHVq1fjt99+Q0xMjNKRamRtbY2nn34a27dvh4WFBdasWYO8vDylYxGZlcqLxnFxccjNzcWRI0cQEhKCzz77DEFBQfDz89N+c/q3335TOq7JBmMwXOGKHeC36x9FXl4e4uPjMWHCBLRp0waDBw/GwYMHMXXqVJw7dw6XLl3S1hi8G0vTJSKoqKhARUVFo/ft6OiIwMDARu+XiOrOwsIC/v7+WLhwIc6fP49Lly5h3rx5uHz5ss4Hz3FxccjPz1c6bpP0E37CD/gBYzFW6SiPJDc3V1tHVN5lXqPRIDIyEkeOHMHNmzcRFxeH6OhoODs7Kx2XmhA7Ozu0b98eX331FU6ePFltuzVr1qBdu3YGH6uv+kfJOkoJvN5C5qBqLVK5asnq1asB/H53ex8fH/Tu3RsLFy7E999/r3BaIiIiosbFq/RERNRsVN65rXv37ujYsSMWLVqEDh06YMeOHbh16xY0Gg2mTJmCNm3aKB2VmpCBAwcC+P33qyl8iNWuXTt4e3ujrKwMP/74o9JxiMyWpaUlAgMDtXdxOXv2LCZOnIjvv/8ew4cPh5eXF0aOHIm4uDgUFhYqHdco1rBGFKKwHduVjtLkXL16FZs2bUJ4eDi8vLzwxz/+EZcvX8aiRYtw/fp1bY3RrVs3paNSPXFycsKlS5ewb98+paMQURNUueTp0aNHkZ2djY8++ggAMHnyZLRu3VpbY1y/fl3hpE3HP/FP+MAHL+AFpaOYrOoSppV3AszKysK7776Lq1evcglTqhcWFhaYO3cuAFS7dGl+fj4++uijau9IVl/1T0uto3i9hcxJ+/btdZZETUhIgL+/v3Z59qpf7OOdaYmIiKi5a6V0ACIioroqLy9HWloa4uPj8cUXXyAzMxO+vr4YPnw41q5diwEDBqBVKw519GiqLn2oUqkUTGK8ysy2trYKJyFqOrp3747u3btj4cKF+OWXX5CYmIikpCS8/vrrmDp1KkJCQhAeHq6dFGeuxmAMPsbHOIdz6I7uSscxa+fOnUNSUhI0Gg1SU1NhZ2eHQYMG4eOPP0ZERATUarXSEYmIqAlo06YNJkyYgAkTJiA/Px/JycnQaDSYP38+YmJi0K1bN0RHRyM8PBz+/v5KxzVLAsFn+AzjMA6WsFQ6Tq1KSkpw9OhRaDQaJCQk4OrVq/Dw8MDQoUOxbds2DB06FE5OTkrHpGbo1VdfxeLFi5GYmIgzZ87gqaee0nl83bp1ePHFF9GxY0eFEjZ/vN5C5qjy7vbh4eGoqKjAqVOnoNFokJSUhM2bN2v/1q1s4+3trXRkIiIionrFr5gREVGTcv/+fWg0Gp1lQw4ePIhJkyZpb/O+du1ahISEcNIb6fmv//oviAhGjx5t9HMOHz4M4PdJMZWTIG7fvo1Zs2ahY8eOsLa2hqurK4YNG4ZDhw7pPLe0tBTz589Hly5dYG9vr10CKTExEeXl5Tptc3JyMH36dPj6+sLa2hoeHh6IiorC6dOnTTrGq1evIisrC87OzujeXXfSi7F9lJWVYefOnRg8eDC8vLxgZ2eHHj16YO3atQaXMql6PmxsbNC2bVuEhIRgy5YtKC4u1mufnZ2NUaNGwcXFBe7u7ggLC8OlS5f02plyTi5cuIDIyEio1Wo4ODggKCgIR48eNXiO6vJ7QC2Ln58fZsyYgeTkZGRlZWHjxo0Afl8+pG3btggMDMTy5cuRkZGhcFJ9/dEfbdGWy50aUFFRgaNHj2Lu3Lno0qULnnzySbz33nvo0KED9uzZg7y8PG2NwUlvTcfD7+kJCQlQqVTan/T0dIwcORLu7u7abR9//LFOm5KSEp19Vh1T7O3t8eyzzyIpKQkhISHa50yaNEkvS23j26pVq6BSqXDv3j0cO3ZMu6/aatbK56lUKrRt2xYnTpxAcHAwnJycYG9vj4EDB+LYsWN6zzO3esWY1yY3N9ekflizkLlxcXFBdHQ04uLicPPmTSQnJyMkJER795XKO8UdPHgQZWVlSsc1G9/iW/yKXzEe45WOUq3c3FzExcVh5MiR8PT01C6F/sc//hFHjhxBdna2dglTTnprfPX1fmns2Plw2+rGFFPHqdrY2NggNjYWIoK///3vOo8VFRXh/fffxzvvvGPwuQ+Pw5X1z8Pbr1y5UuPYZ+x+fv31V4waNQpOTk5wd3fH+PHjcefOHVy5cgXh4eFwcnKCt7c3Jk+erHOH7cWLF2v3UXVp+P3792u3t27duto8de3XGLzewtqlKTC0JOqaNWsA/OeaRtUlUat+4ZeIiIioyRIiIiIzd+vWLdm6dauEhYWJjY2NWFpaSr9+/WTZsmWSkZGhdDxqBk6dOiUAJCIiQrutoKBAvvzyS2nTpo1YWVlJcnKyiIhkZWWJn5+feHp6ikajkYKCAklPT5eoqChRqVSyefNm7T4mTZokarVaDhw4IPfv35fs7GyZPXu2AJBDhw5p2924cUPat28vnp6esnfvXiksLJSzZ89K//79xdbWVlJTU2vN++DBAzl16pT069dPrK2tJS4uTuc5pvSh0WgEgCxZskTy8vIkJydH1q1bJxYWFjJ79myd/VaeDy8vL9FoNHL37l3Jzs6WRYsWCQBZs2aNtm1ERIQ2d2pqqhQVFUlKSoo4OztLQEBAnfNevHhRXFxcxMfHRw4cOCCFhYVy5swZGTJkiPj6+oqNjU2tvwNExrh3754kJibK+PHjxcXFRQBIt27dZM6cOXLkyBGpqKhQOqKIiMyW2dJBOkiFmEceJRUXF0tycrJMnz5dvLy8BIB06NBBpk+fLkeOHJHy8nKlI1IDqRxz+vfvL4cOHZJ79+7J8ePHxdLSUnJycnTaFBcXa59naEw5e/ashISEiIeHh8ExxZTxTUTEwcFB+vXrZ/Ix9ezZUxwcHKRPnz7afk6cOCFPPfWUWFtby+HDh7VtzaFeqU5trw1rFmqOysvL5eTJk7JgwQLp2rWrAJDWrVvL+PHjJTExUUpKSpSOqKiJMlF6S2+lY+g5e/asLFu2TPr16ycWFhZia2srISEh8o9//EOuXr2qdDwygqG/natjythp7Jhiyjgl8vtY7+PjY/A4HBwcRETk/v374unpKRYWFnL+/Hltm2XLlsnIkSNFROTIkSMCQMaOHau3L0P1T9XtVce+5ORksbOzM1jP1LafqKgoOXnypBQVFUlcXJwAkGHDhklERIScOnVKCgsLZcOGDQJAZs6cqbf/6uolf39/cXd3rzbPo/bL6y2sXZqzymsaU6ZMkccee0wAiK+vr0yZMoX1CBERETVpnPhGRERm6dKlS/KPf/xDe4HZzs5OwsLCZOPGjXLz5k2l41EzU3lhs+qPSqUSd3d3GT58uHz33XfathMnThQAsn37dp19lJSUyGOPPSZ2dnaSnZ0tIiJ+fn7St29fvf46deqk80HyK6+8IgDks88+02mXlZUlNjY24u/vX2veyp8RI0bIzz//rNenKX1oNBoZMGCA3j7GjRsnVlZWUlBQoHc+du7cqdd+6NChBi/EajQanXZjxowRANqJCKbmjY6OFgDy+eef67TNzMwUGxsbXoilBlFWViZHjhyR6dOnS9u2bQWAtG/fXnvB+MGDB4pl+16+FwgkTdIUy6Ck27dvy65du2T8+PHi5OSknaC4YMECOXfunNLxqJFUjjn79u2rtU3VD2yrG1Nu3bol9vb2NU58M2Z8E3m0iW8A5NSpUzrbz5w5IwCkZ8+e2m3mUK9Up7bXhjULtQSmhc53AAAgAElEQVRV/95VqVRib28vYWFhsnXrVrlz547S8RpVkRSJkzjJOlmndBSdCfPt2rUTAOLh4SHjx4+XXbt2yd27d5WOSCYyZeKbKWOnsWOKKeOUiHET30REli9fLgBk3LhxIvL7ZBZPT0/58ccfReTRJr49PPa9/PLLBuuZ2vazd+9ene3du3cXAPLtt9/qbPfz85POnTvr5azrxLdH7ZfXW1i7tCRVJ3hXrUc2btwomZmZSscjIiIiMhonvhERkdk4e/asLFiwQLp16yYAxN3dXXuBubCwUOl41IyZcjFcrVYLAIMfeowfP14AyNatW0VE5I033hAAMnnyZElLS5OysrJq92lhYaF30VtEpFevXgJArl27VmPe69evy6hRowSAvP3224/chyErV64UADrf/q3pfDys8kJs5YcFlWJjYwWA9iK9qXkrJ7YYep/o0aMHL8RSo6gcw/z9/QWAuLm5SXR0tGzdulWRD0m7S3f5k/yp0ftVyq+//iobN26UsLAwsbKy0t4d9h//+Idcv35d6XikgMoxJzc3t9Y2VT+wrWlM6dWrV40T34wZ30Qe/Y5vhlTeseHGjRsiYh71SnVqe21Ys1BLc/PmTe0dzq2trXXGMGP+n2rq4iROrMRKbsktRfqvvMN8dHS0zoR5c7ujL9VNQ/2tb8qYYoihcUrE+IlvhYWF4u7uLpaWlnLx4kVZvXq1zjE+ysS3h8e+mTNnGqxnatvPw19aHTx4sACQe/fu6WwPDAwUJycnvZx1nfj2qP3yegtrl5YqOztbOx46OjqKhYWF+Pv7y4IFC+TkyZMcD4mIiMisWYCIiEhB3377LaZNm4bHHnsMTz75JP75z39i2LBh+Ne//oWbN28iLi4O0dHRcHR0VDoqEUpLS1FQUABbW1s4OTnpPe7p6QkAyM7OBgCsX78ecXFxuHz5MoKDg+Hs7IyhQ4di9+7devusqKiAWq2GSqXS+fnhhx8AABcvXqwxm4+PD7Zs2YKOHTti5cqVOHnyZJ37KCgowPz589GjRw+4urpq28XGxgIA7t+/b9T5qI5ardb5t4XF7yVpRUWFyXlLS0tRWFgIW1tbg+8Tbdq0MToX0aPo3r07Fi5ciJMnTyI9PR1z5sxBZmYmXn31VXh5eWHEiBHYsmULysrKGiXPKIzCDuxAGRqnPyX8+uuvePfdd9GrVy+0b98eb7/9NhwdHfHpp58iLy8PR48exYwZM+Dj46N0VFKQg4OD0W1rG1NcXV1rfH5t41t9cHFxMbi9cry7deuWWdcrVRl6bVizUEvUpk0bTJgwARqNBtnZ2di6dSu8vb0xb948PP7443juueewdOlSZGZmKh21QWzFVryEl+ABj0br8/Lly3j33XcREBAAT09PvPHGGygtLcV7772HzMxMnDt3DsuWLUNgYCBUKlWj5SLlmDJ2mjKmGDtOmcrR0RExMTEoLy/HggULsGrVKsybN69O+3rYw2OftbU1ANPrGWdnZ51/W1hYwNLSEvb29jrbLS0t67VWaoh+eb2FtUtL4OnpiQkTJmDXrl3Izs7GF198gaeffhobN25E79694efnh7feegtHjhxROioRERGRHk58IyIiRcXGxuLAgQN48803cebMGfz8889YtWoVgoKCYGlpqXQ8Ih02NjZQq9UoKSlBYWGh3uM3b94EAHh5eQEAVCoVxo8fj4MHDyI/Px8JCQkQEURFRWH16tXafbq4uKBVq1b47bffIL/fkVfvZ+DAgbXms7W1xZIlSyAimDt3rk5uU/oIDw/HokWLMHnyZGRkZKCiogIigjVr1gAARMSo81FXpuS1sbGBk5MTSkpKUFRUpLevvLy8estFZKxOnTrh7bffxrFjx5CZmYk1a9YgLy8Pr776KvLz8xslwxiMQS5ykYKURulPCTt37sSSJUvw3HPPYf/+/bh16xa2b9+OUaNG6X3gRWSM2saUW7du1Us/jzKJ4vbt29pxuKrKbG3atDH7eqUmrFmopXN1dcXYsWMRHx+PnJwcaDQaPPXUU5g/fz4SExOVjlfvMpGJwziMV/BKo/b76aefYtmyZfD394dGo0Fubi727NmDyZMn47HHHmvULGQeTBk7TRlTjB2n6uJPf/oT1Go1tm3bhp49e6J379513pc5srCwwIMHD/S2N9bfUw/j9RbWLi2Jg4MDIiMj8fHHHyMzMxPfffcdJkyYgKSkJMyZM0fpeERERER6OPGNiIgU9/LLL2PevHno0aOH0lGIajVixAgAwN69e3W2l5aWIiUlBXZ2dggNDQXw+11ZLly4AACwsrLC4MGDkZCQAJVKpfP8qKgolJWV4dixY3r9LV++HI8//rjRd4mKjo7GM888g5SUFCQnJ5vcR3l5OY4dOwYvLy9Mnz4dHh4e2g/oi4uLqz0f+/bt03vsmWeewcyZM43K/TBTzsmwYcMAAPv379dpl5ubi/T09Dr1T1RfvLy8MGXKFCxYsKBR++2IjngOz2EbtjVqv43N29sbH330EUJDQ7V3oyB6FNWNKdnZ2cjIyKiXPuzt7XU+yO3cuTM2bdpk1HNLSkpw4sQJnW3//ve/cePGDfTs2RPe3t4AzL9eqQlrFqLf2dra4qWXXsLmzZv17uDTXGzFVqihxjAMa/S+fX19sWHDBrz00kuws7Nr9P7JfLRq1QoXLlwwaew0ZkwxdZwylVqtxqxZs6BWq+vtbm/mxNvbW+9Ol9nZ2bh69apCiXi9pSrWLi2HhYUFAgIC8O677yIqKkrpOEREREQGceIbERERkQmWLl0KPz8/xMTEICkpCYWFhcjIyMCYMWOQlZWFtWvXapdBAYBp06bhzJkzKC0txa1bt7BixQqICAYNGqSzz44dO+K1117DV199hYKCAuTl5WHjxo149913sWrVKrRq1cqofCqVCosXLwYAzJ07V/ttYWP7sLS0xIABA5CdnY2VK1ciNzcXxcXFOHToEDZs2FDt+Zg5cyb27t2LwsJCXL9+HW+++SaysrLqfCHWlHOyZMkSuLm5ISYmBsnJySgqKsL58+cxbtw4LpNMLdof8Ufsxm7cR92WUCJqiQyNKWfPntUuW1wfevXqhYyMDFy7dg1paWm4fPkygoKCjHquWq3GO++8g7S0NNy7dw8nT57EuHHjYG1tjbVr12rbmXu9UhPWLEQtx6f4FGMwBjawUToKkUljpzFjiqnjVF3Mnz8f+fn56Nu3b73sz5wMGTIEN27cwAcffICioiJcunQJM2bMUHR5TV5vYe1CRERERGZKiIiIFBQQECCxsbFKx6AWzMHBQQDo/HTu3LnG5+Tm5kpMTIz4+fmJlZWVqNVqCQ0NlZSUFJ12p0+flqlTp0rXrl3F3t5e3Nzc5Pnnn5fNmzdLRUWFTtvbt2/LrFmzpEOHDmJlZSUeHh4yZMgQSU5OrjXvqFGj9DIGBgZqH+/Xr59JfeTk5MjUqVOlXbt2YmVlJZ6enjJx4kSZO3eudp/+/v7Vng9vb28ZPXq0ZGRkiIhIWlqaXua//OUvIiJ621966SWTz4mISHp6ukRGRoqzs7PY2dlJQECAJCUlSXBwsHbfr7/+eo2vK1FDSklJEQCSk5PTaH1mS7a0klayQ3Y0Wp+Nafny5eLr66t0DDIzhsachy997N69W+/xsWPHah+vOqbY29tL37595dtvv5UBAwaIvb19jX0ZM75duHBBgoKCxMHBQdq1ayfr16836th69uwpPj4+cv78eQkNDRUnJyexs7OT/v37y9GjR/XaK1mvGGLMa2NqP6xZqKVwd3eXDz/8UOkY9eq4HBcI5IScaPS+Fy5cKF27dm30fqlxGfrbubqfn376SUSMHzsNtX14TBExfpxauXJltePPw8cRGhpa43EbOr7333+/2vrH1LHP1P2cOHFCb/vSpUvlyJEjetsXLFigPY78/HyZNGmSeHt7i52dnQQGBsqJEyfE399f237OnDn12i+vt7B2oZrNnDlT+vTpo3QMIiIiIj0qkf/7WgoREZECnn32WQwYMAArVqxQOgoREVGD+eabbxAcHIycnBy0bt260fp9ES9CBRX2Ym/tjZuYFStW4KOPPsIvv/yidBRqIbp06YLi4mL8+uuvivT/9NNPIzc3F9evX1ekfyJSTuvWrbFo0SK88cYbSkepN2/iTXyLb3EO5xq977/97W/YuXMnzp8/3+h9ExERNVWzZs3C8ePHkZqaqnQUIiIiIh1c6pSIiIiIiKiZmoiJ2I/9uIZrSkchahKys7Ph5uaG3377TWf7lStXcOnSJZ2lP4mIqG4e4AF2YRdewStKRyEiIiIiIiKiJo4T34iIiIiIiJqpSETCDW74FJ8qHYWoybhz5w6mTp2Ka9eu4f79+/juu+8watQoODs7469//avS8YiImrxEJOIO7mAMxigdhYiIiIiIiIiaOE58IyIiIiIiaqasYY0xGIP/wf9AIErHITJ7Xl5eOHjwIPLz8/HCCy/A1dUVw4cPxxNPPIHvvvsOHTp0aPRMq1atgkqlwo8//ojMzEyoVCrMmzev0XMQEdWXrdiKwRiMtmirdBQiIiIiIiIiauJaKR2AiIiIiIiIGs4kTMI6rMMRHMELeEHpOERmLzg4GMHBwUrH0Jo9ezZmz56tdAwionpxC7fwNb7GFmxROgoRERERERERNQO84xsREREREVEz1gM90Au98Ak+UToKERERtXDbsA12sEMkIpWOQkRERERERETNACe+ERERUZNRudSXSqVC27ZNd1kcR0dH7XFU/bGwsICHhwciIyNx4sQJpWNqVZdXpVLB1tYWTz31FNavXw8R81lGMSEhQSdnSUlJg/e5Y8cOnfNCZE5exauIRzzu4q7SUYhq1RzG+6KiIoPj5oABA5SOZpTTp09jypQp6Ny5MxwdHeHo6IhOnTphyJAhWLZsGU6dOtXg435NvwesTYzD2oTM0VZsRTSiYQ97paOQmWkO4z9geIxatWqV0rEMqu6cG6pj0tLSat1fbGysznMWL17ckPGbDdY1xmFdQ0RERETV4cQ3IiIiajJmz54NEUHPnj2VjvJIioqKcOrUKQBAREQERAQigjt37mDTpk1IS0tDv379cPDgQYWT/q66vKWlpTh+/DicnZ3x1ltvYc6cOQon/Y/IyEiICCIiIhqtz9GjR0NEzGp5PKJK4zAOFajALuxSOgpRrZrDeO/o6KgdLz09PWFpaQkRweHDh03eV1FREZ544gmEhYXVf9CHVFRUYM6cOejduzdsbGywc+dO5OTk4Pr16/jss8/Qrl07/PnPf0avXr3w/fffN2iWmn4PWJsYh7UJmZuzOIvTOI1X8IrSUcgMNYfxHzA8RpnrkuXVnfPKOqbyOABg0aJFNe7r9u3b2LBhAwBg7NixEBHMmzcPQP3VMo1ZEzUm1jXGYV1DRERERNXhxDciIiIiM6FWqzFixAisXr0av/32G2JiYpSOVCNra2s8/fTT2L59OywsLLBmzRrk5eUpHYuIDHCBCyIQweVOiZogEUFFRQUqKioeeV+Ojo4IDAys9vG//vWvWLFiBT744AO8//77ePrpp2FnZwcXFxcEBATgf/7nf8zqQ9eHsTYhMm+f4BP4wheBqP59iIjMi52dHdq3b4+vvvoKJ0+erLbdmjVr0K5dO4OP1VctU581UVPAuoaIiIiIyDic+EZERERkZgYOHAgAOHfuHPLz8xVOU7t27drB29sbZWVl+PHHH5WOQ0TVeBWvIhWp+Ak/KR2FiEzg5OSES5cuYd++fQ3az08//YRly5bB398f06ZNq7bd3LlzzX55KdYmROanDGXYhm14Ba9ABZXScYjISBYWFpg7dy4AVLt0aX5+Pj766KNqJ8fXVy3TWDWRuWFdQ0RERERUM058IyIiIjIzIqL9b5WqaXwoVJnZ3D8IJ2rJQhCC9miPLdiidBQiMkObNm1CRUUFoqOja2zn4uKC4uJi9O7du5GS1Q1rEyLzsg/7cBM3MR7jlY5CRCZ69dVX4ePjg8TERJw5c0bv8XXr1uHFF19Ex44dFUjXMrCuISIiIiKqHie+ERERkdm4ffs2Zs2ahY4dO8LGxgZt27ZFSEgItmzZguLi4hqfW1ZWhp07d2Lw4MHw8vKCnZ0devTogbVr1+otg1FaWor58+ejS5cusLe3h5ubG8LDw5GYmIjy8nKT29W3w4cPAwC6d+8OtVoNQPfcWFtbw9XVFcOGDcOhQ4fqdGwAkJOTg+nTp8PX1xfW1tbw8PBAVFQUTp8+bVLeq1evIisrC87OzujevXud+jDl9Xv4fBjzu5KdnY1Ro0bBxcUF7u7uCAsLw6VLl/TamXJOLly4gMjISKjVajg4OCAoKAhHjx416dwRNSYLWOAVvIKt2Irf8JvScagF43j/O2PG9oSEBKhUKu1PSUmJwe1XrlypcZxbtWoVVCoV7t27h2PHjmmf16pVK22bf/3rXwCAnj17NtjxAKaP+XXB2oS1CZmfT/AJBmIgOoITY1oqjv/VM3YMfbhtdeexvsdaGxsbxMbGQkTw97//XeexoqIivP/++3jnnXcMPre+ahlj9/Prr79i1KhRcHJygru7O8aPH487d+7gypUrCA8Ph5OTE7y9vTF58mQUFhZq97948WLtPqouC79//37t9tatW1ebp679GoN1DesaIiIiIqqFEBERKSggIEBiY2OVjkFmICsrS/z8/MTLy0s0Go3cvXtXsrOzZdGiRQJA1qxZo23bs2dP8fHx0Xm+RqMRALJkyRLJy8uTnJwcWbdunVhYWMjs2bN12k6aNEnUarUcOHBA7t+/L9nZ2TJ79mwBIIcOHTK5nYjIwIEDxc3NTdLS0ow63lOnTgkAiYiI0G4rKCiQL7/8Utq0aSNWVlaSnJysc248PT1Fo9FIQUGBpKenS1RUlKhUKtm8ebPJmW/cuCHt27cXT09P2bt3rxQWFsrZs2elf//+YmtrK6mpqbXmffDggZw6dUr69esn1tbWEhcXp/McU/ow5fUz5XclIiJCmzs1NVWKiookJSVFnJ2dJSAgoM55L168KC4uLuLj4yMHDhyQwsJCOXPmjAwZMkR8fX3Fxsam1t8BallSUlIEgOTk5Cia47JcFguxkARJUDRHfVi+fLn4+voqHYNM1NLGexERT09PsbS0NHgejBnbRf4znhUXFxvcXnWcS05OFjs7O71xTkTEwcFB+vXrZzCnt7e3AJD//d//NfrY6nI8pryGIoZ/D0RYm7A2aVnc3d3lww8/VDpGnd2Um2IlVvKpfKp0FBERWbhwoXTt2lXpGC1KSxv/DY1RtZ0bY8ZQY89jfY61Dg4OIiJy//598fT0FAsLCzl//ry2zbJly2TkyJEiInLkyBEBIGPHjtXbV33VMrXtJyoqSk6ePClFRUUSFxcnAGTYsGESEREhp06dksLCQtmwYYMAkJkzZ+rtv7payd/fX9zd3avN86j9sq5hXdMUzJw5U/r06aN0DCIiIiI9nPhGRESK4sQ3qjRx4kQBIDt37tR7bOjQoUZdCB8wYIDec8eNGydWVlZSUFCg3ebn5yd9+/bVa9upUyedC9zGthMR6d+/v7i6uupNGKtO5UXNqj8qlUrc3d1l+PDh8t1332nbVp6b7du36+yjpKREHnvsMbGzs5Ps7GyTMr/yyisCQD777DOddllZWWJjYyP+/v615q38GTFihPz88896fZrShymvnym/K5UXYTUajU67MWPG6E1CMiVvdHS0AJDPP/9cp21mZqbY2NjwIizpMZeJbyIiQ2SIDJWhSsd4ZJz41jS1tPFexPDEN1PGdpHaP+R9eJx7+eWXDb7n1DTxzcvLq8aJbz179tQZ/6t+MGvK8ZjyGlb2W9PEN9Ymv2Nt0rw19Ylvq2SVqEUt9+Se0lFEhBPflNDSxn9TJr6ZMoYaex7rc6ytnPgm8nv9DUDGjRsnIiL37t0TT09P+fHHH0Xk0Sa+GVvL1LafvXv36mzv3r27AJBvv/1WZ7ufn5907txZL2ddJ749ar+sa1jXNAWc+EZERETmihPfiIhIUZz4RpXUarUAkLt379batrqLsoasXLlSAOhcoH7jjTcEgEyePFnS0tKkrKzM4HONbVcXplwIr+ncjB8/XgDI1q1bTcqsVqvFwsJC74K3iEivXr0EgFy7dq3GvNevX5dRo0YJAHn77bcfuQ9DDL1+pvyuVF6ErTp5QEQkNjZWAGgv0Jua18nJSQBIYWGhXtsePXrwIizpMaeJb7tlt6hEJRmSoXSUR8KJb01TSxvvRQxPfDNlbBep/UPeh8e5mTNn6o1zIjVPfPP39zf4we3DTpw4oVcTmHo8hhh6DUVMu+MbaxPWJs1VU5/49pQ8JVNlqtIxtDjxrfG1tPG/of7eN+U8GlKXsbbqxLfCwkJxd3cXS0tLuXjxoqxevVrnGB9l4puxtUxt+7l586bO9sGDBwsAuXdPd+JtYGCgODk56eWs68S3R+2XdQ3rmqaAE9+IiIjIXFmAiIiISGGlpaUoKCiAra0tnJyc6rSPgoICzJ8/Hz169ICrqytUKhVUKhViY2MBAPfv39e2Xb9+PeLi4nD58mUEBwfD2dkZQ4cOxe7du3X2aWy7hlTbufH09AQAZGdnG525cp8VFRVQq9Xac1X588MPPwAALl68WGM2Hx8fbNmyBR07dsTKlStx8uTJOvdh7OtX198VtVqt828Li9/L4IqKCpPzlpaWorCwELa2tnB0dNTrq02bNkbnIlJCOMLxOB7Hx/hY6SjUwnC8/52pY7sxHh7nrK2tAfxnnDPGCy+8AADaMc9Yph6PKa+hqVibsDYh8/O/+F+cwRm8ileVjkIK4fhfPVPGUFPOY0ONtY6OjoiJiUF5eTkWLFiAVatWYd68eXXa18Pqo5YBAGdnZ51/W1hYwNLSEvb29jrbLS0tTd53Y/fLuoZ1DREREREZhxPfiIiISHE2NjZQq9UoKSlBYWFhnfYRHh6ORYsWYfLkycjIyEBFRQVEBGvWrAEAiIi2rUqlwvjx43Hw4EHk5+cjISEBIoKoqCisXr3a5HYNqbZzc/PmTQCAl5eX0ZltbGzg4uKCVq1a4bfffoP8fhdgvZ+BAwfWms/W1hZLliyBiGDu3Lk6uU3pw9jXrz5+VwwxJa+NjQ2cnJxQUlKCoqIivX3l5eXVWy6ihmAJS7yKV/H/8P9QghKl41ALwvH+d6aO7fVJpVJV+9jkyZNhYWGBHTt26JzH2ph6PKa8hnXB2oS1CZmXT/AJuqM7nsNzSkchhXD8r54pY6gp57Ehx9o//elPUKvV2LZtG3r27InevXvXeV/myMLCAg8ePNDbnp+fr0Aa1jWsa4iIiIjIGJz4RkRERGZhxIgRAIB9+/bpPfbMM89g5syZ1T63vLwcx44dg5eXF6ZPnw4PDw/tB7vFxcV67V1cXHDhwgUAgJWVFQYPHoyEhASoVCrs3bvX5HYNrfLcPNxnaWkpUlJSYGdnh9DQUJMyR0VFoaysDMeOHdPrb/ny5Xj88cdRVlZmVL7o6Gg888wzSElJQXJyssl9mPr6PcrvSk1MOSfDhg0DAOzfv1+nXW5uLtLT0+vUP1FjmoIpKEABvsAXSkehFobj/e9MGdvrk729vc6HuZ07d8amTZsAAF27dsXcuXNx7tw5rFixotp9lJeX620z9nhMfQ3rirXJf7A2ISUVoxg7sZN3eyOO/wa0atUKFy5cMKkmMOY8NvRYq1arMWvWLKjV6nq725s58fb2RmZmps627OxsXL16VaFErGuqYl1DRERERIZw4hsRERGZhaVLl8LPzw8zZ87E3r17UVhYiOvXr+PNN99EVlZWjRfWLC0tMWDAAGRnZ2PlypXIzc1FcXExDh06hA0bNhh8zrRp03DmzBmUlpbi1q1bWLFiBUQEgwYNqlO7QYMGwd3dHcePH3/0k/GQynMTExODpKQkFBYWIiMjA2PGjEFWVhbWrl2rXQLF2MxLly5Fx44d8dprr+Grr75CQUEB8vLysHHjRrz77rtYtWoVWrVqZVQ+lUqFxYsXAwDmzp2r/aawsX2Y+vo9yu9KbefZ2HOyZMkSuLm5ISYmBsnJySgqKsL58+cxbtw4g0txEJkbb3gjHOHYAMPvkUQNheO97nkwdmyvL7169UJGRgauXbuGtLQ0XL58GUFBQdrHFy1ahNjYWPz5z3/G66+/ju+//x73799HcXEx/v3vf2PJkiWIiIiApaWlzh1ejD2euryGdcHahLUJmYcv8AWKUISxGKt0FFIYx//qmVITGHMeG2OsnT9/PvLz89G3b9962Z85GTJkCG7cuIEPPvgARUVFuHTpEmbMmKHo8pqsa1jXEBEREVEthIiISEEBAQESGxurdAwyE7m5uRITEyN+fn5iZWUl3t7eMnr0aMnIyBARkZUrVwoAnZ+//OUvIiKSk5MjU6dOlXbt2omVlZV4enrKxIkTZe7cudq2/v7+IiJy+vRpmTp1qnTt2lXs7e3Fzc1Nnn/+edm8ebNUVFRo8xjbTkQkKChIXF1dJTU1tdbjdHBw0DuOzp07m3Ru1Gq1hIaGSkpKik47UzLfvn1bZs2aJR06dBArKyvx8PCQIUOGSHJycq15R40apZcxMDBQ+3i/fv1M6sOU18/Q+Xj4dyUtLa3a35WHt7/00ksmnxMRkfT0dImMjBRnZ2exs7OTgIAASUpKkuDgYO2+X3/99RpfV2o5UlJSBIDk5OQoHUUrWZIFAjkjZ5SOUifLly8XX19fpWNQHbSU8b5SmzZtxMrKqtbzYGhs3717t965GDt2bJ3HuQsXLkhQUJA4ODhIu3btZP369QYzf//99/Laa69Jx44dxc7OTqytrcXLy0sGDRokixcvlsuXL9fpeESMfw1r+j1gbcLapKVxd3eXDz/8UOkYJhskgyRSIpWOoWfhwoXStWtXpWO0OC1l/Dc0RlX389NPPxk8N9WNocacRyk2+/0AACAASURBVFPOlyljbWhoaI3Hbej43n///XqrZUzdz4kTJ/S2L126VI4cOaK3fcGCBdrjyM/Pl0mTJom3t7fY2dlJYGCgnDhxQvz9/bXt58yZU6/9sq5hXdNUzJw5U/r06aN0DCIiIiI9KpH/+3oIERGRAp599lkMGDCgxuWUiIiImrpvvvkGwcHByMnJQevWrZWOAwAQCLqgC0IQgvVYr3Qck61YsQIfffQRfvnlF6WjENXIyckJtra2yMnJUToKETVRrVu3xqJFi/DGG28oHcVoV3AFHdERu7EbwzFc6Tg6/va3v2Hnzp04f/680lGIiIiajFmzZuH48eNITU1VOgoRERGRDi51SkRERERE1AKpoMJUTMWn+BR3cVfpOETNwrRp0/D2229r/33z5k0UFRXhqaeeUjAVEVHj24It8IAHhmGY0lGIiIiIiIiIqBnjxDciIiIiIqIW6jW8hnKUYzu2Kx2FqNnYuXMnMjIycPv2bbzzzjsAfp8QR0TUUggEn+JTTMAEWMFK6ThERERERERE1Iy1UjoAERERERERKcMFLohGND7Eh5iKqUrHIWryFixYAADapY07deqETz75BNHR0QonIyJqPClIwWVcxkRMVDoKERERERERETVznPhGRERERETUgr2BN/A8nsdxHMfzeF7pOERNmre3NzZs2KB0DCIiRX2CT/A8nkc3dFM6ChERERERERE1c1zqlIiIiIiIqAV7Ds+hF3rhA3ygdBQiIiJq4gpQgAQk4FW8qnQUIiIiIiIiImoBOPGNiIiIiB7Jjh07oFKpoFKpYGtrq3QcIqqD6ZiOXdiFTGQqHYWIWhjWEUTNyzZsAwCMxmiFkxARsc4gIiIiImoJOPGNiIiIiB7J6NGjISIIDg7We6yoqAhPPPEEwsLCTNpnXZ9HRHUzGqPhDndsxEaloxBRC8M6gqh5+Rgf42W8DGc4Kx2FiIh1BhERERFRC8CJb0RERNRiOTo6IjAwsNn2Zw5EBBUVFaioqNB7rKbzUdPziKj+2cAGUzAFG7ABJShROg5Rk8A6ouGxjiBqWr7H9/gBP2AKpigdhajJY53R8FhnEBERERE1D62UDkBEREREzZeTkxMuXbrUaM8jorr7b/w3VmAFtmEbXsNrSschImIdQdTEbMZmdEEX9EVfpaMQEdWKdQYRERERUfPAO74RERERERER2qANohGNNVgDgSgdh4iIiJqQe7iH7diOqZgKFVRKxyEiIiIiIiKiFoIT34iIiKhZKS0txfz589GlSxfY29vDzc0N4eHhSExMRHl5OQBg1apVUKlUuHfvHo4dOwaVSgWVSoVWrf5zM9yysjLs3LkTgwcPhpeXF+zs7NCjRw+sXbtWZzmLhIQE7fNVKhXS09MxcuRIuLu7a7fNnTu31v6Mdfv2bcyaNQsdO3aEjY0N2rZti5CQEGzZsgXFxcUG21lbW8PV1RXDhg3DoUOHqs1+5coVjBo1Ci4uLnB3d0dYWJjBbzFfuHABkZGRUKvVcHBwQFBQEI4eParX7uH9l5SUGHX+q3teYxwbUUsXgxicxVl8i2+VjkKkCNYR+u1YR7COIDLGdmxHKUoxFmOVjkJktlhn6LdjncE6g4iIiIjokQkREZGCAgICJDY2VukY1IxMmjRJ1Gq1HDhwQO7fvy/Z2dkye/ZsASCHDh3Saevg4CD9+vUzuB+NRiMAZMmSJZKXlyc5OTmybt06sbCwkNmzZ+u1j4iIEADSv39/OXTokNy7d0+OHz8ulpaWkpOTU2t/xsjKyhI/Pz/x8vISjUYjd+/elezsbFm0aJEAkDVr1ui08/T0FI1GIwUFBZKeni5RUVGiUqlk8+bNBrNHRERIamqqFBUVSXJystjZ2UlAQIBO24sXL4qLi4v4+PjIgQMHpLCwUM6cOSNDhgwRX19fsbGxqfbcFBcX62yv7XwYel5DHpuIyMCBA8XNzU3S0tKqzUVUFykpKQJA+35gzvpJP4mUSKVj1Gr58uXi6+urdAxqZlhHsI6o67GJsI6ghuPu7i4ffvih0jFq9Kw8K2NkjNIxjLJw4ULp2rWr0jGoBWKdwTqjrscmwjqDlDdz5kzp06eP0jGIiIiI9HDiGxERKYoT36i++fn5Sd++ffW2d+rUyeQLyQMGDNDbPm7cOLGyspKCggKd7ZUXLPft21dttke9kDxx4kQBIDt37tR7bOjQodoLyZXttm/frtOmpKREHnvsMbGzs5Ps7Gy97BqNRqf9yy+/rDdRJzo6WgDI559/rtM2MzNTbGxsGvxCckMem4hI//79xdXVVVJTU6vNRVQXTWni2y7ZJRZiIT/Lz0pHqREnvlFDYB3BOoJ1BJkjc5/49qP8KBDIITmkdBSjcOIbKYV1BusM1hnUlHHiGxEREZkrLnVKRETUjJ09e1Zn+QSVSoW33nqr2W4HgKFDhyI1NRVTpkzB8ePHtcuFpKenY8CAAUafu7CwMJ2lKCr17NkTv/32G86dO2fwec8++6zpL5SRdu/eDQAYNmyY3mNfffUVYmJidNq99NJLOm1sbGwQHByM4uJifP3113r7CAgI0Pl3u3btAAA3btzQbtu/fz8AIDQ0VKftY489hk6dOpl0PHXRkMcGAIcPH0ZeXh769OkDoGX+P0QUhSi0R3usx3qlo5DCzO09inXEo2EdwTqCdQQ1lE3YhI7oiP7or3QUakLM7T2MdcajYZ3BOoN1BhEREREppZXSAYiIiKjhPPnkkxARg4811+3r169Hnz59sHXrVgQHBwMAgoKCMHXqVIwYMcLgcwwpKCjAe++9h927d+P69evIz8/Xefz+/fsGn+fg4GB0H6YoLS1FQUEBbG1t4eTkVOd2np6eAIDs7Gy9x9Rqtc6/ra2tAQAVFRXafRcWFsLW1haOjo56z2/Tpg0yMjKMPygTNeSxVacl/j9EZAlLTMM0LMZiLMRCOMNZ6UikkJb4Hsg6gnUE64hH204tTzGKsQ3b8Gf8GSqolI5DTUhLfI9kncE6g3XGo20nIiIiIjKEd3wjIiKiZkWlUmH8+PE4ePAg8vPzkZCQABFBVFQUVq9erde2OuHh4Vi0aBEmT56MjIwMVFRUQESwZs0aAHW7CFdTf7WxsbGBWq1GSUkJCgsL69zu5s2bAAAvL686ZXByckJJSQmKior0Hs/LyzNpf6aej4Y8NiLSNRmTUYEKbMVWpaMQNSrWEawjWEcQmWYXduEe7uEVvKJ0FCKzxzqDdQbrDCIiIiKi+seJb0RERNSsuLi44MKFCwAAKysrDB48GAkJCVCpVNi7d69OW3t7ezx48ED7786dO2PTpk0oLy/HsWPH4OXlhenTp8PDw0N70bO4uLjO2arrz1iV3wDft2+f3mPPPPMMZs6cqdPu4eMtLS1FSkoK7Ozs9Jb+MFblsiWVS4hUys3NRXp6ukn7qsv5aMhjI6L/cIUrxmM81mEdKlDznQaImhPWEawjWEcQmWYzNiMCEWiDNkpHITJ7rDNYZ7DOICIiIiKqf5z4RkRERM3OtGnTcObMGZSWluLWrVtYsWIFRASDBg3SaderVy9kZGTg2rVrSEtLw+XLlxEUFARLS0sMGDAA2dnZWLlyJXJzc1FcXIxDhw5hw4YNdc5VXX/GWrp0Kfz8/DBz5kzs3bsXhYWFuH79Ot58801kZWVpLyRXtouJiUFSUhIKCwuRkZGBMWPGICsrC2vXrtUus2GqJUuWwM3NDTExMUhOTkZRURHOnz+PcePGGVxOpCZ1OR8NeWwAMGjQILi7u+P48eN13gdRc/En/AmXcAl7sbf2xkTNCOsI1hF1xTqCWpoLuIBUpGIyJisdhajJYJ3BOqOuWGcQEREREVVDiIiIFBQQECCxsbFKx6Bm5PTp0zJ16lTp2rWr2Nvbi5ubmzz//POyefNmqaio0Gl74cIFCQoKEgcHB2nXrp2sX79e+1hOTo5MnTpV2rVrJ1ZWVuLp6SkTJ06UuXPnCgABIP7+/pKWlqb9d9UfQ2rqz1i5ubkSExMjfn5+YmVlJd7e3jJ69GjJyMiosZ1arZbQ0FBJSUnRtjGU/S9/+YuIiN72l156Sfu89PR0iYyMFGdnZ7Gzs5OAgABJSkqS4OBgbfvXX39ddu/erbefsWPH1no+anteQx5bUFCQuLq6SmpqqsmvDVFNUlJSBIDk5OQoHcUkL8qLEiRBSscwaPny5eLr66t0DGpmWEcYbsc6gnUEKcvd3V0+/PBDpWPoiZEY8RM/KZdypaOYZOHChdK1a1elY1ALxDrDcDvWGawzqGmYOXOm9OnTR+kYRERERHpUIvL/2bv3uKrqfP/jLxBFRfOKWt4QTRus0bS80knFBJm9uKhbz6mT1VipjRPV6FQ2NthkmVkTNWlljjN2moxlCuwt4nUsSZ3MMSs0vOEVryFe8JLA/v1xjvsHpuUF+G7g/ZxHj8c5BPrCGWSx9md9P56fHo0TEREpPz169KBfv35MmzbNdIqIiEi5WblyJRERERw5coSmTZuazrliq1hFf/qzhjX0prfpnFKmTZvGzJkzycnJMZ0iIiJSrpo2bcqf/vQnxo4dazrF6wd+oBWteIInmMhE0zlXZfLkyXz88cds3rzZdIqIiEil8dRTT7Fu3TrWrFljOkVERESkFK06FRERERERkUvqRz960pPXeM10ioiIiPiQ+cznGMd4kAdNp4iIiIiIiIhINabBNxEREREREbmsp3iKhSxkG9tMp4iIiIiPmMUsHDi4iZtMp4iIiIiIiIhINabBNxERERHD/Pz8fvafxMRE05kiUk0NZSihhPJn/mw6RUQuQdcRIlLRtrCFT/mUsfjO6lURKR+6zhAREREREV8XYDpAREREpLrzeDymE0RELqsGNXiCJxjPeJ7neVrQwnSSiJSg6wgRqWhv8zahhDKQgaZTRKSc6TpDRERERER8nU58ExERERERkZ/0EA9Rj3rMZKbpFBERETHoFKf4gA94jMfw161lERERERERETFMdydEREREfFTXrl2vaK3IhX9efPFF08kiUkXVpS6P8Rh/4S8UUGA6R6Ta2b59O35+fsybN++qPm769One64RWrVqVU13ZSU9Pp2PHjgQEXH5BwbX+WYhI2fiADzjPeR7kQdMpImKQ7leIiIiIiIiv0OCbiIiIiA+zbRuPx+P9Z/To0QAsXry41NtHjBhhuFREqrpxjOMMZ/gbfzOdIiJXaPz48Xg8Hrp06WI65Sft2LGDmJgYnn32WQ4dOmQ6R0R+wju8w3/xXzSmsekUETFM9ytERERERMQXaPBNREREREREflYwwTzAA7zGaxRSaDpHRKqQSZMm0adPHzZs2ED9+vVN54jIZaxmNV/zNWMZazpFRERERERERASAy++OEBERERGjvvrqqyt+X637EpGKMIEJzGIWC1mIE6fpHBGpImbPnk2dOnVMZ4jIz5jJTHrQgzu4w3SKiBim+xUiIiIiIuIrdOKbiIiIiIiIXJFQQokllmlMM50iIlWIht5EfN8RjrCABTrtTURERERERER8igbfRERERKqIlJQU/Pz8vP9kZ2czfPhwmjRp4n3bE0884f2/w8PDvR+bkZHhfXvTpk1/9GsfOXKExx9/nJCQEGrVqkVwcDBDhgy5qqe8RaRqmMAEvuRLVrHKdIpItdGhQwc8Hg//+Z//6X3buXPneP7557nllluoW7cujRs3xrIs0tLSKCoquqJf92q+v1/J+06fPt17PdGqVSvWr19PREQE9evXp27duvTv35/PP/+8zP8sRKT8vcd71KUuwxluOkVEKiHdrxARERERkfKiwTcRERGRKiIuLg6Px0NsbCwAo0eP5rHHHmPv3r2sW7eOGjVq8Ic//AGPx0NQUFCpj42KisLj8dC9e/cf/boHDhzgzjvvJDk5mRkzZpCXl8eqVavIy8ujd+/erF27tkI+PxHxDb3oxX/wH0xlqukUkWpt3LhxvPnmm7z11lt8//33bNmyhVtuuYXY2FhWr179sx9/Nd/fr/R9x48fj8fjoUuXLuTn55OQkMCLL77IwYMH+eyzz8jLy2PAgAF8+umn5fbnIiJlr4gi3ud9RjGKutQ1nSMilZDuV4iIiIiISHnR4JuIiBi3bNkyPvzwQ44dO2Y6RaRKefrpp+nXrx9169alZ8+eFBYWXvLp6J/z7LPPsnv3bl5//XWio6OpV68enTt3Zt68eXg8Hn7729+WQ71I1XD+/HmWLVvGu+++azqlTE1kIktYwpd8abTjyJEjTJs2ja1btxrtEDFhxYoVdO7cmXvuuYc6derQvHlzXn31VTp27HhFH38139+v5VqgoKCAGTNm0Lt3b4KCgrjjjjv4n//5H3744QcSEhLK7M9BpCrbvHkzL730EidPnjTa4cbNbnbzCI8Y7ShLubm5vPLKK2zevNl0iki1pPsVIpXH4cOHmTNnDsuXLzedIiIiInJJGnwTERGjnnjiCYKDg3nooYdo3rw599xzD2+//TZ79+41nSZS6fXo0aNMfp2UlBT8/f1xOByl3t6iRQs6d+7Mhg0b2LdvX5n8XiJVwalTp7Btm/vuu49mzZoxaNAgsrOzef7556lfv77pvDIRSSR3cAcv87K5hshInE4n06ZNo1OnToSFhTFx4kS++OILPB6PsS6RihIVFcWaNWt49NFHWbdunXe9aXZ2Nv369fvZj7+a7+/Xci0QFBRE165dS73ttttu46abbmLTpk0cOHDgaj9lkSqvuLiYNWvW8Pvf/56OHTvSuXNnkpKSGDly5BV9XZeXmcwkkkg6cmWDtb7Osizi4+N5/fXX6dy5M+3btychIYHly5fzww8/mM4TqRZ0v0LEt23atIkpU6bQq1cvbrzxRn7zm9/Qpk0bPcAiIiIiPinAdICIiFRv9957L/feey8FBQWsXLkS27Z57rnnGDduHGFhYTidTizLuuQ6AxH5aRevB7kW586d4/jx4wA0aNDgsu+3bds2WrVqdd2/n0hldfToUdLT03G73aSnp3PmzBl69+7NM888Q1xcHJ06dTKdWOae4RmcOPmWb7mVWyv89+/SpQtz5syhqKiItWvX4na7+eSTT3j55ZcJDg4mKioKp9NJZGQktWrVqvA+kfL29ttv07t3b/7+978TEREBwF133cXo0aOJj4//yY+9mu/vwcHB13Qt0LBhw0u+X7NmzcjNzeXw4cPceOONP9kpUh2cO3eO1atX43K5mD9/Prm5ubRr1w7LspgxYwb9+vUjIMDcLdwd7GAZy1jIQmMNZa1bt27MmTOH4uJiNm7ciMvlwu1289Zbb1GnTh0GDBiAZVlYlqW/p0TKie5XiPiWs2fPkpmZicvlIiUlhT179nh/rv7d735HVFRUlXmQT0RERKoeDb6JiIhPCAoK8t5YLnnjf9asWUyePJmQkBBiYmKwLMv4jX+RqsDf3/+Spxnk5+eX+v8DAwNp2LAhp06d4syZM/raEykhJyeHtLQ03G43q1atIiAggPDwcKZMmcKIESNo0aKF6cRyNYQhdKYzr/Iqf+fvxjpq1KhBeHg44eHhTJ06laysLNxuNy6Xi9jYWOrWrUv//v1xOp3Exsb+5ItiIpWJn58f999/P/fffz/nz59n1apVTJ8+nSFDhvDaa6/x1FNPXfZjr/b7+7VcC3z//fd4PB78/PxKvf3w4cPA/w7AiVRXJR/8Sk1N5cSJE4SFhfHII4/43INfM5hBK1rxK35lOqXM+fv70717d7p3705iYiK7d+9myZIluFwuEhISGDt2LLfffjsOhwPLsujWrduP/k4TkbKn+xUiFaPkA3xLlizxXo/813/9Fw6Hg759++r7noiIiFQKWnUqIiI+JzAwkIEDB5KUlMTevXv58ssveeCBB1i2bBn33HMPLVq0YOTIkdi2TUFBgelckUrpxhtvZP/+/aXedvDgQfbs2fOj9x0yZAiFhYV8/vnnP/p3r7zyCm3atKGwsLDcWkV8SVZWFomJidxxxx2Ehobywgsv0KhRI2bPns3hw4dZtmwZCQkJVX7oDcAPPyYwgQ/5kO1sN53j1blzZ55++mkyMzPJycnh9ddfB+Dhhx+madOmhIeHk5SU9KO/A0Uqm4YNG/Ldd98BULNmTe655x5SUlLw8/Nj0aJFP/vxV/P9/VquBc6ePcv69etLve2bb74hNzeXLl266BQlqXaOHDnC3LlzsSyLxo0bEx8fz86dO3nhhRfYs2eP9xrDl4beTnKS2czmN/yGGtQwnVPu2rZty6OPPorL5SIvL48lS5bQt29f3n//fe+13+jRo3G5XJw7d850rkiVpfsVIuUnKyuLV155hfDwcJo3b86YMWM4duwYL7zwAnv37iUrK4upU6cSHh6uoTcRERGpNDT4JiIiPu3CE9iJiYls3ryZHTt2MGnSJHbu3MmIESMIDg7Gsizee+897+kRIvLzBg0aRG5uLn/5y184deoUO3bsICEh4ZKnr7z88su0b9+eX//61yxevJjjx4+Tl5fHu+++ywsvvMD06dP1ZLVUWUVFRWRmZpKQkEDr1q259dZbmTNnDt27dyctLY2DBw+SnJzMyJEjq+Xaj/u4j3a043VeN51ySSVfwD548CD/+Mc/CA0NZdKkSbRp04Y77rjDe40hUhmNGTOGr7/+mnPnznH48GGmTZuGx+NhwIABP/uxV/P9/VquBRo0aMDEiRNZu3YtBQUFfPnll/z3f/83tWrVIikpqVz+PER8zc6dO0lKSir14jLAW2+9RW5ubqlrDF/0V/7Kec4zilGmUypcnTp1vA/k7du3j2+//ZYxY8aQlZVFbGwsjRs39t6LyM3NNZ0rUqXofoVI2Tl79izLly8nISGBNm3acOutt/L6668TGhrKvHnzOHTokPcBPq0EFhERkcrKz+PxeExHiIiIXIsjR46wePFibNtm6dKlFBUV0atXL5xOJ0OGDPHZFw9ErsXf/vY3HnrooR+9/eTJk9SrVw+AdevW0bt37x+9z6Uu944fP8748eNZtGgR+fn5dO/enT//+c+MGTOGDRs2APD0008zdepUAPLy8pgyZQopKSns3buXhg0bcvvttzNhwgQGDhxYlp+qiHGnT59mxYoV2LaNy+UiPz+fsLAwLMvSuo9LmMlMnuRJdrKTm7jJdM4VOXv2LMuWLcPtdnsHGENDQ3E4HDidTvr06YO/v54TE9+2adMmZs6cyWeffcbu3bupXbs2HTt2ZNSoUYwaNQo/Pz+mT5/OhAkTSn3cc889x4svvghc3ff3q3nfrl27cvToUZYtW8aTTz7JmjVrKCwspEePHkyZMoW+ffuWen+3241lWZf8PGfNmsXDDz98vX9cIhWiuLiYjRs34nK5SE5OZsuWLTRp0oTo6GgsyyI6OpqgoCDTmVekmGI60pFIInmbt03n+JTDhw+TkZGB2+1m8eLFnD59WitRpVrT/QoR33Lhnrnb7SYjI4OTJ0/qnoaIiIhUaRp8ExGRKqGgoICVK1di2zZpaWkcP36csLAwnE4nlmX51LoYERHxPUePHiU9PR232016ejpnzpyhd+/eWJZFXFwcnTp1Mp3os85xjlBCuZd7eZVXTedctaKiItauXYvb7WbhwoVs3bqV4OBgoqKicDqdDBo0iMDAQNOZIpXKhcG3ffv2mU4RKXfnzp1j9erVuFwu5s+fT25uLu3atcOyLCzLol+/fpXytKEUUhjCEDazmVu4xXSOzzpz5gyff/45LpeLTz75hP3799O2bVsiIyNxOBy6jhARkQqRlZWF2+3G5XKxdu1aAgMD6du3Lw6Hg6FDh+o0NxEREanSNPgmIiJVzqVeeAgJCSEmJqZSv/AgIiJlKycnh7S0NNxuN6tWrSIgIIDw8HAcDgcjRoygRYsWphMrjelMJ5FEdrGLpjQ1nXNdSr5gsGbNGurUqcOAAQNwOp3ExsbSoEED04kiPk+Db1LVlXzwKjU1lRMnTlS5B6/u5m5u4AZcuEynVCqXu464cMrOTTdVjtNxRUTEt509e5bMzExcLhcLFy5k7969NGvWjMjISCzLYvDgwd4TF0VERESqOg2+iYhIlVaVVs2IiMj1y8rKwrZt3G43GzZsoHHjxkREROBwOIiPj6d+/fqmEyulAgoIIYTf8BsSSTSdU2b27NlDRkYGLpeLJUuW4PF46NmzJ06nk2HDhtGyZUvTiSI+SYNvUhVdWBtm2zZLly6lqKiIXr164XQ6GTJkCK1btzadWGY2spFudGM5y4kgwnROpXW5lagDBw7UqjkREblqWmEqIiIicmkafBMRkWpl586duFwubNtmzZo11K5dm4iICO8qu2bNmplOFBGRMnRhjaVt2yxYsIB9+/bRpk0boqKicDgcREVFUbNmTdOZVcJkJvMmb7KLXdSn6g0Q5uXlsWLFClwuFykpKRQUFHD77bfjcDgYPnw4YWFhphNFjJs+fToTJkwo9bbnnnuOF1980VCRyPWprj8/jmQkG9nI13yNH3oBvSyUXIl64Zq0efPmDBo0SCfziIjIZV18kmjt2rW9K0z1MJaIiIjI/9Lgm4iIVFvV6Yl9EZHq5PTp06xYsQLbtnG5XOTn5+sp6AqQRx4hhDCJSUxgws9/QCVWcq1McnIyBw8eJDQ0FIfDgdPppE+fPvj7+5vOFBGRq6QTw+EABwghhHd4h4d4yHROlaVBBhERuRQNSouIiIhcPQ2+iYiIAAUFBaxcuRLbtklLS+P48eOEhYXhdDqxLIvu3bubThQRkZ9w9OhR0tPTcbvdpKenc+bMGXr37u09kaVTp06mE6uF3/N7PuADdrKTOtQxnVMhiouLWbNmDW63m5SUFLKzswkODiYqKgqn08mgQYMIDAw0nSkiIpdx7tw5Vq9ejcvlYv78+eTm5tKuXTssy8KyLPr160dAQIDpzAoziUm8x3vsZje1qW06p1rQ6joRkert4tXYp06d0vcBERERQIybvgAAIABJREFUkaugwTcREZGLFBYWsm7dOmzb9r7wERISQkxMTLV84UNExFfl5OSQlpaG2+1m1apVBAQEEB4ejsPhYMSIEbRo0cJ0YrVziEOEEsrLvMzjPG46x4iLT3CpU6cOAwYMwOl0EhsbS4MGDUwniohUeyUffEpNTeXEiRN68Ak4xzna0paxjOWP/NF0TrVU8qSfhQsXsnfvXpo1a0ZkZKRO+hERqUIu93PjhWG3m266yXSiiIiISKWhwTcREZGf8HOrbnTTWUSkYmVlZWHbNm63mw0bNtC4cWMiIiJwOBzEx8dTv35904nV3lM8xTzmsYMd1ebUt8vZs2cPGRkZuFwulixZgsfjoWfPnjidTq0xExGpYBdO1bJtm6VLl1JUVESvXr1wOp0MGTKE1q1bm040bhaz+C2/ZRe7aIEeIPAFJQcj1q5dS2BgoHcl6tChQ2nVqpXpRBERuQIlB5s/+eQT9u/fT9u2bYmMjMThcOikcBEREZHroME3ERGRq7Bz505cLhe2bbNmzRpq165NRESEd5Ves2bNTCeKiFQpRUVFrF27Ftu2WbBgAfv27aNNmzZERUXhcDiIioqiZs2apjOlhIMcpD3teYVXGMc40zk+Iy8vjxUrVuByuUhJSfGuMXM6nQwfPpywsDDTiSIiVc7FP7+VPE1FP7+V5sHDbdzGndzJHOaYzpFL0EpUEZHK5eIVpqdPn+b222/H4XBgWRbdunXT39siIiIiZUCDbyIiItfocicGWJbF0KFD6dChg+lEEZFK6fTp06xYsQLbtnG5XOTn5+tFvUrmCZ4gmWSd+nYZZ8+eJTMz03ui7MGDBwkNDcXhcOB0OunTpw/+/v6mM0VEKp2fO7E7OjqaoKAg05k+yY2bGGL4iq/4Jb80nSM/o+S1xKVWokZFRekkZBERA7TCVERERKTiafBNRESkDBQUFLBy5Ups2yYtLY3jx497T3GxLIvu3bubThQR8WlHjx4lPT0dt9tNeno6Z8+e9Q4Tx8XF0alTJ9OJchUOcpBQQpnOdB7jMdM5Pq24uJg1a9bgdrtJSUkhOzub4OBgoqKicDqdWnkjIvIzzp07x+rVq3G5XMyfP5/c3FzatWuHZVlYlkW/fv0ICAgwnenzwgmnEY1w4TKdItdAK1FFRMzQClMRERER8zT4JiIiUsYKCwtZt24dtm17X3gJCQkhJiZGL7yIiJSQk5NDWloabrebVatWERAQwMCBA7Esi5iYGFq0aGE6Ua7D4zxOCilsYxuB6Eb/lbrcCQFOp5PY2FgaNGhgOlFExLiSDx6lpqZy4sQJPXh0HVaxiv70J5NM+tLXdI5cp5IPlCxZssT79aHTk0VEysaePXvIyMhg+fLlpKenc+bMGa0wFRERETFIg28iIiLlqOSqHdu22bx5c6lVO4MHD6ZevXqmM0VEKkxWVha2beN2u9mwYQONGzcmIiICh8NBfHy8VjJVIQc4QHva8xqvMZaxpnMqpQsvqLhcLpYsWYLH46Fnz544nU6GDRtGy5YtTSeKiFSYI0eOsHjxYmzbZunSpRQVFdGrVy+cTqdOtLpOkUTyAz/wT/5pOkXKWMmVqCkpKezZs8d7sqxWooqIXJmS93fdbjf//ve/S60wtSyLG2+80XSmiIiISLWlwTcREZEKtHPnTu8Q3Jo1a6hduzYRERHeVX7NmjUznSgiUqaKiopYu3Yttm2zYMEC9u3bV2rtR1RUFDVr1jSdKeVkHONII02nvpWBvLw8VqxY4X3h+uTJk97TjYYPH05YWJjpRBGRMnfxz08lT8GMiYmhYcOGphMrva/4im50I4MMBjHIdI6Us4tXotaqVYvw8HAcDgdDhgyhdevWphNFRHzC6dOnWbFiBW63G7fb7d3oMWjQIK0wFREREfExGnwTEREx5HInFliWxdChQ+nQoYPpRBGRa3LhBrFt27hcLvLz87VeqZo6wAFCCeUN3mA0o03nVBklT29JTk7m4MGDhIaG4nA4cDqd9OnTB39/f9OZIiJXreSJKsnJyWzZsoWmTZsyePBgLMsiOjqaoKAg05lVyjCGsYMd/Jt/44euz6qTo0eP8s9//hOXy1VqZfCFa3ZdT4hIdbN7926WLFmCy+Vi2bJlnD9/vtQKU61SFxEREfFNGnwTERHxAQUFBaxcuRLbtklLS+P48ePeU1x0Y0VEKoOjR4+Snp6O2+0mPT2ds2fPeod54+Pj6dixo+lEMeQxHmMRi9jGNmpRy3ROlVNcXMyaNWtwu92kpKSQnZ3tXWHmdDp1EoGI+LySw7zz588nNzeXdu3aeVeH9evXj4CAANOZVdJ3fEdnOpNMMkMZajpHDCosLGTdunW43W4WLlzI1q1bS61EjYyM5IYbbjCdKSJSpi61wrRu3br0798fy7KIiYmhRYsWpjNFRERE5Gdo8E1ERMTHXLjhbNu294WfkJAQYmJi9MKPiPiUnJwc0tLScLvdrFq1ioCAAAYOHKgbxFLKXvZyMzfzFm/xCI+YzqnySq4wu3gtYGxsLA0aNDCdKCJS6sGfkidN6cGfivUgD/Iv/kUWWfijk73k/7uwZrjkdf6Flajx8fG0adPGdKKIyDUpucLU5XJx4MAB2rVrxz333IPD4SAyMpJatfTAloiIiEhlosE3ERERH1byyUPbttm8eTNNmjQhOjoay7IYPHgw9erVM50pItVIVlYWtm3jdrvZsGEDjRs3JiIiwvsiWP369U0nig8awxgWs1invlWwPXv2kJGRgcvlYsmSJRQXF9OrVy+cTifDhg2jZcuWphNFpBo5cuQIixcvxrZtli5dSlFRkffvpKFDh9KqVSvTidXKXvbSgQ68x3s8wAOmc8SHff/996xcuRKXy1XqhHqtRBWRymLXrl0sXbrUu8K0sLCQrl27aoWpiIiISBWhwTcREZFK5MJT17Zts3btWgIDA4mIiMCyLOLi4mjWrJnpRBGpYoqKili7di22bbNgwQL27dtH27ZtiYyMxOFwEBUVRc2aNU1nio/bwx5u5mZmMINRjDKdUy3l5eWxYsUKXC4XKSkpnDx50nu60vDhwwkLCzOdKCJVUMmfXy4+hTImJoaGDRuaTqy2xjGONNLYznYNpcsVK7kS9cKK9aZNmzJ48GCtRBURn6EVpiIiIiLViwbfREREKqnLnZhgWRZDhw6lQ4cOphNFpJK6sPrDtm1cLhf5+fmlTnXo27cvfn5+pjOlkhnNaJaxjGyyqYmGJU06e/YsmZmZuFwukpOTOXjwIKGhoTgcDpxOp05uEZFrVvKF5uTkZLZs2VJqKCY6OpqgoCDTmdVeLrl0oAPTmMY4xpnOkUrs4pWoAD179sSyLOLj4+nYsaPZQBGpNrTCVERERKT60uCbiIhIFVBQUMDKlSuxbbvU6hGn06kj+0Xkihw9epT09HRs2/au/rgwTKsXraQs7GY3HenIW7zFozxqOkf+T3FxMWvWrCl1cktwcDBRUVE4nU4GDRpEYGCg6UwR8WElh2nnz59Pbm4u7dq1w7IsLMuiX79+BAQEmM6UEkYzmkUsYhvbqEMd0zlSRVxqJeqFwXr9XSAi5UErTEVEREQENPgmIiJS5VxYPWLbNp988gn79+8nJCSEmJgY3WwWkVJycnJIS0vzntBQs2ZN7/pkrf6Q8vAYj7GIRWxlK4FomMoXZWVleU9JuHgtYWxsLA0aNDCdKCI+ID8/n2XLluFyuUhNTeXEiRN68KaS2MY2OtOZd3mXh3jIdI5UUUVFRaxduxa3201qairfffcdTZs2pX///jgcDl1TiMg1uXiF6YYNGwgKCvKuMI2NjaV58+amM0VERESkgmnwTUREpAoreUPItm02b95MkyZNiI6OxrIsBg8eTL169UxnikgFysrKwrZt703ixo0bExERgcPhID4+nvr165tOlCrsAAdoT3utVqsk9uzZQ0ZGBi6XiyVLllBcXEyvXr1wOp0MGzaMli1bmk4UkQp0+PBhMjIysG2bpUuXUlRU5P07YejQobRq1cp0olyBEYxgE5v4lm8JQA9EScUouRL1008/xePxeFeixsXF0alTJ9OJIuKjLmy5cLvdpKWlcfDgQUJDQxk4cKBWmIqIiIgIoME3ERGRauXCzWbbtlm7di2BgYHe053i4uJo1qyZ6UQRKWMXTluwbZsFCxawb98+2rZtS2RkJA6Hg6ioKGrWrGk6U6qRJ3mSj/mY7WynLnVN58gVOnbsGMuXL8flcpGSksLJkye9pzsNHz6csLAw04kiUg5K/vxw8SmQMTExNGzY0HSiXIVNbKIb3ZjPfOKJN50j1VReXh4rVqzA5XLhcrnIz8/XSlQRKSUnJ8d7smzJYXvLshg4cKBOlhURERGRUjT4JiIiUk0dOXKExYsXY9s2y5Yto7Cw0HsTaejQoXTo0MF0oohco9OnT7NixQps22bh4YWcCjvFLatvITYiFofDQd++ffHz8zOdKdXUEY4QSiiTmcxTPGU6R67B2bNnyczMxOVykZyc7D11weFw4HQ66dOnD/7+/qYzReQalDwxOjk5mS1bttC0aVMGDx6MZVlER0cTFBRkOlOuUSSRHOMY/+Jf+KFrQTGv5ErUtLQ0tmzZQpMmTeh/T3+swZZWoopUE0VFRXz11VelVpg2atTIe6qbZVk0atTIdKaIiIiI+CgNvomIiEipIZm0tDSOHz/uPcXFsiw9SSlSCRw9epT09PQfDbO2+EMLFg9aTB3/Ovz2//7TmMamc6Wae4ZnmM1sdrKT+mi9bmVWXFzMmjVrcLvdpKSkkJ2dTXBwMFFRUTidTgYNGkRgYKDpTBH5CSWHWefPn09ubi7t2rXDsiydvlSFfMZn3M3drGAFAxhgOkfkkr7Z9Q1/3P1H0junUzS4CM9Gj/cBvdjYWG655RbTiSJSRkquME1NTeXQoUOlTn+8++67dTq9iIiIiFwRDb6JiIhIKYWFhaxbtw7btvnkk0/Yv38/ISEhxMTE6IUvER+Tk5NDWloabrebVatWUbNmTe/64piYGFq0aAHACU4wk5m8yquc4xy/5tdMYAKtaGX4M5Dq6nu+J5RQnuEZnuVZ0zlShrKysnC73bhcrh+tRdSpLSK+Iz8/37tCLDU1lRMnTujBlyquD324gRvIIMN0isiP5JLLG7zBu7wLwBjGMCp/FJuWbbrsSlQNxYhUPjt37mT58uWXXGFqWRZhYWGmE0VERESkEtLgm4iIiFxWyVVHtm2zefNmmjRpQnR0NJZlMXjwYOrVq2c6U6RaycrKwrZt7/qPxo0bExERgcPhID4+nvr1L396VgEFvM/7TGc6hznMCEbwHM/RiU4V+BmI/K/neZ63eIsccmhIQ9M5Ug727NlDRkYGLpeLJUuWUFxcTK9evXA6nQwbNoyWLVuaThSpVg4fPkxGRga2bZd6sdnpdDJ06FBatdJAfFW1kIUMZShf8iXd6GY6R8RrBzt4kzeZxSzqU5+xjCWBBBpReqVhyZWoLpfLe29iwIABOBwOYmJiaNhQ15MivuZSK0xL3sPQ166IiIiIlAUNvomIiMgV27lzp3cIbu3atQQGBnpPl4qLi6NZs2amE0WqnAsv8ti2zYIFC9i3bx9t27YlMjISh8NBVFTUVZ908AM/MI95vMRLbGMb0UTzPM9zJ3eW02ch8mPHOU4oofyW35JIoukcKWfHjh3znu6QkpLCyZMnvadLDR8+XKc7iJSTktfvF5/CqBebq4eznKUznelJT/7BP0zniACwkY38mT/zD/5BW9ryOI/zKI9ShzpX9PEX/m5zu918+umn3uH6Cydf/+IXvyjnz0BELufCdf/y5cu1wlREREREKoQG30REROSaHDlyhMWLF2PbNsuWLaOwsNB7o3nIkCHcfPPNphNFKq3Tp0+zYsUKbNv2rvUJCwvDsiwcDgd9+/bFz8/vun+fYopZxCL+xJ9Yz3r60pdEEhnIwDL4LER+3hSmMI1p5JBDYxqbzpEKcvbsWTIzM3G5XCQnJ3Pw4EHvi2FOp5M+ffrg7+9vOlOkUip5YnNycjJbtmyhadOmDB48GMuyiI6OJigoyHSmVKDJTGY60/mO72iJTtoUszLJ5BVewY2brnTlSZ7kPu6jBjWu+dcsOVzvdrs5duyYhmxEKljJYdTPPvus1ApTDaOKiIiISHnT4JuIiIhct5JDOmlpaRw/ftx7iotlWXTv3t10oojPO3r0KOnp6ZccJo2Pj6djx47l+vtnkslkJrOc5fSlL0/zNA4c+HH9A3Yil3OKU7SnPaMYxUu8ZDpHDCg5pDNv3jyys7MJDg4mKioKp9PJoEGDCAwMNJ0p4tNKDpPOnz+f3Nxc2rVrh2VZWJZFv379CAgIMJ0pBuxhD7/gFySSyAQmmM6RaupSD9s8zdNYWGX+e5Vcibp8+XKtVRQpJ5daP6yvNRERERExRYNvIiIiUqYKCwtZt24dtm3zySefsH//fkJCQoiJidELbyIXycnJIS0tDbfbzapVq6hZs6Z3fXBMTAwtWrSo8KYLpzAsYhG3cRu/43fcy70EoK9bKR+v8iqTmcxOdtIMrcyu7rKysrwvoF28ljE2NpYGDRqYThTxCfn5+SxbtgyXy0VqaionTpzQgyfyI7/iV+SQw1d8RS1qmc6RauYc5/iYj5nCFLaznWiimcQketCjwhp27tzpPQ1u6dKlOoVK5Drk5eWxYsUKna4oIiIiIj5Hg28iIiJSrrKysrBtG9u22bx5M02aNCE6OhrLshg8eDD16tUznShSoS58Tbjd7h+dQBAfH0/9+vVNJwLwNV8znel8xEe0pjUJJDCa0dSmtuk0qWLOcIabuZn/5D+ZznTTOeJD9uzZQ0ZGBi6XiyVLllBcXEyvXr1wOp0MGzaMli21sk+ql8OHD5ORkYFt26UGOJxOJ0OHDqVVq1amE8WH/J2/82t+zSpWcRd3mc6RauQEJ5jDHF7hFfLIYzjDeY7n6EQno10FBQWsXLkSt9tNamoqhw4d0tCOyM8oucL0008/9V6PW5ZFbGwst9xyi+lEERERERENvomIiEjF2bJlC6mpqaSkpPDFF19Qt25doqKiiIuLo1evXvj7+5tOFCkX27dvJyUlhbS0NPbv30+7du2IjY0lLi6O8PBwatSoYTrxsnLI4Q3e4D3eowENGMMYnuRJGqBTl6TsvMmbPM3TbGc7LdEwk/xYXl6e94XqJUuWcObMGXr06EFcXBxRUVE+MzQsUtaOHz9Oeno6KSkpbNiwgXr16nmvn6Ojo7VGTC7pIAfpTGfu537e4A3TOVJNHOQg7/AOb/AGHjw8yIM8zdPcxE2m036ksLCQzz//3HvKbHZ2No0bNyYqKgrLsrjjjjt0f0KqrZycHNxuN263m+3btxMcHMzgwYOxLItBgwZxww03mE4UERERESlFg28iIiJiRG5uLmlpaSxcuJBVq1bxww8/mE4SKVe33347sbGxxMbG0rVrV9M5V+0Qh5jJTO8LWWMZywQm0IQmptOkCjjLWTrSEQcOZjDDdI74uDNnzrBs2TJSU1NxuVwcOXLEdFL1EQi0BPYC5w23VCPNmzcnJiaGuLg4IiIiCAwMNJ0kPsyDh1/xK7LJ5mu+Jogg00lSxW1nO2/xFu/yLo1oxGhG8wRP0JDKM5i7bds276DP6tWrOX9e3+Skerv11lu9pyH27NnTpx/WExERERHR4JuIiIgYd/z4cbZv3246Q6TcNGvWjNatW5vOKBMnOMFMZvIqr3KWs4xiFBOYQCu0Xk2uz2xmM4YxfMM33IJW5siVKSoqIisrSy9QV5Dsutnc94v7WPDtAtqca2M6p1oIDAwkLCxMJw/JFXuVV5nIRD7lU/rQx3SOVGEb2EASSXzIh4QSyjjGMZrR1Ka26bTrkp+fz44dO0xniBgTHBxMmza6zhMRERGRykODbyIiIiIictUKKOB93mc60znMYUYwgolM1MCSXLMiiuhCFzrTmY/52HSOiFzCRjbSjW5sZSs3c7PpHBG5yHrWE044L/IiE5hgOkeqIA8e3Lh5hVf4nM/pRjcSSOA+7qMGOhFKREREREREKp4eFxURERERkasWRBAJJLCDHcxiFutZT2c6Y2GxnvWm86QSqkENpjAFG5t1rDOdIyIiUqnkk88IRjCAAfyO35nOkSrmPOeZy1xu4zZiiAEgjTQ2sIGRjNTQm4iIiIiIiBijwTcREREREblmtajFSEaSRRYppHCIQ/SgB+GE48JlOk8qmVhi6UMfnuEZ0ykiIiKVymM8xmlOM4c5+OuWr5SRAgpIIokOdOAhHqId7fiSL8kkEwvLdJ6IiIiIiIiI7oKIiIiIiMj188cfC4sv+ILVrKYRjYghxjsA58FjOlEqialM5VM+JYMM0ykiIiKVwgxm8DEf8yEf0oIWpnOkCjjKURJJpC1teY7niCKKbLJx4aI73U3niYiIiIiIiHhp8E1ERERERMrUhWG3CwNwscTShS7MZS6FFJrOEx8XTjhxxPE7fqf/vYiIiPyMb/mW8YxnEpOIIMJ0jlRyu9hFAgm0pS1v8zbjGMdudvMu79KBDqbzRERERERERH5Eg28iIiIiIlIuLgzAbWITXenKKEbRkY4kkcQZzpjOEx/2Gq+xgx3MZKbpFBEREZ9VQAHDGc6d3MkkJpnOkUrsa75mJCO5mZtJJZWXeIld7CKRRJrQxHSeiIiIiIiIyGVp8E1ERERERMrVbdzGXOayla1YWDzLs7SjHYkkcpzjpvPEB4USyhM8wR/5I0c5ajpHRETEJz3GYxziEB/wATWoYTpHKqFMMrGw6EpXvuIrZjObbWwjgQSCCDKdJyIiIiIiIvKzNPgmIiIiIiIVoh3tSCKJHHIYwxje4A3a0IZneIbv+d50nviY53iO2tQmkUTTKSIiIj5nHvP4gA+Ywxza0MZ0jlQixRTjwkUf+nAXd3GMY6SSyiY2MZKR1KSm6UQRERERERGRK6bBNxERERERqVDNaU4iiexhDxOZyPu8T1vakkAC+9hnOk98RH3q8yIv8g7v8A3fmM4RERHxGVlk8QiP8BRPEUOM6RypJH7gB+Yyl1u5lVhiaUITPudz76lvfviZThQRERERERG5an4ej8djOkJERERERKqvAgp4n/eZznQOc5gRjGAiE7mFW0yniWHFFNOTntSjHitZqRdkRQzbyEa60Y2tbOVmbjadI1ItHeMYPehBM5rxT/5JLWqZThIfd5KT/JW/lrrWfoZnCCPMdJqIiIiIiIjIddOJbyIiIiIiYlQQQSSQwA52MItZrGc9nemMhcV61pvOE4P88WcmM1nNaj7kQ9M5IiIiRhVTzP3cTwEF2NgaepOfdJjDJJJIW9ryB/7AEIawne3MZa6G3kRERERERKTK0OCbiIiIiIj4hFrUYiQjySKLFFI4xCF60INwwnHhMp0nhtzBHTzKo4xnPMc4ZjpHRETEmOd5nuUsJ4UUbuIm0znio3aykwQSCCGEGczgcR5nN7tJIonWtDadJyIiIiIiIlKmNPgmIiIiIiI+xR9/LCy+4AtWs5pGNCKGGO8AnAeP6USpYFOZij/+PMdzplNERESMSCWVl3iJv/AXetDDdI74oK/4ipGMpBOdcOHiZV5mF7tIJJHGNDadJyIiIiIiIlIuNPgmIiIiIiI+68KwWyaZNKIRscTShS7MZS6FFJrOkwpyAzcwjWm8y7usY53pHBERkQqVTTYP8ABjGcvDPGw6R3xMJplYWHSjG1/zNbOZzVa2kkACdalrOk9ERERERESkXGnwTUREREREfF5f+uLCxSY20ZWujGIUHelIEkmc4YzpPKkA93Ef/ejHYzymoUcREak2TnKSeOIJI4w/82fTOeIjiinGhYue9OQu7uIYx0gllY1sZCQjCSDAdKKIiIiIiIhIhdDgm4iIiIiIVBq3cRtzmctWtmJh8SzPEkIIiSRynOOm86Qc+eHHTGbyHd/xKq+azhERESl3xRRzL/dyjGPY2NSilukkMewc55jLXMIII444mtGMdazznvrmh5/pRBEREREREZEKpcE3ERERERGpdNrRjiSS2MUuxjKWN3iDNrQhgQQOctB0npSTjnTkj/yRyUxmM5tN54iIiJSryUxmCUtIJpmWtDSdIwad4ARJJBFKKI/wCD3oQRZZ3lPfRERERERERKorP4/H4zEdISIiIiIicj1OcII5zGEqUznJSUYxivGMpzWtTadJGSukkN70JoAAMsmkBjVMJ4lUGxvZSDe6sZWt3MzNpnNEqrQ00ognnnd4h0d4xHSOGHKIQ8xkJkkkUUQRD/EQv+f3GoQUERERERER+T868U1ERERERCq9G7iBBBLYznamMIWFLKQDHRjJSL7jO9N5UoYCCGA2s9nABmYww3SOiIhImfuGb7if+xnFKA29VVM72EECCYQQwju8QwIJ7GEPSSRp6E1ERERERESkBA2+iYiIiIhIlRFEkHcAbhazWM96OtMZC4v1rDedJ2Xkl/ySp3maiUxkF7tM54iIiJSZAxzAgYMudOEt3jKdIxXs3/ybkYykE51YxCKmMpUcckgkkYY0NJ0nIiIiIiIi4nM0+CYiIiIiIlVOLWoxkpFkkUUKKRziED3oQTjhuHCZzpMy8Af+QAghPMiDFFNsOkdEROS6neEM8cRTk5osYAGBBJpOkgqSSSYWFt3pzrd8y1/5K9lkk0ACdahjOk9ERERERETEZ2nwTUREREREqix//LGw+IIvWM1qGtGIGGK8A3AePKYT5RoFEsgHfMBa1vIGb5jOERERuS7FFHMf97Gd7SxmMU1pajpJylkxxbhwcSd3chd3cYxjpJHmPfWtBjVMJ4qIiIiIiIj4PA2+iYiIiIhItXBh2C2TTBrRiFhi6UIX5jKXQgpN58k16EpXJjGJiUzkG74xnSMiInLNxjOexSwmjTRu5mbTOVKOznGOuczlFm4hjjha0IIv+MJ76psv9kXnAAAgAElEQVSIiIiIiIiIXDkNvomIiIiISLXSl764cLGJTXSlK6MYRUc6kkQSZzhjOk+u0kQmcid38gAPcJ7zpnNERESu2vu8zxu8wSxm0Yc+pnOknBznOEkkEUIIj/IovejFFrZ4T30TERERERERkaunwTcREREREamWbuM25jKXrWzFwuJZniWEEBJJ5DjHTefJFfLHn9nMJptsXuRF0zkiIiJXJYMMxjKWP/En/pv/Np0j5WA3u0kggZa05HmeZzjDySGHucylIx1N54mIiIiIiIhUan4ej8djOkJERERERMS0wxxmBjNIIoliinmQB3mWZ2lBC9NpcgVmMIMEEvgn/ySccNM5IlXSRjbSjW5sZatWMYqUgSyy6Etf4olnDnNM50gZ+5ZvmcY05jGPJjRhNKN5kidpQAPTaSIiIiIiIiJVhgbfRERERERESjjBCeYwh6lM5SQnGcUoxjOe1rQ2nSY/wYOHeOLZwAY2sYnGNDadJFLlaPBNpOwc4AC96EUIISxlKYEEmk6SMpJJJq/wCotYRHvaM45xjGGM/jsWERERERERKQdadSoiIiIiIlLCDdxAAglsZztTmMJCFtKe9oxkJN/xnek8uQw//JjDHPzx51EeNZ0jIiJyWQUUYGFRl7qkkKKBqCrAgwcXLvrSl7u4iwMc4G/8jWyySSBB/x2LiIiIiIiIlBMNvomIiIiIiFxCEEEkkMAOdvA+77Oe9XSmMxYWX/CF6Ty5hEY0Yi5zSSGF93nfdI6IiMiPnOc8wxjGHvbgxk0jGplOkutwnvPMZS63ciuxxNKYxmSSyZd8yUhG4q/b7yIiIiIiIiLlSj95i4iIiIiI/ISa1GQkI8kiixRSOMxhetKTcMJx4TKdJxe5m7uZwAQSSGALW0zniIiIeHnw8AiP8Dmfs5jFtKe96SS5Rqc4RRJJtKc9D/Mw3enON3zjPfVNRERERERERCqGBt9ERERERESugD/+WFj8i3+xmtU0ohExxNCd7tjYePCYTpT/8wIv8Et+iRMnpzhlOkdERASA3/E7PuIjbGy60910jlyDIxwhkUTa0pbneI544tnOduYyl850Np0nIiIiIiIiUu1o8E1EREREROQqXTjtbQMbaE97RjCCLnRhLnMppNB0XrVXk5okk8xhDvMwD5vOERER4UVeJIkkPuADIok0nSNXaRe7SCCBEEJ4m7f5Lb9lN7tJIok2tDGdJyIiIiIiIlJt+Xk8Hh1LICIiIiIich2+4Rte5VU+4iNa05oEEniUR6lDHdNp1dpKVjKIQUxnOk/whOkckUrlHOfoTnfyyfe+rZBC8sijCU2oQQ3v25vTnC/4otTbROT/e4/3GM1okkjicR43nSNXYRObeI3X+IiPaEUrnuAJHuER6lLXdJqIiIiIiIiIoBPfRERERERErttt3MZc5rKNbVhYPMuzhBBCIomlhkakYg1gAH/iT0xgAp/xmekckUolkEA605kDHGD///3nEIc4z3kOctD7tgMc4HZu19CbyGWkkcZv+A2Tmayht0okk0wsLG7ndjaxidnMZhvbSCBBQ28iIiIiIiIiPkQnvomIiIiIiJSxwxxmBjNIIoliinmQB3mWZ2lBC9Np1Y4HD06cZJLJv/k3N3GT6SSRSiONNOKIw8NP3zpayUr607+CqkQqj1WsYjCDeYiHmMEM0znyM4opZhGLeImXWMc6+tKXp3kaBw788DOdJyIiIiIiIiKXoME3ERERERGRcnKCE8xhDlOZyklOMopRjGc8rWltOq1aOclJetKThjRkFauoRS3TSSKVwg/8QDDBnODEZd8nmGAOcEAnvolc5Gu+5m7upj/9sbH1NeLDfuAH5jGPl3mZrWwlmmgmMpHe9DadJiIiIiIiIiI/Q6tORUREREREyskN3EACCWxnO1OYwkIW0p72jGQk3/Gd6bxqoz71SSaZr/maZ3nWdI5IpVGLWjhxUpOal/z3NanJ/dyvgR6Ri+xgB5FE0o1ufMRH+hrxUSc5SRJJhBLKIzzCndzJt3yLC5eG3kREREREREQqCZ34JiIiIiIiUkHOc56P+IipTCWbbKKJZhKT6EEP02nVwkd8xH3cxzzmMZzhpnNEKoWVrCSCiMv++/Ws5w7uqMAiEd+2n/38B/9BE5qwkpXUo57pJLnIhZX0b/Imhf+PvfsOj6rO2z/+TiCEjoi0RWqAVIIJEEASOhZggF0EsewoiCA+khERCCh69sFCwLIHBBURdHRBBfcxDL0TgrRQAySBhKZSpSjN1Pn9sSu/zU5AxMBJuV+5cnEx85nzvU+QeDHcfL9kM5CBjGIUd3O31dFERERERERE5HdS8U1EREREROQ2yyWXRSziNV5jC1toRzvGMAYbNqujFXvDGc4nfMImNhFMsNVxRAq9XHKpRS1Oc9rjubrU5ShHLUglUjid4AQd6IAPPqxlLXdxl9WR5D8c5CAmJh/xEZWoxDCG4cBBVapaHU1EREREREREbpKOOhUREREREbnNvPHGho3NbGY966lKVXrRixa0YB7zcKN/n3SrvM3bhBLKQzzEBS5YHUek0PPGm8d53OO4Ux98GMQgi1KJFD6nOU1XuuLGzQpWqPRWiOxgB3bsNKUpC1nIm7zJYQ5jYKj0JiIiIiIiIlLEqfgmIiIiIiJioUgiceFiG9vww4+HeZhQQnHiJJtsq+MVO2Uow1d8xXnOM4AB5JBjdSSRQu8RHiGLrDyPZZGlI4NF/u0853mAB7jIRVawgtrUtjqSAAkkYMNGOOEkkcQsZpFKKg4clKOc1fFEREREREREpACo+CYiIiIiIlIIhBPOV3zFbnYTRhhP8RRNaIKJyRWuWB2vWKlDHRaykHWsYxjDrI4jUui1ohUNaXj151540YxmBBFkYSqRwuEnfuI+7uM0p1nDGupT3+pIJVouubhwEUEEUURxjnMsYAHb2Y4dO6UpbXVEERERERERESlAKr6JiIiIiIgUIiGE4MTJAQ7Qi16MZSwNaICBwXnOWx2v2GhBCz7lUz7mY6Yy1eo4IoXeX/nr1eNOS1MaO3aLE4lY7xKXsGHjGMdYw5o8BVG5vTLIwImTQALpQx9qUpPNbL6665sXXlZHFBEREREREZFbwMvtdrutDiEiIiIiIiL5O8UppjMdE5NccnmSJxnLWGpRy+poxcKbvMl4xvNP/kkvelkdR6TQSiGFQAKBf+34dohD2tlKSrTLXKYHPdjHPtay9urvD7m9fuZnZjObSUziDGfoT39e4iX88bc6moiIiIiIiIjcBiq+iYiIiIiIFAG//sVuLLH8zM88xVO8yIvUpa7V0Yq8Z3iGOcxhPetpTnOr44gUWs1oxh720IY2bGSj1XFELHOFK/SkJ0kksZrVhBBidaQS5wQn+IAP+Dt/x42bJ3mSMYzhT/zJ6mgiIiIiIiIichup+CYiIiIiIlKEZJDBp3zKa7zGCU4wgAGMZax2mvkDssjiQR4kmWQ2s5m7udvqSHIDzp07x8GDB62OUaI4azqZcvcUYo7G8NDph6yOU6I0btyYKlWqWB1DgEwy+Qt/YQMbWMlKWtDC6kglShppTGUqM5hBFarwDM/wPM9zB3dYHU1ERERERERELKDim4iIiIiISBGURRZzmctEJpJKKt3pznjGE0GE1dGKpJ/4iXa0wxdf4omnAhWsjiTXkJOTw4cffsj48eM5e/as1XFKlrpAGlAH+NHiLCVMjRo1ePPNN3nyySfx9va2Ok6JlUkmfenLetazkpW0pKXVkUqMbWzDxGQOc2hAA4YznKEMpSxlrY4mIiIiIiIiIhZS8U1ERERERKQIyyWXRSziNV5jC1toRzvGMAYbNqujFTmHOEQb2tCKVsQRRylKWR1J/kt8fDzR0dEkJyfjcDh4+OGHrY5U4nxa61OeOPGE1TFKFLfbzWeffcb06dMJCwtj6tSptG7d2upYJc4v/EJf+pJAAstYRhvaWB2pREgggVhiWchCwgnHgYPHeEz/jxYRERERERERQMU3ERERERGRYuO//3I4hhge4iG88LI6WpGRQAJd6YoDB7HEWh1H/u3YsWPExMTw+eef07lzZ0zTJDg42OpYJVIuuXijHceskJqaisPhYPny5Tz++ONMmjSJWrVqWR2rRLjMZfrQh61sZQlLVHq7xX7d1XYyk9nDHpX6RUREREREROSa9E6liIiIiIhIMRFJJC5cbGMbfvjxMA8TSihOnGSTbXW8IiGSSGYyk8lM5kM+tDpOiZeVlYVpmgQEBPDtt9/y5ZdfsnLlSpXeLKTSm3X8/f1ZunQpcXFxrF+/nsaNG2MYBhkZGVZHK9YucYle9CKRRJazXKW3W+gSlzAxaUxjBjKQBjRgK1tJIEGlNxERERERERHJl3Z8ExERERERKab2sIdJTGIuc7mbu3me5xnCEMpRzupohd4EJvA3/sZc5tKPflbHKZFWrlxJdHQ0R44cYdSoUcTExFC2bFmrY4kUCleuXCE2NpZJkyZRt25d3n33Xbp37251rGLnEpfoSU/2sY8VrCCUUKsjFUs/8iPv/fvjIhfpT3/GM54mNLE6moiIiIiIiIgUciq+iYiIiIiIFHOHOcy7vMtHfEQlKjGMYTzP89zBHVZHK9RGMpKpTGUBC3iAB6yOU2IcOHCAESNGsGjRInr27Ml7771H/fr1PeZycnL46KOPME2TzMxMC5KK3Hply5Zl1KhRPPHEE3h5eR5b/f333zNu3Dg+++wzevbsiWmaNGrUyIKkxc9P/MQDPMAhDrGSlYQQYnWkYucIR3iHd5jJTHzw4QmeYCxjqYWO8BURERERERGRG6Pim4iIiIiISAlxilNMZzomJrnk8iRPEkMMtaltdbRCyY2bp3iKL/mS5SynHe2sjlSsXbp0icmTJzNx4kQCAgKYMmUK7du3z3c2ISGB6Oho9uzZw1//+leqV69+m9OK3B7Hjx9nzpw5tGjRgqlTp9KqVat859asWUN0dDT79+/nmWee4fXXX6dixYq3OW3xcY5zPMADHOUoq1hFEEFWRypWkkhiMpOZy1zqUIcRjGAwg6lABaujiYiIiIiIiEgRo+KbiIiIiIhICfMzPzOb2cQSy1nO8gRP8DIvU5e6VkcrdHLIoT/9Wc1q1rKW5jS3OlKx43a7mT9/PiNHjuTixYu8+uqrPPfcc5QqVcpj9tixY8TExPD555/TqVMnpkyZQnBwsAWpRW6flJQUHA4HK1as4PHHH2fy5MnUrFnTYy47O5tp06bx6quvUrFiRd544w3++te/5rtTnFzbaU7TjW6c4xyrWEVjGlsdqdhIIIFYYlnEIoIJZhSjeIRH8MHH6mgiIiIiIiIiUkR5Wx1AREREREREbq/KVMaBg0McYgpTWMIS/PDDjp1kkq2OV6iUohSf8zmhhNKd7hzikNWRipUdO3YQFRXFgAED6NixI6mpqTgcDo/SW1ZWFqZpEhgYyNq1a/nkk09YtWqVSm9SIgQEBLBs2TLi4uJYv349jRs3xjAMjyN+S5cujcPhID09nb59+zJo0CA6derE7t27LUpe9JzkJF3ownnOs4Y1Kr0VgFxyceHiXu4liijOcY444tjNbuzYVXoTERERERERkT9ExTcREREREZESyhdfhjCEdNKZyUwSSSSEEGzY2MIWq+MVGuUohwsXtahFN7pxghNWRyryzp49i8PhoFWrVmRlZbFx40acTme+R5auXLmS5s2bM27cOEaMGMH+/fux2+0WpBaxls1mY+/evYwcOZLY2FiaNWvGkiVLPOaqVauGaZps3ryZrKwswsLCsNvt/PjjjxakLjq+53s60IFf+IUEEmhEI6sjFWmZZOLESTOa0ZveVKMaG9hAAgnYsOGFdiIUERERERERkT9OxTcREREREZESzgcf7NjZwx6+4RtOcYrWtCaSSFy4rI5XKFSmMktZSmlKcx/3cY5zVkcqkrKzs5kxYwb+/v7Mnz+fWbNmsWnTJiIiIjxm09LSsNlsdOvWDT8/P/bu3YthGJQtW9aC5CKFQ/ny5TEMg/3799O6dWu6d++OzWbj0CHP3ShbtGhBQkICs2fPZvny5fj7+2OaJjk5ORYkL9wOcIAooihFKdaxjru52+pIRdZFLmJi4ocfgxlMC1qwhz1Xd30TERERERERESlIKr6JiIiIiIgIAN54Y8PGZjaznvVUpSq96EULWjCPebhxWx3RUtWpzgpW8BM/0YMeXOKS1ZGKlHXr1tGiRQuee+45Hn30UVJSUrDb7Xh55d315/LlyxiGQUhICGlpaSxbtgyXy0WDBg2sCS5SCNWtWxen08mqVas4dOgQwcHBxMTEcPHixTxzXl5e2O120tPTGT58OKNHj6ZVq1YkJCRYlLzw2cMeOtKRu7iLtaylNrWtjlQkneIUBgb1qc/LvMxf+AvppOPESRBBVscTERERERERkWJKxTcRERERERHx8Otub9vYRjDBDGAAoYTixEk22VbHs0xd6rKYxaSSyiM8QhZZVkcq9H744QfsdjudOnWiRo0a7Nq1C9M0qVSpksesy+UiMDAQ0zSJjY0lKSmJ++67z4LUIkVD586d2bFjB2+++SYffPABAQEBOJ1Oj7kKFSpgGAZJSUnUqlWL9u3b079/f44ePWpB6sJjPeuJJJKmNGUVq6iO53HLcn2HOIQDBw1owHSmM5zhHOEIJiZ1qWt1PBEREREREREp5lR8ExERERERkWsKJxwnTnaxizDCeIqnaEITTEyucMXqeJYIJphFLGINa1R+u47MzExM0yQgIICNGzeyYMECVqxYQWBgoMfszp07iYqKok+fPnTo0IHU1FQcDgelS5e2ILlI0eLj44PD4SA9PZ2+ffsycOBAOnXqRFJSksds06ZNWbx4MXFxcSQmJhIUFIRhGGRkZFiQ3FqLWMT93E9HOrKEJVSmstWRipRd7MKOnaY0xYWLN3mTwxzGwOBO7rQ6noiIiIiIiIiUECq+iYiIiIiIyG8KIQQnTg5wgF70YixjaUADDAzOc97qeLddG9qwlKUsZ7nKb/n4dee2l156iZEjR7Jnzx569uzpMXf27FkcDgctW7YkIyODb7/9FqfTSY0aNSxILVK0VatWDdM02bx5MxkZGYSHhzN06FB+/PFHj1mbzcbevXsZP348b7/9NiEhISxatMiC1NaYwxz+zJ/pRz/mM5+ylLU6UpGRQAI2bIQRxm528zEfs5/9OHBQnvJWxxMRERERERGREkbFNxEREREREblhDWiAiclhDjOMYZiY1KMeDhwc57jV8W6rdrRjCUtUfvsP+/fvp0ePHvTu3ZsWLVqwb98+DMPA19c3z1xubi5Op5OAgADmzZvHrFmz2Lx5M61bt7YouUjx0bJlSzZs2MDHH39MXFwc/v7+mKZJTk5Onrly5coxZswYUlJSaNu2LTabjW7dupGcnGxR8ttjGtP4K39lGMP4hE8ojXaW/C255OLCRRvaEEUU5zhHHHHsYAd27PoaioiIiIiIiIhlVHwTERERERGR360GNTAwOMpRJjCBecyjIQ0ZylCOctTqeLfNr+W3ZSzjUR4lm2yrI1ni0qVLGIZBaGgox48fJz4+nq+++op69ep5zK5bt46wsDAGDx7MI488QkpKCna7HS8vLwuSixRPXl5e2O12UlJSePrppxk9ejQRERFs2LDBY7ZOnTo4nU5Wr17NqVOnaN68OQ6HgwsXLliQ/NaKJZbhDGc84zEx8ULfd64nk0ycOAkiiD70oTrV2cjGq7u+6esnIiIiIiIiIlZT8U1ERERERERuWiUq4cDBIQ4xhSksZSmNaYwdO8kU712DfvVr+W0pS3mER0pU+c3tduN0OmncuDFTp04lNjaWrVu3EhkZ6TF77Ngx7HY7nTp1okaNGuzcuRPTNKlcubIFyUVKhjvuuIOJEyeye/duatSoQVRUFP379+e7777zmO3YsSPbtm3jvffeY86cOQQEBOB0OnG73RYkL1hu3IxkJC/xEh/wAQaG1ZEKtQtcwMSkEY14mqeJIIK97L2665uIiIiIiIiISGGh4puIiIiIiIj8Yb74MoQhpJHGTGaSSCIhhGDDxmY2Wx3vloskssSV37Zv305kZCQDBw6kW7dupKam4nA4KFWqVJ65zMxMTNMkICCAjRs38uWXX7JixQqCgoIsSi5S8vj7+7NkyRLi4uJITEwkMDAQwzDIyMjIM1e6dGmGDBlCamoqDz30EIMGDaJNmzZs2bLFouR/XCaZPM7jTGMaX/AFQxhidaRC6yQnMTCoRz3GM56+9OUgB3HiJIAAq+OJiIiIiIiIiHhQ8U1EREREREQKjA8+2LGzhz18wzec5jRtaEMkkbhwWR3vlookksUsZilLi/Wxp2fOnMHhcBAREYGPjw87duzA6XRy1113ecy6XC4CAwMZN24cL7zwAklJSfTr18+C1CICYLPZ2Lt3L+PHj+ftt9+mWbNmLF682GPuzjvvxDRNtmzZgo+PD23btsVut3P69GkLUt+8n/iJ7nRn4b8/HuIhqyMVSumk48BBAxrwPu/jwMERjmBiUoc6VscTEREREREREbkmFd9ERERERESkwHnjjQ0bm9jEetZTlar0ohfhhOPESS65Vke8JaKIYjGLWcKSYld+y87OxjRN/Pz8+Prrr5k1axZr1qwhNDTUY/bAgQP06NGDXr16ERQURHJyMoZhULZsWQuSi8h/KleuHGPGjCE5OZk2bdrQo0cPbDYbBw8e9JgNDw9n/fr1fPHFF6xduxZ/f39M0yQnJ8eC5L/PcY7TkY7sYx9rWENXulodqdDZwQ7s2PHHn4UsZCITOcxhDAyqUtXqeCIiIiIiIiIiv0nFNxEREREREbmlft3tbTvbCSGEgQykOc1x4ixWxbBfRRHFN3zDQhbyBE8Ui3tcs2YNYWFhjB49mieeeILk5GTsdjteXl555i5duoRhGDRr1oxjx44RHx+Py+WiXr16FiUXkWu5++67cTqdrF69miNHjhAYGIjD4eDChQt55ry8vOjXrx/JyclER0czZswYWrZsyfr16y1K/tv2spc2tCGTTDaykXDCrY5UqCSQgA0b4YSzhz3MYhb72Y8DB+UoZ3U8EREREREREZEbpuKbiIiIiIiI3BZhhOHEyS52EUYYT/EUTWiCickVrlgdr0B1oQsLWMA3fEN/+pNBhtWRbsr333+P3W6nc+fONGjQgOTkZEzTpFKlSnnm3G438+bNIzAwkClTphAbG0tiYiJRUVEWJReRG9WpUye2b9/O1KlT+cc//kFgYCBOpxO3251nrkKFChiGQVJSEnXq1KF9+/bYbDaOHDlyW/P+1o6ha1hDJJHUoQ7rWEd96t+mZIVbLrm4cBFBBFFEcY5zLGAB29mOHTulKGV1RBERERERERGR303FNxEREREREbmtQgjBiZMDHKAXvRjLWBrQAAOD85y3Ol6B6UpXVrOadazjAR7gAhd++0WFxJUrV4iNjSUwMJBNmzaxaNEiXC4XjRo18pjdvn07UVFRDBgwgI4dO5KamorD4aBUKZUoRIqK0qVLM2TIEFJTU+nbty+DBg2iU6dO7N6922O2SZMmLFy4kAULFpCcnExQUBCGYfDLL7/clqwmJtOZnu9zX/M13elOZzqzilXcxV23JVNhlkEGTpwEEEAf+lCTmmxhy9Vd30REREREREREijIV30RERERERMQSDWiAiclhDjOMYZiY1KMeDhwc57jV8QpEa1qzkpXsYx9d6MIZzlgd6Te5XC6Cg4OZMGECI0eOJCkpie7du3vMnT17FofDQUREBKVKlWL79u04nU6qV69uQWoRKQjVqlXDNE22bNlCVlYWYWFh2O12Tp8+7TFrs9lITk7mjTfe4J133iEkJIR58+bd0nwnOcl4xjOc4SxneZ7nTEz6058hDGEe80r8kZ0/8zMmJg1pyBCG0IY2JJOMCxetaGV1PBERERERERGRAqHim4iIiIiIiFiqBjUwMDjKUSYwgXnMoyENGcpQjnLU6nh/WBhhxBPPCU7QnvYc45jVkfKVmprKgw8+SO/evYmMjCQtLQ3DMPD19c0zl52dzYwZM/D392f+/PnMmjWLtWvX0rx5c4uSi0hBCw8PJyEhgdmzZ7NixQoCAgIwTZOcnJw8cz4+PjgcDlJSUrj33nt5+OGH6dq1K/v27bsluUYzmkwyAehLX5JJJocchjOcEYzgTd7ExMS7BL/leYITGBjUox6v8Ar96MdBDuLESVOaWh1PRERERERERKRAebndbrfVIURERERERER+lUEGn/Ipr/M6xznOAAYwlrEEEmh1tD/kKEfpRjeyyGIFK/DDz2NmF7uoTGUa0vC25Tp//jwTJ07k3XffJSQkhClTptCuXbt8Z9euXUt0dDQpKSkMGzaM1157jUqVKt22rCJy+126dInJkyczceJEgoKCmDJlCpGRkfnOxsfHEx0dzb59+xg2bBgTJkygcuXKBZIjkUQiiMDNv97KLE1palKT5jRnNav5jM94iIcKZK2iaA97mMpUPuVTqlKVoQxlBCOoQhWro4mIiIiIiIiI3DIl958/ioiIiIiISKHkiy9DGEIaacxkJokkEkIINmxsZrPV8W5aPeoRTzxVqEIUUexhT57nv+M77uM+RjP6tuRxu904nU4CAgL46KOPmDRpElu2bMm39PbDDz9gt9vp1KkTNWvWZNeuXZimqdKbSAlQoUIFDMNg9+7d1K5dm6ioKGw2G0ePeu7I2b59e7Zv387MmTOZO3cuAQEBzJgxg9zc3D+UIZdchjCEUpS6+lg22ZziFFvYwiIWldjSWwIJ2LARSiirWU0ssRziEAaGSm8iIiIiIiIiUuyp+CYiIiIiIiKFkg8+2LGzhz18wzec5jRtaEMkkbhwWR3vptSkJmtYQyMa0YEOV4t8P/ET93EfZzjD13zNBjbc0hyJiYm0a9eOp556it69e7N//xhcYBYAACAASURBVH4cDgelSpXKM3flyhViY2MJCAhg06ZNLFy4kBUrVhAYWLR33xOR369p06YsWrSIBQsWsG/fPgIDAzEMg4yMjDxz3t7e2O12UlNT6devH88++yxt2rRh06ZNN732x3zMLnaRTXaex7PI4jznmc3sm752UeTGjQsXkUQSRRTHOc4nfEIKKThwUJayVkcUEREREREREbktVHwTERERERGRQs0bb2zY2MQm1rOeqlSlF70IJxwnTnLIsTri73IHd7Cc5bSiFV3pynKW82f+TDrp5JBDKUoxjGHk8sd2SMrPiRMnGDp0KK1bt8bX15ft27fz4YcfUq1aNY9Zl8tFcHAwEyZMYOTIkSQlJdGjR48CzyQiRYvNZiM5OZk33niDt99+m5CQEBYuXOgxV7VqVUzTJDExkbJly9KuXTvsdjunTp36Xeud4xxjGHP1iNP/lk02c5jDm7x5U/dTlGSRhRMnzWhGL3oBsIAFJJKIHXueHfFEREREREREREoCFd9ERERERESkyPh1t7ftbCeEEAYxiOY0x4nTYyegwqw85Ykjjvu4jz70IZ54ssgC/lXi2MMe5jK3wNbLysrCNE38/f1ZvHgxs2fPZs2aNTRr1sxjdv/+/XTv3p3evXvTsmVLkpOTMQwDX1/fAssjIkVbmTJlcDgcpKSk0LZtW3r16kW3bt1ITk72mL3nnnuIj4/nm2++Yd26dfj7+2OaJtnZN/Y9ezzjucjFaxbf4F9Hob7ES/yTf970PRVmF7mIiYkffgxmMOGEk0TS1WNORURERERERERKKhXfREREREREpMgJIwwnTnaxi3DCeYqnaEITTEyucMXqeDfEF1+a0pQMMvLdte4FXuAyl//wOqtXryYsLIyxY8cybNgwkpOTsdvtHnMXL17EMAyaNWvGiRMniI+P56uvvqJu3bp/OIOIFE916tTB6XSyZs0aTp06RfPmzXE4HPz8888es7/uFOdwOIiJiaFZs2YsW7bsutffzW7e5/2rxeBr8cEHL7yYw5wiVYL+Lac5jYFBferzEi/xZ/5MGmk4cRJCiNXxREREREREREQsp+KbiIiIiIiIFFnBBOPEyQEO0ItejGUs9amPgcF5zlsd77o+5mMmMjHfI03duDnLWd7hnZu+/nfffYfdbqdLly40bNiQvXv3MnHiRCpWrJh3Lbcbp9NJ48aNmTp1KpMmTWLr1q1ERkbe9NoiUrJ06NCBHTt2MHPmTObMmUNgYCBOpxO3O+8ubeXLl8cwDJKSkmjcuDEPPPAANpuNw4cP53vd/+F/8L7G25dlKANAbWrzAi+QTjrzmU9pShfovVnhMIdx4KABDZjGNIYznCMcwcSkHvWsjiciIiIiIiIiUmh4uf/7HSgRERERERGRIuo0p5nGNExMcshhIAOJIYba1LY6Wh6LWYwNW76lt/9UjnKkk/678l++fJlJkyYRGxtLvXr1+Pvf/86DDz6Y7+y2bdsYPnw4W7duZdCgQbz++uvcddddv+teRET+09mzZ/nb3/7GtGnTCA8P57333iMiIiLf2ZUrV+JwODh8+DCjRo0iJiaGsmXLAjCXuTzGY3mOOPXGGy+88Mab3vRmKEPpQhe88Lot93ar7WY3b/EWc5lLHeowghE8zdOUp7zV0URERERERERECiXt+CYiIiIiIiLFRnWqY2BwlKNMYALzmEdDGmLHThppVscD4ChHeZiH85Q5riWbbMYx7oav7XK5CA4OxjTNq7sq5Vd6O3PmDA6Hg4iICMqUKcO2bdv48MMPVXoTkT/szjvvxDRNtm7diq+vL23btsVut3P69GmP2a5du7Jz507eeOMN3n33XZo2bYrT6eQiF3me56/O/XqUaStaMYMZnOUs85hHV7oWi9JbAgnYsHEP97CTnXzMx6SRhgOHSm8iIiIiIiIiIteh4puIiIiIiIgUO5WohAMHhzjEDGawkY0EEYQdO/vYZ2m2etRjJzsZzWju5E688KIUpfKdzSKLT/mUbWy77jVTUlK4//776d27N1FRUaSkpDBmzBjKlCmTZy47OxvTNPHz8+Prr79m9uzZrFmzhtDQ0AK7PxERgLCwMOLj4/niiy9Yt24d/v7+mKZJdnZ2njkfHx8cDgcpKSl07NiRJ598kpC5IZziFG7cVKc6L/IiKaSwiU0MYhAVqXiNVYuOXHJx4aItbYkiinOcI444drELO/ZicWSriIiIiIiIiMitpqNORUREREREpNjLIou5zCWWWFJIoTvdeZmXaU1rS3NlkkkccUxnOutYR2lKk0VWnhkffGhNa9az3uP1586dwzAMpk+fTvPmzZk6dSpt27bNd63Vq1fjcDjYv38/zzzzDK+//joVKxb98oiIFH6XLl1i8uTJTJw4kYYNG2KaJvfdd1++s/9M+if9/frjXu6m58mezB4wmzur3HmbE986mWTyBV8wkYmkkkp3ujOOcbQl/+/dIiIiIiIiIiJybdrxTURERERERIo9H3ywYyeJJL7hG05zmja0IZJIXLgsy1WGMvSjH2tYQyqpvMALVKVqnl3gssgigQTiiLv6utzcXJxOJwEBAfzjH//grbfeYsuWLfmW3r7//nvsdjtdunShQYMGJCcnY5qmSm8icttUqFDh6vHLfn5+3H///dhsNo4cOeIx27BZQ46XPc7sn2ez6ZVNNPVrimma5ObmWpC84FzgAiYmfvjxNE/TkpYkkXR11zcREREREREREfn9VHwTERERERGREsMbb2zY2MQm1rOeqlSlF70IJxwnTnLIsSxbE5owkYkc5zif8RkRRAD/KscBjGAEmWSydetW7r33XgYPHsyAAQNIT0/H4XDg7Z33j/hXrlzBMAyaNGnC5s2bWbRoES6Xi0aNGt32exMRAWjSpAkLFy5kxYoVpKenExQUhGEY/PLLL1dnwgijund17HY7KSkpPPbYY7z44ou0bt2ajRs3Wpj+5pziFAYG9anPy7zMX/gL6aTjxEkQQVbHExEREREREREp0lR8ExERERERkRLp193etrOdEEIYxCCa0xwnTrLJvqFrzGFOgefyxZfHeIxv+Za97GUYw6hEJQ5xiHb/aEfr1q2pUKEC27dvxzRNqlSp4nENl8tFUFAQb731FmPGjGH37t107969wLOKiNyMrl27smvXLt544w3eeecdQkJCmDdvnsdc1apVMU2TpKQk7rzzTtq1a4fdbufkyZMWpP59DnIQBw4a0ID3eZ9oojnCEUxM7uZuq+OJiIiIiIiIiBQLKr6JiIiIiIhIiRZGGE6c7GIX4YQzmME0pjEmJpe5fM3XbWITj/EYL/LiLcsWRBCTsybzyrRXKDesHHtq7WHa3GmsWrWKkJAQj/nU1FQeeOABevfuTVRUFGlpaRiGga+v7y3LKCJyM3x8fHA4HKSkpHDvvffy8MMP07VrV/bu3esxGxAQwLJly4iLiyM+Pp6AgABiY2PJzMy8LVn/j//jGMduaHYnO7FjpylNceHiTd7kMIcxMLiTO29xUhERERERERGRkkXFNxEREREREREgmGCcODnAAXrTm3GMowENMDA4xzmP+dd4DW+8eZd3eZ7nceMu8EwrV67knnvu4ZVRrzC65mjOtTvHkIeHeMydP3+emJgYQkNDOX36NAkJCTidTmrVqlXgmURECtKf/vQnnE4nmzZt4sKFC4SFheFwOPj55589Zm02G/v27cPhcGAYBqGhoSxduvSW5vuSL+lPf/7O3687l0ACNmyEEcZudjOLWexnPw4clKPcLc0oIiIiIiIiIlJSqfgmIiIiIiIi8h/qUx8Tk8Mc5lmeZQpTqE99HDg4znEAkklmMYvJ/ffHVKbyDM8UWPktLS2N/v37061bNxo1asS+ffswDIOyZctSilJX59xuN06nE39/f2bOnMmkSZPYsmUL9957b4HkEBG5XSIiIti4cSMzZ85k7ty5BAQEMGPGDHJzc/PMlS9fHsMw2LNnD6GhoTz44IPYbDYOHTpU4Jk+4zMe5VGyyWYa0zjP+TzP55KLCxetaU0UUZzjHAtYwA52YMdOaUoXeCYREREREREREfn/VHwTERERERERyUd1qmNgcJCDxBDDF3xBYxoTTTRjGZun0JBLLjOZydM8TS6517nq9V2+fBnDMGjWrBlJSUksXboUl8tFgwYNPGYTExO59957eeqppxgwYADp6ek4HA5KlSrleWERkSLA29sbu91Oamoq/fr149lnn6V169Zs2rTJY9bPz4+vvvqKlStXcujQIYKDg4mJieHixYsFkuVjPuYJnrj6PT2TTN7nfQAyyMCJkyCC6EMfalCDTWy6uuubF14FkkFERERERERERK7Py+12F/xZLCIiIiIiIiLFTAYZfMmXvMIrfMd3+RbcvPHmSZ7kIz7C+3f+WzOXy8Vzzz3Hzz//jGEY/M///A+lS3vuFnT8+HEMw2DmzJl06NCBKVOmEBISctP3JSJSWO3cuZPo6GgSEhJ4/PHHeeutt6hRo4bHXFZWFtOnT+eVV16hcuXKvP7669jt9ptedwYz8t3F8w7u4CVe4l3e5Ud+5GEe5iVewh//m15LRERERERERERunnZ8ExEREREREbkBvvhix8593JfnuNH/lEsun/IpT/HUDe/8tnPnTtq3b0+fPn3o0KEDqampOBwOj9JbVlYWpmkSEBDA4sWLmT17NqtXr1bpTUSKrXvuuYf4+Hji4uKIj4/H39+f2NhYMjMz88z5+PjgcDhISUmhe/fuDBw4kM6dO5OUlPS713yf9695dPXP/Mx4xvMQD3GQgzhxqvQmIiIiIiIiImIhFd9EREREREREbtBJTvIpn5JF1jVncsjhMz7jMR4jh5xrzp07dw6Hw0HLli355Zdf2LBhA06nM9/djFatWkVYWBhjx45l2LBhJCcn/6HdjEREihKbzca+fftwOBwYhkFoaCjLli3zmKtduzYffvghmzdv5sqVK4SHhzN06FDOnDlzQ+u8xVs8y7P5lt4A3Li5i7t4h3eoQ50/dE8iIiIiIiIiIvLHqfgmIiIiIiIicoPe4Z1rFiL+Uw45zGMej/Io2WTneS43Nxen04m/vz/z5s1j+vTpbNq0iTZt2nhcJz09nf79+9O1a1caNmzI3r17mThxIhUrViywexIRKQrKly+PYRjs2bOH0NBQHnjgAWw2G4cPH/aYbdmyJd9++y0ff/wxcXFx+Pv7Y5omOTnXLiPHEssoRl03gxs3P/AD/+Sff/R2RERERERERESkAKj4JiIiIiIiInIDznOeaUzzKLJdSw45fM3X2LFf3fktPj6e8PBwBg8ezCOPPEJKSgpDhgzB2zvvH88vX76MYRiEhISwe/dulixZgsvlomHDhgV+XyIiRYmfnx9fffUVK1eu5ODBgwQFBWEYBleuXMkz5+Xlhd1uJyUlhcGDBzN69GgiIiL49ttvPa75Kq8SQ8wNre+FF3/jbzdUghYRERERERERkVvLy+12610aERERERERkd+wl718wicc5zgHOcgP/MBJTpJBxtWZ0v/+yCWXTDKvPm67YqPKs1X4x6f/oHPnzpimSXBwcL7ruFwuhg8fzk8//URMTAwjRoygTJkyt/z+RESKmqysLKZPn84rr7xC5cqVef311695DHRqaioOh4Ply5fz+OOPM2nSJGrVqsUYxjCZyTdcZPPGm1xyWcEKutK1IG9HRERERERERER+JxXfRERERERERP6AM5zhOMf5ju+u/niMY3zHdxx0H+Ro5lGu+F6h4uKKfHT5IwY8NCDf66SkpBAdHc3KlSt5/PHHmTx5MjVr1rzNdyMiUvQcP34cwzCYOXMmHTp0YMqUKYSEhOQ763K5iI6O5vSPpwlZEcLmNpuBfxXavPHGCy+yyMrzmkpUojrVuZu7aUADalObLnShG91u+b2JiIiIiIiIiMi1qfgmIiIiIiIicgusXLmS6Ohojhw5wgtjX+CxUY9R27c2VaiSZ+7cuXMYhsH06dO55557mDJlCm3btrUotYhI0bV161aio6NJTEzk2Wef5X//93+pUqWKx9zlK5fpsKcD2xptw+eCD8EVgwm9K5Q61KEWta7++Cf+RC1qUZayFtyNiIiIiIiIiIj8FhXfRERERERERArQgQMHGDFiBIsWLaJnz56899571K9f32MuNzeXzz//nBdffJFSpUrxt7/9jcGDB+Pt7W1BahGR4uHX762jRo0iJyeH8ePHM3z48DzfW3PJJZtsTn1/inHjxvHZZ5/Rs2dPTNOkUaNGFqYXEREREREREZHfQ++mi4iIiIiIiBSAS5cuYRgGzZo14/vvv2fdunW4XK58S29btmyhbdu2DB48mEceeYTU1FSGDBmi0puIyB/k7e2N3W4nNTWVxx57jBdffJGIiAi+/fbb/z+DN2Uow913343T6WT16tUcPnyYwMBAHA4HFy9etPAORERERERERETkRukddREREREREZE/wO12M2/ePAIDA5kyZQqxsbFs27aN9u3be8weO3YMu91OmzZtqFixIjt27MA0TSpXrmxBchGR4uuOO+7ANE2SkpK46667iIyMxG63c/LkSY/ZTp06sWPHDiZNmsSnn35KQEAATqcTHZQhIiIiIiIiIlK4qfgmIiIiIiIicpN27NhBVFQUAwYMoGPHjqSmpuJwOChVqlSeuaysLEzTJDAwkLVr1/LJJ5+watUqgoODLUouIlIyBAQEsHTpUuLi4li/fj2NGzfGMAwyMzPzzJUuXRqHw0F6ejp9+/Zl0KBBdOrUid27d1uUXEREREREREREfouKbyIiIiIiIiK/09mzZ3E4HLRq1YqsrCw2btyI0+mkevXqHrMrV66kefPmjBs3jhEjRrB//37sdrsFqUVESi6bzcbevXsZOXIksbGxNGvWjCVLlnjMVatWDdM02bx5M1lZWYSFhWG32/nxxx8tSC0iIiIiIiIiItej4puIiIiIiIjIDcrOzmbGjBn4+/szf/58Zs2axaZNm4iIiPCYTUtLw2az0a1bN/z8/Ni3bx+GYVC2bFkLksvtkJaWhpeXF1988cXVxypWrIiXl9cNfSYmJhZoni+++OLqtf/zv7uLFy96rL1x48bfvN6oUaPyvOa1114r0LxWye/XTYqn8uXLYxgG+/fvp3Xr1nTv3h2bzcahQ4c8Zlu0aEFCQgKzZ89m+fLl+Pv7Y5omOTk5FiQXEREREREREZH8qPgmIiIiIiIicgPWrVtHixYteO6553j00UdJSUnBbrfj5eWVZ+7y5csYhkFISAhpaWksW7YMl8tF/fr1LUouVrp48SI7duwAoHfv3rjd7nw/q1SpUuBrDxgwALfbTZcuXfI8XrFiRdxu99VcABMmTLjutc6cOcMHH3wAwGOPPYbb7ebll18u8MwXL16kSZMm9OzZs8CvLfKrunXr4nQ6WbVqFYcOHSI4OJiYmBguXryYZ87Lywu73U56ejrDhw9n9OjRtGrVioSEBIuSi4iIiIiIiIjIf1LxTUREREREROQ6fvjhB+x2O506daJGjRrs2rUL0zSpVKmSx6zL5SIwMJApU6YQGxtLUlIS9913nwWpRW5MuXLlqF+/PkuWLLnujnPvvvsudevWLZA1K1asSGRkZL7Pud1ucnNzyc3NLZC1RK6nc+fO7NixgzfffJMPPviAgIAAnE6nx1yFChUwDIOkpCRq1apF+/bt6d+/P0ePHrUgtYiIiIiIiIiI/ErFNxEREREREZF8ZGZmYpomAQEBbNy4kQULFrBixQoCAwM9Znfs2EFUVBR9+vShQ4cOpKSk4HA4KF26tAXJpSg6f/48LVu2vO3rent7ExMTA3DNo0vPnz/P+++/z5gxY255nkqVKpGens7ixYtv+VoiAD4+PjgcDtLT0+nbty8DBw6kU6dOJCUlecw2bdqUxYsXExcXR2JiIkFBQRiGQUZGhgXJRURERERERERExTcRERERERGR//Lrzm0vvfQSI0eOZM+ePfkevXj27FkcDgetWrUiIyODb7/9FqfTSY0aNSxILUVRZGQkn3zyiaUZBg4cSJ06dViwYAG7d+/2eH7KlCl0794dPz8/C9KJ3B7VqlXDNE22bNlCRkYG4eHhDB06lB9//NFj1mazsXfvXsaPH8/bb79NSEgIixYtsiC1iIiIiIiIiEjJpuKbiIiIiIiIyL/t37+fHj160Lt3b1q0aMG+ffswDANfX988c7m5uTidTvz9/Zk3bx6zZs1i8+bNtG7d2qLkUhg0btwYt9vNgAED/tB1vvnmG7y8vK5+Hj58mIcffpg77riDatWq0bNnT9LT0z1el5KSQp8+fahSpQoVKlQgKiqKhISE31zP19eXUaNG4Xa7ef311/M8d/HiRaZOncq4ceOue40zZ87wwgsv4OfnR5kyZahatSoPPvgga9asuTrz1ltv4eXlxaVLl9iwYcPV+/t1Z8T/vu9ffvnld69xM1+7gvp1k+KhRYsWbNiwgY8//pi4uDj8/f0xTZOcnJw8c+XKlWPMmDGkpKTQtm1bbDYb3bp1Izk52aLkIiIiIiIiIiIlj4pvIiIiIiIiUuJdunQJwzAIDQ3l+PHjxMfH89VXX1GvXj2P2XXr1hEWFsbgwYN59NFHSUlJwW634+XlZUFyKUri4uLylLK8vLzYsGGDx1yfPn1wu9307t0bgOeff57nn3+eH374gS+//JLVq1fzyCOP5HlNWloabdu2JTExkfnz53Py5EmmT5/OhAkT8i3J/bchQ4ZQs2ZN5s+fn6e4M23aNDp37pzvEb+/OnHiBK1atWLOnDmYpsmPP/7I5s2bKV++PF26dGHmzJkAvPjii7jdbipUqEC7du1wu9243W6ys7Pzve+bWeNmvnYi/83Lywu73U5KSgpPP/00o0ePJiIiIt/fr3Xq1MHpdLJ69WpOnjxJ8+bNcTgcXLhwwYLkIiIiIiIiIiIli4pvIiIiIiIiUmK53W6cTieNGzdm6tSpxMbGsnXrViIjIz1mf/jhB+x2O506daJGjRrs3LkT0zSpXLmyBcmlKOrdu/fVstevn+3atfvN1w0ePJi2bdtSoUIFunbtSo8ePdi6dWueIxjHjRvH+fPnMU2Tbt26UbFiRZo1a8bs2bM5fvz4b65Rrlw5XnjhBXJzc3njjTcAuHz5Mu+++y4vvfTSdV87duxYDh06xN///nd69uxJ5cqVadq0KXPmzKF27dpER0dz8uTJ38xwK9a4ka+dyLXccccdTJw4kd27d1OjRg2ioqLo378/3333ncdsx44d2b59O++99x5z5swhICAAp9OJ2+22ILmIiIiIiIiISMmg4puIiIiIiIiUSNu3bycyMpKBAwfSrVs3UlNTcTgclCpVKs9cZmYmpmkSGBjIxo0b+fLLL1mxYgVBQUEWJZeSplWrVnl+XrduXQCOHTt29bGlS5cCcP/99+eZ/dOf/kTTpk1vaJ1nn32WatWqMXfuXNLS0vjwww9p06YNoaGh133d//3f/wHQo0ePPI/7+vrSpUsXrly5wrJly24oQ0GvcSNfO5Hf4u/vz5IlS4iLiyMxMZHAwEAMwyAjIyPPXOnSpRkyZAipqak89NBDDBo0iDZt2rBlyxaLkouIiIiIiIiIFG8qvomIiIiIiEiJcubMGRwOBxEREfj4+LBjxw6cTid33XWXx6zL5SIwMJBx48bxwgsvkJSURL9+/SxILcVVQkICTz755HVnqlSpkufnZcqUASA3NxeAjIwMLly4QNmyZalYsaLH62vUqHFDWSpWrMjzzz9PTk4Or776Km+99RYvv/zydV+TkZHBTz/9RNmyZalUqZLH8zVr1gT+dVTpzfoja/zW107k97DZbOzdu5fx48fz9ttv06xZMxYvXuwxd+edd2KaJlu2bMHHx4e2bdtit9s5ffq0BalFRERERERERIovFd9ERERERESkRMjOzsY0Tfz8/Pj666+ZNWsWa9asyXc3qwMHDtCjRw969epFUFAQycnJGP+PvXuPyrLK////ujxwRhTkIGqTH8tgCNECi9SGQArzJszJRDI/1XiYXHKIr+ZhHMfGxkal9NZ0tFyj45oUyzWiadpS01ITRyx1SoRRy/EAOkjIISCR6/eHP+5PBCogeos9H2vdf9z7eu+939e+rts/XG/2njFDTk5OdsgcuDZHR0e5u7uroqJCpaWlda4XFhY2eKzExER5eHho1apVCgkJUWho6HXn9vDwUEVFhUpKSupcrzl+1M/Pz9ZmGEaD82nqHMDN4uzsrEmTJik7O1sPP/ywBg0apNjYWJ04caJO7AMPPKBdu3YpPT1dO3fu1H333Ser1arLly/bIXMAAAAAAIA7D4VvAAAAAIA73o4dO9S7d2+9+uqr+t///V9lZ2dr5MiRdQpwysrKNGPGDAUHB+vs2bP67LPP9OGHH+quu+6yU+b4uQgNDVV6enqT+w8cOFDS/x15WqOgoEA5OTkNHsfDw0Opqany8PC47m5vNZ5++mlJ0qZNm2q1V1ZWavv27XJ2dq51BKuLi4t++OEH2/f77rtP77zzTrPOAdxsXbp00cqVK/XJJ5/o5MmTCgwMVHJycp3iTMMwNHToUGVnZyspKUmTJk1SaGiodu3aZafMAQAAAAAA7hwUvgEAAAAA7linT5/WyJEjFRkZqbvvvlvZ2dmyWq11jks0TVMffPCBAgMDtWDBAs2ePVtZWVnq37+/nTIHGmfWrFny9PRUSkqKtm7dqtLSUh05ckQjRoyo9/jTa5k+fbqKior0yCOPNCj+jTfeULdu3ZSSkqKNGzeqpKREubm5SkhIUF5enqxWq+04UunKLli5ubk6deqU9u7dqxMnTlz3t9bYOYBb5bHHHtMXX3yhhQsX6r333lNAQIBWrlwp0zRrxbm6umrGjBn617/+pc6dO+vRRx9VbGysTp48aafMAQAAAAAAWj4K3wAAAAAAd5zy8nLNC84DdgAAIABJREFUnj1bgYGByszM1KZNm/Thhx/qf/7nf+rEfvHFF+rfv7/i4+MVERGhnJwcJScnq3Xr1nbIHHcaNzc39e7dW5K0fv16GYZR7+fAgQO2PpmZmTIMQ+vXr5d05WjFmt3XDMPQ7NmzJUm9e/eWxWKRJHXv3l179+5VWFiYnnnmGfn4+OiFF15QYmKigoODVVlZKcMwNGrUqFp5lZWVyTAMxcTEXPM+DMOwFae99957MgxDb7/9tqQrR4zu379fw4cPV1JSkry8vNSnTx+VlZVp27ZtGj16dK2x5s+fr549eyowMFDDhg2T1WpVYGCgMjIy6tz3iBEjGjVHU9YOuFFt2rTRmDFjlJOTo2eeeUYvvfSSIiIidPjw4Tqx9957rzZu3KgNGzYoOztbv/zlLzVjxgxVVFTYIXMAAAAAAICWzTB/+ueHAAAAAAC0YB9++KGSk5N1/vx5TZgwQVOmTJGjo2OduMLCQr322mtatGiR+vbtqwULFigkJMQOGQMA7iRffPGFEhMTlZmZqeeee05vvvmmvL2968RdunRJixcv1u9//3v5+PjojTfe0NChQ+2QMQAAAAAAQMvEjm8AAAAAgDtCTk6OBg4cqLi4OPXr10/Hjh3TjBkz6hS9VVVV6Z133tF9992ntWvX6q9//at27txJ0RsAoFk88MAD2r17t5YvX66tW7cqICBAVqtVly9frhXXtm1bJScn6+jRo3rkkUc0bNgwDRgwQEeOHLFT5gAAAAAAAC0LhW8AAAAAgBatqKhIkydPVs+ePXX+/Hnt2rVLK1eulJ+fX53YnTt36oEHHtD48eOVkJCgo0ePauTIkTIMww6ZAwDuVIZhaOTIkTp27JgSExM1adIkhYaGateuXXVi/f39tXLlSu3cuVMFBQXq1auXkpOTVVxcbIfMAQAAAAAAWg4K3wAAAAAALZJpmlq5cqUCAgL07rvvas6cOfrnP/+pvn371ok9ffq0Ro4cqccee0y+vr46dOiQrFar3N3d7ZA5AODnwtXVVTNmzNDhw4fl7++vRx99VLGxsfrPf/5TJ/bRRx/VF198oWXLlmn16tUKCAjQO++8o+rqajtkDgAAAAAAcPuj8A0AAAAA0OJkZWWpb9+++s1vfqO4uDjl5uYqOTlZrVu3rhVXXl6u2bNnKzAwUJmZmdq4caO2bt2qwMBAO2UOAPg56tGjhzZt2qQNGzboyJEjCgwM1IwZM1RZWVkrrlWrVho5cqRycnI0dOhQjRs3Tg8//LAyMzPtlDkAAAAAAMDti8I3AAAAAECLkZ+fr7Fjx+qhhx6So6OjvvjiCy1dulReXl51Yj/88EMFBQVp5syZ+n//7//pX//6lwYNGmSHrAEAuCI2NlbZ2dmaNWuW3nrrLd1///3auHFjnbgOHTrIarUqKytLTk5O6tu3r0aOHKnz58/bIWsAAAAAAIDbE4VvAAAAAIDb3qVLl2S1WhUQEKCPPvpIy5cv144dOxQcHFwnNjc3V08++aTi4uIUGhqq7OxszZgxQ46OjnbIHC1NWlqaDMOQYRjq0qWLvdNpMjc3N9t9XO+TlZXVrHOnp6fbxnZycrK1l5aW1pl779691x1v4sSJtfq8/vrrzZovcKs5ODgoOTlZ2dnZCg8P11NPPaXo6GgdOXKkTmyvXr302WefKSMjQ59++qnuu+8+Wa1WVVVV2SFzAAAAAACA2wuFbwAAAACA29q2bdvUs2dPTZkyRSkpKcrNzdXIkSPrxJWWlmrGjBkKDg5Wfn6+PvvsM73//vvq2rWrHbJGSzVhwgSZpqmQkBB7p3JDSktL9eWXX0qS4uLiZJpmvR8PD49mnzs+Pl6maSoqKqpWu5ubm0zTtOUlSTNnzrzmWBcuXNCSJUskSc8995xM09S0adOaPefS0lLde++9slgszT42cDWdO3fWypUrtWPHDp0/f169evVScnKyiouL68TGxsbq66+/1tixY/Xqq6/qwQcf1K5du+yQNQAAAAAAwO2DwjcAAAAAwG1t6tSpat++vY4cOaIZM2bI2dm51nXTNLVy5Urdc889WrhwoebMmaP9+/erX79+dsoYwPU4OzvrF7/4hTZv3nzNHefmzZvXbMWrbm5uV/13wTRNVVdXq7q6ulnmAhrjV7/6lb788kstW7ZMq1atUkBAgFauXCnTNGvFubm56c9//rO++uortWrVSjNmzLBPwgAAAAAAALcJCt8AAAAAALe9/v376+67767TfuDAAfXt21e/+c1vFBcXp5ycHCUnJ6t169a3PkmgBSoqKlJoaOgtn7dVq1aaPHmyJF316NKioiL95S9/0aRJk256Pu7u7jp+/Lg++uijmz4XUJ9WrVpp5MiRysnJ0dChQ/XSSy/poYce0r59++rE3nvvvXr44YftkCUAAAAAAMDthcI3AAAAAECLc+7cOb344osKCwuTk5OTvvzySy1dulQdO3a0d2pAi9CvXz+tWLHCrjm8+OKL6ty5szZs2KDDhw/Xub5gwQI9+eST6t69ux2yA+zD09NTVqtV+/btU9u2bdW3b1+9/PLLKiwstHdqAAAAAAAAtx0K3wAAAAAALc6KFSv0wQcfaM2aNfrkk090//332zsltBAXLlxQamqqunfvLkdHR3Xp0kUDBgzQihUrVF5efs2+VVVVWrNmjaKjo+Xn5ydnZ2cFBwfLarXWOSKzsrJS06dPV0BAgFxcXOTp6anY2Fht2LBBly9fbnTcrZCRkSHDMGyfb7/9VsOGDVP79u3l5eUli8Wi48eP1+l39OhRDR48WB4eHnJ1dVX//v21e/fu687n6OioiRMnyjRN/elPf6p1rbS0VAsXLtTUqVOvOcaPn6eDg4M6dOiggQMHaseOHbaYtLQ0GYahsrIy7dmzx3Z/bdq0qfe+KyoqGj1HU9cOuJoHH3xQu3fv1vLly7V8+XKlp6fbOyUAAAAAAIDbDoVvAAAAAIAWycfHR0OHDrV3GmhB8vPzFRYWptWrV8tqtaqgoEAHDhxQRESEXnzxRS1duvSa/bds2aL4+HhFRkYqOztbp06d0pgxY5SamlrnOM7x48drwYIFWrhwoS5cuKDs7GwFBAQoLi5Ou3btanScJEVGRsrLy0uZmZmNuu/169fXKsoyDEN79uypEzd48GCZpqm4uDhJUkpKilJSUnTmzBlbkenw4cNr9Tl27JjCw8OVlZWltWvX6ty5c1q8eLFmzpzZoEKvMWPGyNfXV2vXrlV2dratfdGiRYqMjFRgYOBV+9Y8z1WrVtme5759++Ti4qKoqCgtW7ZMkjRhwgSZpilXV1f17dtXpmnKNE1VVVXVe99NmaMpawdcj2EYev755+Xu7m7vVAAAAAAAAG5LFL4BAAAAAICfhSlTpuibb76R1WqVxWKRu7u7fH19NW3aNMXExDRojIiICE2ZMkUdOnRQx44dlZiYqISEBFmtVhUXF9vitm/frqCgIEVHR8vZ2Vm+vr6aO3euevToUWu8hsZJUnV1ta1oqzHi4uJs/Wo+ffv2vW6/UaNGKTw8XK6urhowYIAGDRqk/fv3q6CgwBYzdepUFRUVyWq1Kjo6Wm5ubgoODtby5cuVl5d33TmcnZ2Vmpqq6upqzZo1S5L0/fffa968efrd7353zb41z3P+/PmyWCxq166devTooVWrVqlTp05KSkrSuXPnrpvDzZijIWsHAAAAAAAA4MZQ+AYAAAAAAH4W1q1bJ0kaOHBgnWubN29WSkrKNftbLJZax1vWCAkJ0aVLl/T111/b2mJiYvT5559rzJgxyszMtB1bmpOTo4iIiEbHSdLOnTtVWFio8PDwBt3vjQoLC6v1vWvXrpKks2fP2tq2bNkiSXriiSdqxfr7+9dbvFefcePGycvLS6tXr9axY8e0dOlSPfzww+rZs+c1+9U8z0GDBtVqd3R0VFRUlMrLy/Xxxx83KIfmnqMhawcAAAAAAADgxlD4BgAAAAAA7niVlZW6ePGinJycmnxs4MWLFzV9+nQFBwerQ4cOtmNDJ06cKOnKTmU1Fi1apJUrV+rEiROKiopSu3btFBMTYyukamxcc9u9e7deeOGFa8Z4eHjU+u7g4CDpys5z0pU1LSkpkZOTk9zc3Or09/HxaVAubm5uSklJ0eXLl/WHP/xBaWlpmjZt2jX7XO95+vr6SrpyVGlT3cgc11s7AAAAAAAAADeOwjcAAAAAAHDHc3R0lIeHhyoqKlRSUtKkMWJjYzVz5kyNHj1aubm5tqNH582bJ0m1jiA1DEPPP/+8tm3bpqKiImVkZMg0TQ0ZMkRvvfVWo+NuR46OjnJ3d1dFRYVKS0vrXC8sLGzwWImJifLw8NCqVasUEhKi0NDQ6859redZc/yon5+frc0wjAbn09Q5AAAAAAAAANw6FL4BAAAAAICfhaefflqS9NFHH9W51rt3b73yyitX7Xv58mXt2bNHfn5+SkpKkre3t62Qqry8vE58+/btdfToUUlS27ZtFR0drYyMDBmGoU2bNjU67mYJDQ1Venp6k/vXHBtbc+RpjYKCAuXk5DR4HA8PD6WmpsrDw+O6u73VqHmeP12nyspKbd++Xc7OzrWOYHVxcdEPP/xg+37ffffpnXfeadY5AAAAAAAAANw6FL4BAAAAAICfhTfeeEPdunXTK6+8ok2bNqmkpESnT5/WuHHjlJeXd83Ct9atWysiIkL5+fmaO3euCgoKVF5erh07dmjJkiX19vntb3+rw4cPq7KyUufPn9ecOXNkmqYiIyObFBcZGSkvLy9lZmbe+GI0k1mzZsnT01MpKSnaunWrSktLdeTIEY0YMaLe40+vZfr06SoqKtIjjzzSoPia55mSkqKNGzeqpKREubm5SkhIUF5enqxWq+04Ukl64IEHlJubq1OnTmnv3r06ceKE+vfv36xzAAAAAAAAALh1KHwDAAAAAAA/C35+ftq/f7+GDRumxMREeXl5qU+fPvruu++0a9cu3XXXXUpLS5NhGDp06JDOnDkjwzBsO5CtWbNGY8eO1cKFC+Xv769u3bpp5cqVSkhIkCRFR0fbjuj89NNPFRAQoPj4eHl6eiowMFBbtmzRu+++q6lTp9pyamicJFVVVck0zVpHql6Nm5ubevfuLUlav369DMOo93PgwAFbn8zMTBmGofXr10uSnJ2dbfduGIZmz54t6crueBaLRZLUvXt37d27V2FhYXrmmWfk4+OjF154QYmJiQoODlZlZaUMw9CoUaNq5VVWVibDMBQTE3PN+zAMw1ac9t5778kwDL399tu1nufw4cOVlJRke55lZWXatm2bRo8eXWus+fPnq2fPngoMDNSwYcNktVoVGBho22Hvx/c9YsSIRs3RlLUDAAAAAAAAcGMMsyH/WwoAAAAAgJ306dNHERERmjNnjq1t9uzZWrp0qU6cOGHHzAAAuPm8vb312muvady4cba2l19+Wbm5udq+fbsdMwMAAAAAALAvdnwDAAAAAAAAAAAAAAAAALQoFL4BAAAAAAAAAAAAAAAAAFoUCt8AAAAAAAAAAAAAAAAAAC0KhW8AAAAAAAAAAAAAAAAAgBaFwjcAAAAAAAAAAAAAAAAAQItC4RsAAAAAAADsIj09XYZhyDAMOTk52TsdAAAAAAAAAC0IhW8AAAAAAACwi/j4eJmmqaioqDrXSktLde+998pisTRqzKb2AwAAAAAAANCyUPgGAAAAAADQSG5uburXr98dO9/twDRNVVdXq7q6us61a63HtfoBAAAAAAAAuHO0sXcCAAAAAAAAwE+5u7vr+PHjt6wfAAAAAAAAgJaFHd8AAAAAAAAAAAAAAAAAAC0KhW8AAAAAAACSKisrNX36dAUEBMjFxUWenp6KjY3Vhg0bdPnyZUlSWlqaDMNQWVmZ9uzZI8MwZBiG2rT5v031q6qqtGbNGkVHR8vPz0/Ozs4KDg6W1WqtdfxmRkaGrb9hGMrJydGzzz4rLy8vW9vkyZOvO19DXbhwQampqerevbscHR3VpUsXDRgwQCtWrFB5eXm9cQ4ODurQoYMGDhyoHTt2XDX3b7/9VsOGDVP79u3l5eUli8VS765rR48e1eDBg+Xh4SFXV1f1799fu3fvrhP30/ErKioatP5X63cr7g0AAAAAAADArUXhGwAAAAAAgKTx48drwYIFWrhwoS5cuKDs7GwFBAQoLi5Ou3btkiRNmDBBpmnK1dVVffv2lWmaMk1TVVVVtnG2bNmi+Ph4RUZGKjs7W6dOndKYMWOUmpqqSZMm2eIGDx4s0zQVFxcnSRo7dqzGjRunU6dOKTMzU61bt27QfA2Rn5+vsLAwrV69WlarVQUFBTpw4IAiIiL04osvaunSpbXiVq1aZYvbt2+fXFxcFBUVpWXLltWbe0pKilJSUnTmzBmtWbNGn3zyiYYPH14rh2PHjik8PFxZWVlau3atzp07p8WLF2vmzJl1Csl+On6N663H1frd7HuTpMjISHl5eSkzM7NRzwYAAAAAAABA01D4BgAAAAAAIGn79u0KCgpSdHS0nJ2d5evrq7lz56pHjx6NHisiIkJTpkxRhw4d1LFjRyUmJiohIUFWq1XFxcX19pk0aZIiIiLk4uKihx56SFVVVerYseON3pYkacqUKfrmm29ktVplsVjk7u4uX19fTZs2TTExMXXi5s+fL4vFonbt2qlHjx5atWqVOnXqpKSkJJ07d67O+KNGjVJ4eLhcXV01YMAADRo0SPv371dBQYEtZurUqSoqKpLValV0dLTc3NwUHBys5cuXKy8vr1nusyFrcDPuTZKqq6tthXgAAAAAAAAAbj4K3wAAAAAAQB1fffVVreMeDcPQ+PHj79h2SYqJidHnn3+uMWPGKDMz03a8aU5OjiIiIhq8dhaLpdbRmTVCQkJ06dIlff311/X269OnT+MfVAOtW7dOkjRw4MA61zZv3qyUlJRacYMGDaoV4+joqKioKJWXl+vjjz+uM0ZYWFit7127dpUknT171ta2ZcsWSdITTzxRK9bf379JxYWNdTPvTZJ27typwsJChYeHS/p5/oYAAAAAAACAW6mNvRMAAAAAAAC3n/vvv/+qO1fdqe2LFi1SeHi4/va3vykqKkqS1L9/f40dO1ZPP/10vX3qc/HiRb355ptat26dTp8+raKiolrXv//++3r7ubq6NniOxqisrNTFixfl5OQkd3f3Jsf5+vpKunJk6E95eHjU+u7g4CDpyi5oNWOXlJTIyclJbm5udfr7+PgoNze34TfVSDfz3q7m5/gbAgAAAAAAAG4ldnwDAAAAAACQZBiGnn/+eW3btk1FRUXKyMiQaZoaMmSI3nrrrTqxVxMbG6uZM2dq9OjRys3NtR2BOW/ePElNKxq61nzX4+joKA8PD1VUVKikpKTJcTXHgPr5+TUpB3d3d1VUVKi0tLTO9cLCwkaN19j1uJn3BgAAAAAAAMA+KHwDAAAAAACQ1L59ex09elSS1LZtW0VHRysjI0OGYWjTpk21Yl1cXPTDDz/Yvt9333165513dPnyZe3Zs0d+fn5KSkqSt7e3rUirvLy8ybldbb6Gqtmx7qOPPqpzrXfv3nrllVdqxf30fisrK7V9+3Y5OzvXOaq0oWqOWa058rRGQUGBcnJyGjVWU9bjZt4bAAAAAAAAgFuPwjcAAAAAAID/329/+1sdPnxYlZWVOn/+vObMmSPTNBUZGVkr7oEHHlBubq5OnTqlvXv36sSJE+rfv79at26tiIgI5efna+7cuSooKFB5ebl27NihJUuWNDmvq83XUG+88Ya6deumV155RZs2bVJJSYlOnz6tcePGKS8vz1b4VhOXkpKijRs3qqSkRLm5uUpISFBeXp6sVqvtWNDGmjVrljw9PZWSkqKtW7eqtLRUR44c0YgRI+o9/vRamrIeN/PeJCkyMlJeXl7KzMxs8hgAAAAAAAAAGo7CNwAAAAAAAEmffvqpAgICFB8fL09PTwUGBmrLli169913NXXq1Fqx8+fPV8+ePRUYGKhhw4bJarUqMDBQkrRmzRqNHTtWCxculL+/v7p166aVK1cqISFBkhQdHa3Q0FBlZmbKMAytX79ekuTs7HzVIzyvNV9D+Pn5af/+/Ro2bJgSExPl5eWlPn366LvvvtOuXbt011131YobPny4kpKSbHFlZWXatm2bRo8eLUn15j5t2jRJV44hnT17tqQru8lZLBZJUvfu3bV3716FhYXpmWeekY+Pj1544QUlJiYqODhYlZWVMgxDo0aNsu209+PxR4wYcd31uFa/m3lvklRVVSXTNJt0lC0AAAAAAACAxjNM/jcOAAAAAHAb69OnjyIiIjRnzhxb2+zZs7V06VKdOHHCjpkBAHDzeXt767XXXtO4ceNsbS+//LJyc3O1fft2O2YGAAAAAABgX+z4BgAAAAAAAAAAAAAAAABoUSh8AwAAAAAAAAAAAAAAAAC0KBS+AQAAAAAAtFCGYVz3M2PGDHunCQAAAAAAAADNro29EwAAAAAAAEDTmKZp7xQAAAAAAAAAwC7Y8Q0AAAAAAAAAAAAAAAAA0KJQ+AYAAAAAAG6akydP6qmnnlJxcbEk6dixYzIMQ+np6bYYNze3OsdzpqWl2Svla0pLS7Pl2KVLF1t7aWlpnXvYu3fvdcebOHFirT6vv/76zUz/jlHfO1PzcXJyUs+ePbVo0aLbake8jIyMWnlWVFTc9DnT09NrrcuP1fdbBAAAAAAAAFoSCt8AAAAAAMBNcfDgQYWGhurxxx9Xu3btrhpXWlqqL7/8UpIUFxcn0zQ1YcKEW5Vmo0yYMEGmaSokJKRWu5ubm0zTtN2HJM2cOfOaY124cEFLliyRJD333HMyTVPTpk2TdGVN7r33XlkslhvKt7nGud3U986YpqnKykplZmaqXbt2Gj9+vCZNmmTnTP/P4MGDZZqm4uLibtmc8fHxMk1TUVFRt2xOAAAAAAAA4Fah8A0AAAAAADS74uJixcbG6te//rXGjx9v73RuKWdnZ/3iF7/Q5s2blZWVddW4efPmqWvXrvVeM01T1dXVqq6uvqFcmmuclsLBwUG9evXS6tWr1apVK82bN0+FhYX2TgsAAAAAAADATUDhGwAAAAAAaHZz5sxRfn6+pk+fbu9UbrlWrVpp8uTJknTVo0uLior0l7/85ao7krm7u+v48eP66KOPbiiX5hqnpenatas6deqkqqoqHTp0yN7pAAAAAAAAALgJKHwDAAAAAADNyjRNLVu2TA899JD8/f3tnY5dvPjii+rcubM2bNigw4cP17m+YMECPfnkk+revbsdsvt5ME1TkuTk5GTnTAAAAAAAAADcDBS+AQAAAACAZnXo0CGdO3dOISEhda7dc889Mk1T8fHxNzTHhQsXlJqaqu7du8vBwUEdOnTQwIEDtWPHjmvGOjo6qkuXLhowYIBWrFih8vJySVJVVZXWrFmj6Oho+fn5ydnZWcHBwbJarU06JtTR0VETJ06UaZr605/+VOtaaWmpFi5cqKlTp9bbNyMjQ4Zh2D4VFRX1tn/77bcaNmyY2rdvLy8vL1ksFh0/frzR45w8eVLDhg2Tu7u7vLy89Pzzz+u7777Tt99+q9jYWLm7u6tTp04aPXq0SkpKbOO//vrrtjH69etna9+yZYutvWPHjlfNp6nzNsR//vMf5eXlqV27dgoKCqp17b///a+SkpJ09913y8HBQd7e3hoyZIgOHjxYK66x70RD3rMfy8/Pv+bza2y+knT06FENHjxYHh4ecnV1Vf/+/bV79+5616i5fosAAAAAAACAvVD4BgAAAAAAmtVXX30lSerSpctNGT8/P19hYWFatWqVrFarCgoKtG/fPrm4uCgqKkrLli2rE7t69Wpb7IEDBxQREaEXX3xRS5culXSlWCs+Pl6RkZHKzs7WqVOnNGbMGKWmpl71ONLrGTNmjHx9fbV27VplZ2fb2hctWqTIyEgFBgbW22/w4MEyTVNxcXHXbE9JSVFKSorOnDmjNWvW6JNPPtHw4cMbPU5qaqpeffVV5efna/78+fr73/+u5557TikpKZo5c6by8vI0Y8YMLVu2TH/4wx9s40ybNk2macrV1bXW+DExMTJNUw8++OBNmfdaLl26pIMHDyohIUFt27bV22+/rXbt2tmu5+XlKSwsTO+//74WL16swsJC7dy5U4WFhQoPD9fevXttsY15Jxr6nv3Yj5/fBx98oF27dtV6fo3N99ixYwoPD1dWVpbWrl2rc+fOafHixZo5c2a9BXUAAAAAAABAS0fhGwAAAAAAaFZ5eXmSJA8Pj5sy/pQpU/TNN99o/vz5slgsateunXr06KFVq1apU6dOSkpK0rlz52rFWq1WWSwWubu7y9fXV9OmTVNMTEytcSMiIjRlyhR16NBBHTt2VGJiohISEmS1WlVcXNzoPJ2dnZWamqrq6mrNmjVLkvT9999r3rx5+t3vfnfD6zBq1CiFh4fL1dVVAwYM0KBBg7R//34VFBQ0apzf/OY3evDBB+Xq6qrnn39eQUFB2rx5s1JTU9WrVy+5ublp7Nix6tatmz766KMbzru5512/fr1tFzkHBwf17t1bPj4+OnLkiJ5//vlasVOmTNHJkyf11ltv6cknn5Sbm5uCgoKUnp4u0zSVmJhYK76h70Rj3rMaP35+kZGRslgsdZ5fY/KdOnWqioqKZLVaFR0dLTc3NwUHB2v58uW23yQAAAAAAABwJ6HwDQAAAAAANKuaIzXbtm17U8Zft26dJGnQoEG12h0dHRUVFaXy8nJ9/PHHtWIHDhxYZ5zNmzcrJSVFkmSxWOo9JjUkJESXLl3S119/3aRcx40bJy8vL61evVrHjh3T0qVL9fDDD6tnz55NGu/HwsLCan3v2rWrJOns2bONGic0NLTWd39//3rbO3fu3Oixb8W8cXFxMk1Tpmnq9OnTGjZsmNatW6d33nmnTmxGRoZatWoli8XPGaqRAAAgAElEQVRSq93Pz09BQUE6cOCATp8+Lalx70RD37Mf++nz69y5s6Taz68x+W7ZskWS9MQTT9SK9ff3V48ePerMDwAAAAAAALR0beydAAAAAAAAuLM4OTlJunLsZHOrrKzUxYsX5eTkJHd39zrXfX19JV05evJ6sT928eJFvfnmm1q3bp1Onz6toqKiWte///77JuXr5uamlJQU/f73v9cf/vAH7dy5U+vXr2/SWD/10x31HBwcJEnV1dWNGufHR4FKUqtWrdS6dWu5uLjUam/dunWjx77V83bu3FkrVqxQVlaW5s6dq6FDh9oK6WreB+nauxH++9//VpcuXRr8TjTmPfuxn+bQqtWVv0+tudfG5Ovt7a2SkhI5OTnJzc2tToyPj49yc3MbnBsAAAAAAADQErDjGwAAAAAAaFadOnWSJFvRTnNydHSUh4eHKioqVFJSUud6zRGnfn5+1439sdjYWM2cOVOjR49Wbm6uqqurZZqm5s2bJ0kyTbPJOScmJsrDw0OrVq1SSEhInR3NWrpWrVrphx9+qNP+00KxW8XJyUmzZs2SaZqaPHmyrd3R0VHt27dXmzZtdOnSJdsucT/9PPbYY5Ia/k405j1rjMbk6+joKHd3d1VUVKi0tLTOWIWFhc2WFwAAAAAAAHC7oPANAAAAAAA0q/vvv1+SbEcwNpc2bdro6NGjevrppyVJmzZtqnW9srJS27dvl7Ozs+24x5rYjz76qM54vXv31iuvvKLLly9rz5498vPzU1JSkry9vWUYhiSpvLz8hvP28PBQamqqPDw8NG3atBse73bTqVMnnTlzplZbfn6+/vOf/9gpI2no0KHq3bu3tm/frq1bt9rahwwZoqqqKu3Zs6dOn9mzZ+uuu+5SVVVVo9+JhrxnTdHQfKX/O2a15sjTGgUFBcrJyWnS/AAAAAAAAMDtjMI3AAAAAADQrEJCQuTj46NDhw7dlPHfeOMNdevWTSkpKdq4caNKSkqUm5urhIQE5eXlyWq12o48rYl95ZVXtGnTJpWUlOj06dMaN26c8vLy9Morr6h169aKiIhQfn6+5s6dq4KCApWXl2vHjh1asmRJs+Q8ffp0FRUV6ZFHHmmW8W4njz/+uM6ePau3335bpaWlOn78uJKTk+Xj42O3nAzD0Ouvvy5Jmjx5sm13tjfeeEPdu3fXSy+9pM2bN+vixYsqLCzU0qVL9cc//lFpaWlq06ZNo9+JhrxnTdHQfCVp1qxZ8vT0VEpKirZu3arS0lIdOXJEI0aMqPf4UwAAAAAAAKClo/ANAAAAAAA0K8MwNGrUKO3bt09nz569brybm5t69+4tSVq/fr0Mw6j3c/nyZUlXjjHdv3+/hg8frqSkJHl5ealPnz4qKyvTtm3bNHr0aNvYNbHDhg1TYmKiLfa7777Trl27dNddd0mS1qxZo7Fjx2rhwoXy9/dXt27dtHLlSiUkJEiSoqOjFRoaqrS0NBmGoUOHDunMmTMyDMO2i1vNfZSVlckwDMXExFx3nfr37y9Jeu+992QYht5++21lZGTIMAytX79ekuTs7KwRI0YoMzOzTnvN3IZhaPbs2ZKu7DBmsVgaPU5WVpYMw9DHH3+sy5cvyzAM/fnPf9bu3btlGIY+/fRT273NmDHDdh+vv/66Ro0apVmzZsnHx0cvvPCCJk6cKD8/P124cEGGYWjy5MnNOm9970x8fHyt9X3yySfVr18/ffHFF2rVqpX69esnHx8f/fOf/9TgwYM1fvx4eXt7KyAgQP/4xz+0fv16Pfvss7b+DX0nGvqeNfb5SWpUvt27d9fevXsVFhamZ555xvYsEhMTFRwcrMrKSttvEwAAAAAAALgTGGbNn7wCAAAAAHAb6tOnjyIiIjRnzhxb2+zZs7V06VKdOHHCjpnhWi5evKigoCBZLJZm2zUNAH6OvL299dprr2ncuHG2tpdfflm5ubnavn27HTMDAAAAAACwL3Z8AwAAAAAAzc7Dw0Mffvih1q5dq0WLFtk7HQAAAAAAAADAHYbCNwAAAAAAcFP07t1bWVlZ2rx5s4qLi+2dDgAAAAAAAADgDtLG3gkAAAAAAIA71913362NGzfaOw0AAAAAAAAAwB2GHd8AAAAAAAAAAAAAAAAAAC0KhW8AAAAAAAAAAAAAAAAAgBaFwjcAAAAAAIAWJD09XYZhyDAMOTk5Nbr/yZMn9dRTT6m4uFiSdOzYMRmGofT09EaNk5aWZsujS5cujc7jVvjuu++0ZMkSRUZGytPTU87Ozrr33nv13HPP6dChQ3Xim7oWAAAAAAAAAG49Ct8AAAAAAABakPj4eJmmqaioqEb3PXjwoEJDQ/X444+rXbt2N5THhAkTZJqmQkJCbmicm2nixIlKTExUXFycjhw5ogsXLuivf/2rDh48qAcffFAZGRn2ThEAAAAAAABAE1H4BgAAAAAA8DNQXFys2NhY/frXv9b48ePtnc4t89JLLyk5OVl+fn5ycXFR//79tWrVKl2+fFmvvvqqvdMDAAAAAAAA0ERt7J0AAAAAAAAAbr45c+YoPz9f06dPt3cqt8yyZcvqbQ8JCZGzs7OOHz8u0zRlGMYtzgwAAAAAAADAjWLHNwAAAAAAgDucaZpatmyZHnroIfn7+9s7HbsrKytTeXm57r//foreAAAAAAAAgBaKwjcAAAAAAIAbUFVVpTVr1ig6Olp+fn5ydnZWcHCwrFarqqurbXEZGRkyDMP2+fbbbzVs2DC1b99eXl5eslgsOn78eJ3xjx49qsGDB8vDw0Ourq7q37+/du/e3agcDx06pHPnzikkJKTOtXvuuUemaSo+Pt7WVllZqenTpysgIEAuLi7y9PRUbGysNmzYoMuXLzdozv/+979KSkrS3XffLQcHB3l7e2vIkCE6ePBgk2LT0tJsa9elSxft379fUVFRcnd3l4uLix577DHt2bOnQbl98MEHkqTf/e53110LAAAAAAAAALcnCt8AAAAAAABuwJYtWxQfH6/IyEhlZ2fr1KlTGjNmjFJTUzVp0iRb3ODBg2WapuLi4iRJKSkpSklJ0ZkzZ7RmzRp98sknGj58eK2xjx07pvDwcGVlZWnt2rU6d+6cFi9erJkzZ9ZbJHc1X331lSSpS5cuDYofP368FixYoIULF+rChQvKzs5WQECA4uLitGvXruv2z8vLU1hYmN5//30tXrxYhYWF2rlzpwoLCxUeHq69e/c2OnbChAkyTVMhISEqKipScnKyXn/9deXn5+uzzz5TYWGhIiMj9emnn14zt3Pnzmny5MkaNWqUnn322QatBwAAAAAAAIDbD4VvAAAAAAAANygiIkJTpkxRhw4d1LFjRyUmJiohIUFWq1XFxcX19hk1apTCw8Pl6uqqAQMGaNCgQdq/f78KCgpsMVOnTlVRUZGsVquio6Pl5uam4OBgLV++XHl5eQ3OrybWw8OjQfHbt29XUFCQoqOj5ezsLF9fX82dO1c9evRoUP8pU6bo5MmTeuutt/Tkk0/Kzc1NQUFBSk9Pl2maSkxMbFJsjbKyMi1evNi2fqGhofr73/+uH374QcnJyVfN68KFC4qJiVFERISWLFnSoHsBAAAAAAAAcHui8A0AAAAAAOAGWCwW7dixo057SEiILl26pK+//rrefmFhYbW+d+3aVZJ09uxZW9uWLVskSU888UStWH9//wYXoUlSRUWFJKlt27YNio+JidHnn3+uMWPGKDMz03a8aU5OjiIiIq7bPyMjQ61atZLFYqnV7ufnp6CgIB04cECnT59udGwNV1dX9erVq1ZbcHCw/P39dejQoXqLAsvKyvTEE0/ol7/8pd577z21bt36uvcBAAAAAAAA4PZF4RsAAAAAAMANuHjxoqZPn67g4GB16NBBhmHIMAxNnDhRkvT999/X2++nu685ODhIkqqrqyVJlZWVKikpkZOTk9zc3Or09/HxaXCOTk5OkqRLly41KH7RokVauXKlTpw4oaioKLVr104xMTFat27ddftWVlbq4sWLqq6uloeHh209aj5ffPGFJOnf//53o2J/rH379vXOXbMm58+fr9VeVVWloUOHqnPnzvrb3/5G0RsAAAAAAABwB6DwDQAAAAAA4AbExsZq5syZGj16tHJzc1VdXS3TNDVv3jxJkmmaTRrX0dFR7u7uqqioUGlpaZ3rhYWFDR6rU6dOkq4U6TWEYRh6/vnntW3bNhUVFSkjI0OmaWrIkCF66623rpt3+/bt1aZNG126dEmmadb7eeyxxxoV+2MXLlyod11rCt5+WhQ4duxYVVZW6v3331ebNm1s7ffcc48yMzMbtCYAAAAAAAAAbi8UvgEAAAAAADTR5cuXtWfPHvn5+SkpKUne3t4yDEOSVF5efsPjDxw4UNL/HXlao6CgQDk5OQ0e5/7775ekOkeGXk379u119OhRSVeOR42OjlZGRoYMw9CmTZuu23/IkCGqqqrSnj176lybPXu27rrrLlVVVTU6tkZFRYX2799fq+1f//qXzp49q5CQEFuhnyTNmDFDX3/9tdavXy9HR8fr3zwAAAAAAACAFoHCNwAAAAAAgCZq3bq1IiIilJ+fr7lz56qgoEDl5eXasWOHlixZcsPjz5o1S56enkpJSdHWrVtVWlqqI0eOaMSIEfUef3o1ISEh8vHx0aFDhxrc57e//a0OHz6syspKnT9/XnPmzJFpmoqMjLxu3zfeeEPdu3fXSy+9pM2bN+vixYsqLCzU0qVL9cc//lFpaWm2ndcaE1vDw8NDU6dO1d69e1VWVqasrCyNGDFCDg4OslqttrgVK1botdde0759++Tu7l7nKNXjx483eD0AAAAAAAAA3F4ofAMAAAAAALgBa9as0dixY7Vw4UL5+/urW7duWrlypRISEiRJ0dHRCg0NVWZmpgzD0Pr16yVJzs7OmjZtmqQrR4vOnj1bktS7d29ZLBZJUvfu3bV3716FhYXpmWeekY+Pj1544QUlJiYqODhYlZWVMgxDo0aNumaONTH79u3T2bNnr3tPn376qQICAhQfHy9PT08FBgZqy5YtevfddzV16lRJUlpamgzD0KFDh3TmzBkZhmG7Hx8fH/3zn//U4MGDNX78eHl7eysgIED/+Mc/tH79ej377LO2uRoTW8PNzU0LFy7Ua6+9pk6dOunRRx9Vhw4d9Mknn+hXv/qVLW7t2rXXvVcAAAAAAAAALZNhmqZp7yQAAAAAALiaPn36KCIiQnPmzLG1zZ49W0uXLtWJEyfsmBnQsly8eFFBQUGyWCzNshudvfTq1UsFBQUNPrYVaOm8vb312muvady4cba2l19+Wbm5udq+fbsdMwMAAAAAALAvdnwDAAAAAAD4GfDw8NCHH36otWvXatGiRfZOBwAAAAAAAABuCIVvAAAAAAAAPxO9e/dWVlaWNm/erOLiYnunAwAAAAAAAABNRuEbAAAAAADAz8jdd9+tjRs3ql27dvZOpVHS0tJkGIYOHTqkM2fOyDAMTZs2zd5pAQAAAAAAALCTNvZOAAAAAAAAALieCRMmaMKECfZOAwAAAAAAAMBtgh3fAAAAAAAAAAAAAAAAAAAtCoVvAAAAAADgjpCeni7DMGQYhpycnBrd/+TJk3rqqadUXFwsSTp27JgMw1B6enpzp3pdGRkZtnsxDEMVFRW3PAc0L3s802v9Juz5fgMAAAAAAADNgcI3AAAAAABwR4iPj5dpmoqKimp034MHDyo0NFSPP/642rVrd0N5lJaW6t5775XFYmnyGIMHD5ZpmoqLi7uhXHD7sMczvZHfBAAAAAAAAHC7o/ANAAAAAAD8rBUXFys2Nla//vWvNX78+BsezzRNVVdXq7q6uhmyaxw3Nzf169fvls8LAAAAAAAAALdaG3snAAAAAAAAYE9z5sxRfn6+pk+f3izjubu76/jx480yFgAAAAAAAACgfuz4BgAAAAAAfrZM09SyZcv00EMPyd/f397pAAAAAAAAAAAaiMI3AAAAAABwU1RVVWnNmjWKjo6Wn5+fnJ2dFRwcLKvVWusY0IyMDBmGYft8++23GjZsmNq3by8vLy9ZLJZ6d1A7evSoBg8eLA8PD7m6uqp///7avXt3o3I8dOiQzp07p5CQkDrX7rnnHpmmqfj4+HrzzMnJ0bPPPisvLy9b27Jly2rFVFRUXDVnFxcX9enTRxs3btSAAQNsfUaNGlUnl/z8/GuuSVpamgzDUFlZmfbs2WMbq02ba2/2X9PPMAx16dJF+/fvV1RUlNzd3eXi4qLHHntMe/bsqdPvwoULSk1NVffu3eXg4KAOHTpo4MCB2rFjR624yspKTZ8+XQEBAXJxcZGnp6diY2O1YcMGXb58uVbsf//7XyUlJenuu++Wg4ODvL29NWTIEB08ePCa99DQZ1NQUNCoeRr6/ta3Jo6OjurSpYsGDBigFStWqLy8vE789Z5pU9alMb+Jn77fAAAAAAAAQEtD4RsAAAAAALgptmzZovj4eEVGRio7O1unTp3SmDFjlJqaqkmTJtniBg8eLNM0FRcXJ0lKSUlRSkqKzpw5ozVr1uiTTz7R8OHDa4197NgxhYeHKysrS2vXrtW5c+e0ePFizZw5s1HHjH711VeSpC5dulw39qd5jh07VuPGjdOpU6eUmZmp1q1b14m5Vs7nz5/X8uXLZbVadfjwYTk6Otp2oPupH6/JBx98oF27dtVakwkTJsg0Tbm6uqpv374yTVOmaaqqquqa91TTLyQkREVFRUpOTtbrr7+u/Px8ffbZZyosLFRkZKQ+/fRTW5/8/HyFhYVp1apVslqtKigo0L59++Ti4qKoqKha+Y8fP14LFizQwoULdeHCBWVnZysgIEBxcXHatWuXLS4vL09hYWF6//33tXjxYhUWFmrnzp0qLCxUeHi49u7de8PPprHzNPT9/fGarF692rYmBw4cUEREhF588UUtXbq00c+0sfk2128CAAAAAAAAaCkofAMAAAAAADdNRESEpkyZog4dOqhjx45KTExUQkKCrFariouL6+0zatQohYeHy9XVVQMGDNCgQYO0f/9+245dkjR16lQVFRXJarUqOjpabm5uCg4O1vLly5WXl9fg/GpiPTw8Gn1vkyZNUkREhFxcXPTQQw+pqqpKHTt2vGp8fTkHBQVp1apVKisru+ZcP16TyMhIWSyWOmtyo8rKyrR48WLbPKGhofr73/+uH374QcnJyba4KVOm6JtvvtH8+fNlsVjUrl079ejRQ6tWrVKnTp2UlJSkc+fOSZK2b9+uoKAgRUdHy9nZWb6+vpo7d6569OhRa+4pU6bo5MmTeuutt/Tkk0/a1iY9PV2maSoxMbFR93K1Z9PYeRr6/tasidVqlcVikbu7u3x9fTVt2jTFxMTUm2NDnmlj8m2u3wQAAAAAAADQUlD4BgAAAAAAbgqLxVLn6EtJCgkJ0aVLl/T111/X2y8sLKzW965du0qSzp49a2vbsmWLJOmJJ56oFevv71+nqOpaao4ibdu2bYP71OjTp0+j4q+Ws7e3twICAq7Z96dr0rlzZ0m11+RGubq6qlevXrXagoOD5e/vr0OHDtmKp9atWydJGjRoUK1YR0dHRUVFqby8XB9//LEkKSYmRp9//rnGjBmjzMxM2/GmOTk5ioiIsPXNyMhQq1atZLFYao3p5+enoKAgHThwQKdPn27wvVzt2TRmnsa8vzVrMnDgwDrxmzdvVkpKSp32hjzTxuTbXL8JAAAAAAAAoKVoY+8EAAAAAADAnenixYt68803tW7dOp0+fVpFRUW1rn///ff19vvp7msODg6SpOrqaklSZWWlSkpK5OTkJDc3tzr9fXx8lJub26AcnZycJEmXLl1qUPyPubq6Njj2ejl36NDhmv1/uiatWl35W8aaNWkO7du3r7fdx8dHZ8+e1fnz5+Xp6amLFy/KyclJ7u7udWJ9fX0lXTn6U5IWLVqk8PBw/e1vf1NUVJQkqX///ho7dqyefvppSVfW5uLFi5KuvfPev//97wYdSSvV/2waO09D39+aca+2JldzvWfamHy9vb2b7TcBAAAAAAAAtBTs+AYAAAAAAG6K2NhYzZw5U6NHj1Zubq6qq6tlmqbmzZsnSTJNs0njOjo6yt3dXRUVFSotLa1zvbCwsMFjderUSZJsBUb/H3v3HVXVme9//HMURGxYAmKJY4uAiohRLBEDIokFgjEWdJKT6Bid5CpHjT9RJ+XMZEaDMSZHEyc6pp07k9hmIsGWi10R7AWVMmrM2FARCxYQZP/+yJUbctSA7Vjer7XOH+z93fv5nGc/LNdifd3P3fJrmU+ePHlHxjGZTLd87enTp6/7TK5l8/Lykpubmzw8PJSXl6fc3FyH2mtbnHp7exfneemll7RixQqdPXtWixYtkmEY6tOnj6ZNmybpp7mpXr26XFxcVFBQIMMwrvsJDQ295e92K+OUdv3+2pzci7x38ncCAAAAAAAAeFDQ+AYAAAAAAO64q1evKikpSd7e3oqJiZGnp2dxU9bly5dv+/7XtpS8tr3jNdnZ2crIyCj1fVq2bClJZdpG81bdKHNWVtYdextXpUqVdOXKleKffXx8NHv27FJdm5eXpy1btpQ4lpqaqmPHjikgIKC4SfDam9qWLFlSojY/P18rV66Uu7t78Xab1atXV3p6uqSftpMNDw/XokWLZDKZSlzfp08fFRYWKikpySFXXFycGjRooMLCwlJ9j5sp7ThlXb/X5mTp0qUO5wIDAzV69Oi7mle6c78TAAAAAAAAwIOCxjcAAAAAAHDHlS9fXiEhIcrKytL777+v7OxsXb58WatXr9ann3562/efNGmSatasqVGjRikxMVEXLlzQvn379OKLL153q8cbCQgIkJeXl3bt2nXbmX7N9TLv2bNHgwcPLn5D2u1q06aNMjMzdfjwYSUnJ+vgwYMKDg4u1bUeHh6aOHGikpOTdfHiRW3dulUvvviiKlSoIJvNVlw3efJkNWrUSKNGjdLixYuVm5urzMxMDRo0SMePH5fNZive8lSSfv/732v37t3Kz8/XyZMnNWXKFBmGoa5du5a4Z5MmTTRkyBAtW7ZM586dU05OjmbNmqU//elPmjp1qlxcXG57fko7TlnX77U5GT16tJYsWaLc3FwdOXJEr7/+uo4fP37LjW9lmZc79TsBAAAAAAAAPChofAMAAAAAAHfFvHnzNHz4cM2YMUN169ZVo0aNZLfbNWjQIElSeHi42rZtq5SUFJlMJsXHx0uS3N3d9eabb0r6aavMuLg4ST+9OSsiIkKS1KRJEyUnJ6tdu3bq27evvLy89Morr2jkyJHy9/dXfn6+TCaThg4detOM12o2bdqkY8eO3bT2ejl/ubXotbeZ/bzmxRdfvG7m2rVra/jw4ZowYYIaNWqk8uXL33SsX5sTSfroo4/UqlUr+fn5acCAAbLZbPLz87vp97qmSpUqmjFjhv74xz+qTp066tKli2rUqKFVq1bp6aefLq7z9vbWli1bNHDgQMXExKhWrVoKCgrSxYsXtWLFCr366qvFtWvXrpWvr6+io6NVs2ZN+fn5afny5frb3/6miRMnFtd5eXlp8+bN6t27t0aMGCFPT0/5+vrqX//6l+Lj49W/f//bfjZlHae06/fnczJgwACNHDmyeE7OnDmj9evXq0GDBrf0TMuS9079TgAAAAAAAAAPCpNhGIazQwAAAAAAcCNBQUEKCQnRlClTio/FxcVp1qxZOnjwoBOT4WFx7tw5tWjRQhEREXfkbXS3wtfXV5cvX9aPP/7olPFbt26t7Ozse7LlK4Cy8fT01B//+Ee9/vrrxcdee+01ZWZmauXKlU5MBgAAAAAA4Fy88Q0AAAAAADzSPDw8lJCQoIULF+qTTz65a+NkZWWpZs2aKigoKHH80KFDOnDgQImtPwEAAAAAAAAAN0fjGwAAAAAAeOQFBgZq69atWrZsmc6fP3/Xxjlz5oyGDx+uw4cP69KlS9q8ebMGDBigatWq6a233rpr4wIAAAAAAADAw4bGNwAAAAAAAEkNGzbU4sWLVa1atbtyf29vb61YsUJnz55Vly5dVKNGDT333HN64okntHnzZjVu3PiujHszU6dOlclk0q5du3T06FGZTCa9+eab9zwHAAAAAAAAAJSVi7MDAAAAAAAAPCrCwsIUFhbm7BjFxo4dq7Fjxzo7BgAAAAAAAACUGW98AwAAAAAAAAAAAAAAAAA8UGh8AwAAAAAAD725c+fKZDLJZDKpYsWKZb7+xx9/1HPPPafz589Lkvbv3y+TyaS5c+dK+r8tQ00mk+rXr3/beefNm6fWrVvL3d29+L579uy57fvi7lm0aFHxszKZTMrLy7vrY95sXf9yjQIAAAAAAAAPGxrfAAAAAADAQy86OlqGYdzSNqM7d+5U27Zt9cwzz6hatWrXrRk7dqwMw1BAQMDtRlVSUpIGDhyoZ555RqdOndL+/fvvSDMd7q7evXvLMAxFRUXdszFvZ10DAAAAAAAADzoXZwcAAAAAAAC4X50/f16RkZF64YUXNGLEiHsy5oIFC2QYhiwWi6pUqaIqVaro8OHDkqQqVaqodevW2rBhwz3JAgAAAAAAAAD3K974BgAAAAAAcANTpkxRVlaW3n777Xs25rUmt1q1at2zMQEAAAAAAADgQUPjGwAAAAAAwHUYhqE5c+aoffv2qlu37j0b9+rVq/dsLAAAAAAAAAB4UNH4BgAAAAAA7rnCwkLNmzdP4eHh8vb2lru7u/z9/WWz2VRUVFRct2jRIplMpuLPoUOHNGDAAFWvXl21atVSRESEDhw44HD/9PR09e7dWx4eHqpcubKCg4PLvD3orl27dOLECQUEBDica9q0qQzDUHR0dKnuderUKcXExKhhw4aqUKGCPD091adPH+3cudPhu8bHx0uS3N3dZTKZ1KFDB02dOlUmk0kXL15UUlJS8Xy4uLjcdNxr162B8wwAACAASURBVJlMJtWvX19btmxRWFiYqlatqkqVKik0NFRJSUkO150+fVpjxoxRkyZNVKFCBdWoUUM9evTQ6tWrS9Tl5+fr7bfflq+vrypVqqSaNWsqMjJS3333nUMDX2nm4EZ+uQ4yMjLUv39/1apVq/hYdnZ2mcYp7Rq83py4ubmpfv366tatm7788ktdvnzZoT4rK6tUa7Us81KWdV3WNQoAAAAAAAA8aGh8AwAAAAAA99zy5csVHR2trl27Ki0tTYcPH9awYcM0ZswYxcbGFtf17t1bhmEoKipKkjRq1CiNGjVKR48e1bx587Rq1SoNHDiwxL3379+vjh07auvWrVq4cKFOnDihmTNn6t13371u49GN7NmzR5JUv3792/qux48fV7t27TR//nzNnDlTOTk5WrNmjXJyctSxY0clJydf97tevnxZhmEoJSVFY8eOlWEYqly5sp566ikZhiHDMFRYWHjTsa9dFxAQoLNnz8pisejPf/6zsrKytG7dOuXk5Khr165au3Zt8TVZWVlq166dvv76a9lsNmVnZ2vTpk2qVKmSwsLCNGfOnOLaESNGaPr06ZoxY4ZOnz6ttLQ0+fr6KioqSuvXry/zHNzIL+dm+PDhev3113X48GGlpKSofPnyZR6ntGvw53PyzTffFM/Jtm3bFBISosGDB2vWrFkOmX++VhcsWKD169c7rNWy5L1T6xoAAAAAAAB4WND4BgAAAAAAnCIkJEQTJkxQjRo19Nhjj2nkyJEaNGiQbDabzp8/f91rhg4dqo4dO6py5crq1q2bevXqpS1bthS/7UuSJk6cqLNnz8pmsyk8PFxVqlSRv7+/vvjiCx0/frzU+a7Venh43Nb3nDBhgn788UdNmzZNPXv2VJUqVdSiRQvNnTtXhmFo5MiRt3X/0rp48aJmzpxZPH9t27bV3//+d125ckUWi6VE3h9++EEfffSRIiIiVK1aNTVr1kxff/216tSpo5iYGJ04cUKStHLlSrVo0ULh4eFyd3dX7dq19f7776tZs2Z3dQ5iY2MVEhKiSpUqqX379iosLNRjjz1W5nFKuwavzYnNZlNERISqVq2q2rVr680331T37t2vm/Hna7Vr166KiIhwWKtlyXun1jUAAAAAAADwsKDxDQAAAAAA3HMREREO22ZKUkBAgAoKCrR3797rXteuXbsSPz/++OOSpGPHjhUfW758uSTp2WefLVFbt25dh4asm8nLy5Mkubq6lvqa61m0aJHKlSuniIiIEse9vb3VokULbdu2TUeOHLmtMUqjcuXKat26dYlj/v7+qlu3rnbt2lXcPPXtt99Kknr16lWi1s3NTWFhYbp8+bK+//57SVL37t21ceNGDRs2TCkpKcXbm2ZkZCgkJKT42js9B0FBQdc9XpZxyrIGr81Jjx49HOqXLVumUaNGORz/5VqtV6+epJJrtSx579S6BgAAAAAAAB4WLs4OAAAAAAAAHj3nzp3TBx98oG+//VZHjhzR2bNnS5y/dOnSda/75dvXKlSoIEkqKiqSJOXn5ys3N1cVK1ZUlSpVHK738vJSZmZmqTJWrFhRklRQUFCq+uvJz8/XuXPnrpv95/7973/f9paqv6Z69erXPe7l5aVjx47p5MmTqlmzps6dO6eKFSuqatWqDrW1a9eW9NPWn5L0ySefqGPHjvrqq68UFhYmSQoODtbw4cP1/PPPS7o7c1C5cmWHY2Udp7Rr8Np9bzQnN/LLDOXK/fT/T3++Vkub19PT846tawAAAAAAAOBhwRvfAAAAAADAPRcZGal3331Xr776qjIzM1VUVCTDMPThhx9KkgzDuKX7urm5qWrVqsrLy9OFCxcczufk5JT6XnXq1JGk4uakW81TvXp1ubi4qKCgQIZhXPcTGhpaqvuZTKZbznL69OnrzuvJkycl/dQ85ebmJg8PD+Xl5Sk3N9eh9toWp97e3sV5XnrpJa1YsUJnz57VokWLZBiG+vTpo2nTpkm683NwI2Udp7Rr8Nfm5F7kvZPrGgAAAAAAAHhY0PgGAAAAAADuqatXryopKUne3t6KiYmRp6dncUPX5cuXb/v+17ajvLY15DXZ2dnKyMgo9X1atmwpSbe9DWmfPn1UWFiopKQkh3NxcXFq0KCBCgsLS3WvSpUq6cqVK8U/+/j4aPbs2aW6Ni8vT1u2bClxLDU1VceOHVNAQEBxo9+1N7UtWbKkRG1+fr5Wrlwpd3f34u02q1evrvT0dEk/bQkbHh6uRYsWyWQylbj+Ts7BzZR2nLKuwWtzsnTpUodzgYGBGj169F3NK925dQ0AAAAAAAA8LGh8AwAAAAAA91T58uUVEhKirKwsvf/++8rOztbly5e1evVqffrpp7d9/0mTJqlmzZoaNWqUEhMTdeHCBe3bt08vvvjidbeJvJGAgAB5eXlp165dt5Vn8uTJatKkiYYMGaJly5bp3LlzysnJ0axZs/SnP/1JU6dOlYuLS6nu1aZNG2VmZurw4cNKTk7WwYMHFRwcXKprPTw8NHHiRCUnJ+vixYvaunWrXnzxRVWoUEE2m61E3kaNGmnUqFFavHixcnNzlZmZqUGDBun48eOy2WzFW55K0u9//3vt3r1b+fn5OnnypKZMmSLDMNS1a9e7Mgc3U9pxyroGr83J6NGjtWTJEuXm5urIkSN6/fXXdfz48VtufCvLvNypdQ0AAAAAAAA8LGh8AwAAAAA8cFxcXHTkyBG9/fbbunTpkrPj4BbMmzdPw4cP14wZM1S3bl01atRIdrtdgwYNkiSFh4erbdu2SklJkclkUnx8vCTJ3d1db775pqSfttmMi4uT9NNbtyIiIiRJTZo0UXJystq1a6e+ffvKy8tLr7zyikaOHCl/f3/l5+fLZDJp6NChN814rWbTpk06duzYTWunTp0qk8mkXbt26ejRozKZTMU5vby8tHnzZvXu3VsjRoyQp6enfH199a9//Uvx8fHq37+/JBW/Ke3n39VkMiklJaV4nI8++kitWrWSn5+fBgwYIJvNJj8/v1LNeZUqVTRjxgz98Y9/VJ06ddSlSxfVqFFDq1at0tNPP11c5+3trS1btmjgwIGKiYlRrVq1FBQUpIsXL2rFihV69dVXi2vXrl0rX19fRUdHq2bNmvLz89Py5cv1t7/9TRMnTiyuK+0c3Mj11sH1tn0tyzilXYM/n5MBAwZo5MiRxXNy5swZrV+/Xg0aNLiltVqWvHdqXePBkZubq9jYWJ05c+aONIYCAAAAAAA8bEyGYRjODgEAAAAAwI0EBQUpJCREU6ZMKT5WWFioTz75RO+8846qVKmiSZMm6aWXXrpuIwxwO86dO6cWLVooIiLijryNzllat26t7Ozs2962FcDdZxiGFi5cqDfeeEMXLlzQO++8oxEjRqh8+fLFNa+99poyMzO1cuVKJyYFAAAAAABwLt74BgAAAAB44Li4uMhisejAgQN64YUXNHjwYIWGhmr37t3OjoaHjIeHhxISErRw4UJ98sknzo4D4CG3Y8cOBQcHKzo6WiEhIcrIyJDFYinR9AYAAAAAAICf0PgGAAAAALivmUwmffvtt9d9q02tWrVks9m0efNmFRQUKDAwUGazWdnZ2U5IiodVYGCgtm7dqmXLlun8+fPOjgPgIZSTkyOLxaJ27dqpoKBAycnJstvt8vT0dKhdunSpli1bxltOAQAAAADAI4/GNwAAAADAfW3hwoXq2LGjunXrpsjISP3www8ONU8++aQ2bNigL774Qv/zP/8jHx8f2Ww2Xb161QmJ8TBq2LChFi9erGrVqjk7SplMnTpVJpNJu3bt0tGjR2UymfTmm286OxaA/1VYWKjZs2fLx8dHCxcu1Oeff66UlBQFBQU51O7fv1/9+/dXr1695O/vrzlz5jghMQAAAAAAwP3DZBiG4ewQAAAAAAD8mlWrVikmJkYHDx5UTEyM3nzzTVWpUsWh7uLFi3r//fc1efJktWjRQtOnT1fnzp2dkBgAgBtbu3atYmJilJaWptdee01//vOfVbVqVYe6S5cuacqUKYqLi1PDhg310Ucf6dlnn3VCYgAAAAAAgPsLb3wDAAAAADwQunbtqh07dmjy5Mn661//Kj8/P9ntdoe6ypUry2q1KjU1Vd7e3urSpYv69++v//znP05IDQBASUePHpXZbFZoaKi8vLy0a9cu2Wy26za9JSQkyM/PTzabTe+9955SU1NpegMAAAAAAPhfNL4BAAAAAB4Yrq6uslgsysjIUM+ePTV48GCFhoYqNTXVobZZs2ZaunSp4uPjtXXrVjVv3lxWq1X5+flOSI4Hwdy5c2UymWQymVSxYsVSXbN//36ZTCbNnTu3+FiVKlWK7/PzT7ly5eTp6anevXtry5Ytd+trlNmN8l6bh1atWumTTz7R/bRpwKJFi0rkzMvLu+tj3mx9XG8djB8/XvPmzbvuve7GOdz/rly5IpvNJl9fXyUnJ+u7775TYmKi/Pz8HGp37typLl26qHfv3nr66aeVkZEhi8UiFxcXJyQHAAAAAAC4P9H4BgAAAAB44Hh7e2vWrFnatGmT8vPz1aZNGw0fPlynT592qI2MjNTevXv11ltv6YMPPpC/v7+WLFnihNS430VHR8swDIWFhd3WfS5cuKAdO3ZIkqKiomQYhgzD0JkzZzR79mwlJyfrqaee0ooVK+5E7Nt2o7z5+flKSUlRtWrVNGLECMXGxjo56f/p3bu3DMNQVFTUPRuzrOvj1Vdf1YQJE/TWW2/dk3O4v117c9sf/vAHvfHGG9qzZ48iIiIc6s6cOSOLxaK2bdsqLy9PSUlJstvt8vLyckJqAAAAAACA+xuNbwAAAACAB1bbtm2VlJSkzz77TPHx8WrWrJlsNpuuXr1aos7d3V2xsbFKT09Xhw4dFBkZqfDwcKWlpTkpOR5FHh4eev755zVt2jQVFBRo1KhRzo50UxUqVFDr1q31zTffqFy5cvrwww+Vk5Pj7FgPjCZNmujbb7/VX/7yF82fP/+un8P9KTMzU7169VJUVJSefPJJ7du3T1arVW5ubiXqioqKZLfb5ePjowULFmjmzJlKSUlRhw4dnJQcAAAAAADg/kfjGwAAAADggWYymWQ2m5Wenq5XX31V48aNU1BQkJKSkhxq69WrJ7vdrlWrVunEiRMKCAiQxWJRbm6uE5LjURUaGipJ2rt3r86ePevkNL/u8ccfV506dVRYWKhdu3Y5O84DJSAgQH379tUbb7yhwsLCu34O94+LFy/KarWqVatWOn78uNatW6f58+erQYMGDrXr1q1TmzZtNHToUA0cOFDp6ekaNmyYypXjT7cAAAAAAAA3w19PAAAAAAAPherVq+u9997T7t275eXlpeDgYJnNZmVlZTnUhoSEaPv27fr444/19ddfy9fXV3a7XYZhOCE5HjU/X2cmk8mJSUrvWuaKFSs6OcmD5/nnn9eRI0euu8Xy3TgH5zIMQ3a7XU2bNtWMGTMUFxenLVu2qHPnzg61x44dk9lsVkhIiB577DHt3LlTNptN1apVc0JyAAAAAACABw+NbwAAAACAh4qPj4+WLVum+Ph4bdiwQU2bNpXValV+fn6JOhcXFw0bNkwZGRnq27evhgwZog4dOmjz5s1OSo5fKiws1Lx58xQeHi5vb2+5u7vL399fNptNRUVFxXWLFi2SyWQq/hw6dEgDBgxQ9erVVatWLUVEROjAgQMO909PT1fv3r3l4eGhypUrKzg4WBs2bChTxqZNm8owDEVHR5f6mjVr1kiSWrRoIQ8PD0nS6dOnNWbMGDVp0kQVKlRQjRo11KNHD61evbrEtfn5+Xr77bfl6+urSpUqqWbNmoqMjNR3333nsMXvqVOnFBMTo4YNG6pChQry9PRUnz59tHPnzjJ9x//85z86fvy4qlWrphYtWtzSGKV9ltf8fD7c3NxUv359devWTV9++aUuX77sUJ+VlVWqZ16WOSnL+rjZOmjdurUk6fvvv78n5+A827dvV+fOnTV48GCFh4crIyNDFotF5cuXL1FXUFAgm80mX19fbdy4UfPmzdOKFSvUvHlzJyUHAAAAAAB4MNH4BgAAAAB4KEVGRmrv3r1666239MEHH8jf319Lly51qKtZs6ZsNps2b94sV1dXdezYUWazWadOnXJCavzc8uXLFR0dra5duyotLU2HDx/WsGHDNGbMGMXGxhbX9e7dW4ZhKCoqSpI0atQojRo1SkePHtW8efO0atUqDRw4sMS99+/fr44dO2rr1q1auHChTpw4oZkzZ+rdd9+9bsPUnXD+/Hl9++23GjNmjFxdXfXRRx9J+qlpq127dvr6669ls9mUnZ2tTZs2qVKlSgoLC9OcOXOK7zFixAhNnz5dM2bM0OnTp5WWliZfX19FRUVp/fr1xXXHjx9Xu3btNH/+fM2cOVM5OTlas2aNcnJy1LFjRyUnJ/9q3oKCAu3cuVODBg2Sq6urPv744xJvoirLGKV9lj+fj2+++aZ4PrZt26aQkBANHjxYs2bNcsj682e+YMECrV+/3uGZlyXvnVwf9erVkyTt2bPnnpzDvXf69GlZLBYFBQXJ1dVVO3bskN1u12OPPeZQu2LFCrVq1UoTJ07UmDFjtGfPHvXr188JqQEAAAAAAB4CBgAAAAAAD7nDhw8bL730kiHJiIiIMA4cOHDduqKiImP+/PnG448/btSoUcP46KOPjMLCwnucFtckJCQYISEhDsdffPFFw9XV1Th37lyJ41FRUYYkIyEhocTxvn37GpKMU6dOFR/r16+fIclYuHBhidqjR48abm5uhpub221l37FjhyGpxMdkMhm1atUynnvuOWPz5s3Fta+88oohyfjmm29K3CMvL8+oW7eu4e7ubmRlZRmGYRiNGjUyOnXq5DBes2bNjNWrVxf//PLLLxuSjH/84x8l6o4fP264ubkZTz755K/mvfZ5/vnnjf379zuMWZYxyvIsr83HvHnzHOq7d+9ufPjhh8U/3+iZDxo0yOGZlyXvnV4fJpPJaNq06T07h3ujoKDA+OijjwwPDw+jXr16xldffWUUFRVdtzYzM9Po1atX8b9Dhw4dusdpAQAAAAAAHj688Q0AAAAA8NCrX7++7Ha7Vq1apUOHDsnPz08Wi0W5ubkl6kwmk/r166e0tDTFxMQoNjZWbdu2LfEmLdw7ERERDlt9SlJAQIAKCgq0d+/e617Xrl27Ej8//vjjkqRjx44VH1u+fLkk6dlnny1RW7duXTVr1uy2cv9cVFSUDMOQYRgqKipSdna24uPjS2T89ttvJUm9evUqca2bm5vCwsJ0+fLl4i0tu3fvro0bN2rYsGFKSUkp3t40IyNDISEhxdcuWrRI5cqVU0RERIl7ent7q0WLFtq2bZuOHDly07xHjhzRgAED9O2332r27NkOtWUZoyzP8tp89OjRw6F+2bJlGjVqlMPxXz7za29E+/kzL0veO70+XFxcrrtF6906h7tv9erVCgwM1Lhx4/Tyyy8rLS1NZrNZJpOpRN3FixdltVrl7++vo0ePat26dUpISNBvfvMbJyUHAAAAAAB4eND4BgAAAAB4ZISGhmrHjh2aMmWKvvrqK/n5+clut8swjBJ1lStXltVqVWpqqurVq6cuXbooMjJSP/74o5OSP5rOnTunt99+W/7+/qpRo4ZMJpNMJpP+3//7f5KkS5cuXfc6Dw+PEj9XqFBBklRUVCRJys/PV25uripWrKgqVao4XO/l5XUnv8ZN5efn69y5c6pYsaKqVq3qcL527dqSftr+U5I++eQT2e12HTx4UGFhYapWrZq6d+9e3Cz283sWFRXJw8OjeN6ufbZv3y5J+ve//33TbPXq1dOXX36pJk2a6P3339fWrVtveYzSPstfm48b+eUzL1fupz95/fyZlzbv3VgfhYWFcnd3v2fncPccOXJEZrNZXbt2VcOGDZWWliabzeawXg3D0IIFC+Tn56fp06crLi5OW7duVXBwsJOSAwAAAAAAPHxofAMAAAAAPFJcXFxksVh04MABvfDCCxoyZIhCQ0O1e/duh9onnnhCixcv1nfffae0tDQ1b95cVqtVeXl5Tkj+6ImMjNS7776rV199VZmZmSoqKpJhGPrwww8lyaFhsbTc3NxUtWpV5eXl6cKFCw7nc3Jybit3WbN4eHgoLy/P4Q2EknTixAlJP72VTPrprYQvvfSSVqxYobNnz2rRokUyDEN9+vTRtGnTiu9ZvXp1ubi4qKCgoPgNbr/8hIaG/mq+ihUratKkSTIMQ+PHjy+RuyxjlPZZ/tp83Kqy5L3T6+P8+fMyDEN16tS5J+dwd1y+fFlxcXHy8/NTSkqKlixZooSEBDVu3Nihdvv27QoODlZ0dLRCQkKUkZEhi8Wi8uXLOyE5AAAAAADAw4vGNwAAAADAI6lWrVqy2WzavHmzCgoKFBgYKLPZrOzsbIfayMhIpaWladKkSZo2bZpatmypBQsWOCH1o+Pq1atKSkqSt7e3YmJi5OnpWbyF4J3Y3vHaNprXtrS8Jjs7WxkZGbd9/7J4/vnnJUlLliwpcTw/P18rV66Uu7t78Zab1atXV3p6uiTJ1dVV4eHhWrRokUwmU4nr+/Tpo8LCQiUlJTmMFxcXpwYNGqiwsLBU+fr166fAwECtXLlSiYmJZR6jrM/y2nwsXbrU4VxgYKBGjx5dqty/VJY5uZPr4+jRo5Kkli1b3pNzuPMSEhLUokULvfvuu3rjjTeUmpqqnj17OtTl5OTIYrEoKChIBQUFSk5Olt1ul6enpxNSAwAAAAAAPPxofAMAAAAAPNLatGmjDRs26IsvvlBiYqJ8fHxks9l09erVEnWurq6yWCxKT09Xp06dNGDAAHXr1k379u1zUvKHW/ny5RUSEqKsrCy9//77ys7O1uXLl7V69Wp9+umnt33/SZMmqWbNmho1apQSExN14cIF7du3Ty+++OJ1t7e8myZPnqxGjRpp1KhRWrx4sXJzc5WZmalBgwbp+PHjstlsxVueStLvf/977d69W/n5+Tp58qSmTJkiwzDUtWvXEvds0qSJhgwZomXLluncuXPKycnRrFmz9Kc//UlTp06Vi4tLqfKZTCb9+c9/liSNHz+++O1spR2jrM/y2nyMHj1aS5YsUW5uro4cOaLXX39dx48fv+XGt7LMyZ1cHzt37pQkPfPMM/fkHO6cjIwM9ejRQ1FRUercubP2798vq9UqNze3EnWFhYWaPXu2fHx8tHDhQn3++edKSUlRUFCQk5IDAAAAAAA8IgwAAAAAAGAYhmFcuHDBeOeddww3NzcjMDDQWL9+/Q1r165dawQEBBiurq5GTEyMce7cuXuY9NFw6tQpY/jw4cbjjz9uuLq6GrVr1zZeeeUVY/z48YYkQ5Lx5JNPGsnJycU/X/v84Q9/MAzDcDjeq1ev4vtnZGQYvXv3NqpVq2a4u7sb7dq1MxYvXmyEhYUV1//ud78rc+7KlSs7jOvj43PTa7Kzs41Ro0YZjRo1MlxdXQ0PDw/j2WefNVauXFmibufOncbw4cMNPz8/o1KlSkbNmjWNDh06GH/729+MoqKiErWnT582xowZYzRu3NhwdXU1PD09jWeeecZITEz81bwDBgxwyNi5c+fi80899VSZxijts7zRfNSpU8eIjo42MjMzDcMwbvmZlzavYdy59dGvXz+jXr16xpUrV+7JOdy+M2fOGLGxsUaFChWMNm3aGBs2bLhh7erVqw1/f//ifwvOnz9/D5MCAAAAAAA82kyG8b//TRcAAAAAAEiSMjMzNXr0aC1btkx9+/bV1KlT1aBBA4e6oqIi/f3vf9fYsWPl4uIiq9WqoUOHqlw5XrAOQNq1a5cCAwP19ddfKzo6+q6fw+0xDEP//d//rXHjxqmgoEBvv/22RowYofLlyzvUHj16VBMmTNDf//53hYWFafr06fLz83NCagAAAAAAgEcXf4kHAAAAAOAXmjVrpiVLlig+Pl7btm1T8+bNZbValZ+fX6KuXLlyMpvNysjIUL9+/fT666+rQ4cOSklJcVJyAPeLgwcPqk+fPpowYYJDg9rdOIfbs3XrVj311FP63e9+p6ioKGVmZspisTg0vV2+fFlxcXHy9fVVcnKyEhISlJiYSNMbAAAAAACAE/DGNwAAAAAAbuLKlSv661//qjfffFPe3t768MMPFRERcd3anTt3KiYmRklJSfrtb3+rqVOnysvL6x4nBnA/iI2NVWBg4HUb1O7GOdyarKwsvfPOO5ozZ466dOmi6dOny9/f/7q1CQkJslgsOnnypMaOHasJEybIzc3tHicGAAAAAADANTS+AQAAAABQCmXZ1i4hIUEjRozQ+fPnZbVa9V//9V9ycXG5x4kBADdSUFCgmTNn6u2331a1atX0l7/8RWaz+bq1mZmZGjVqlJYvX37T7a8BAAAAAABwb7HVKQAAAAAApVCvXj3Z7XatXr1aJ0+eVEBAgCwWi3Jzcx1qIyMjlZaWJovFovHjx8vf31/ff/+9E1IDAH5p1apVCgwM1IQJE/Taa68pLS3tuk1vFy9elNVqlb+/v7KysrRu3TrNnz+fpjcAAAAAAID7BI1vAAAAAACUwdNPP61t27bp448/1tdffy1fX1/Z7Xb98oXqlSpVktVqVWpqqpo2baru3bsrMjJShw4dck5wAHjEHT58WGazWWFhYWrUqJH27t2r9957T1WqVClRZxiG7Ha7mjRpohkzZmjKlCnasmWLOnfu7KTkAAAAAAAAuB4a3wAAAAAAKCMXFxcNGzZMGRkZ6tu3r4YMGaIOHTpo8+bNDrVNmzZVQkKCEhMTdfDgQbVo0UJWq1V5eXlOSA4Aj55Lly7JarWqWbNm2rRpk5YuXaqEhAQ1atTIoXbbtm3q3LmzBg8erGeeeUYZGRmyWCwqX768E5IDAAAAAADgZmh8AwAAAADgFtWsWVM2m01btmyRP3RTZgAAGe9JREFUq6urOnbsKLPZrFOnTjnUduvWTTt37tSkSZP04YcfqlmzZrLb7U5IDQCPjoSEBDVv3lw2m634LZw9evRwqDt9+rQsFouCgoLk6uqqHTt2yG6367HHHnNCagAAAAAAAJQGjW8AAAAAANymwMBArV+/XnPnztWaNWvk4+Mjm82mq1evlqhzdXWVxWJRenq6QkJC9MorrygsLEx79+51UnIAeDilp6fr2WefVVRUlLp06aL09HTFxsaqQoUKJeoKCwtls9nUpEkT/fOf/9QXX3yh1atXq1WrVk5KDgAAAAAAgNKi8Q0AAAAAgDvAZDKpX79+SktLU0xMjGJjY+Xv76/ExESH2jp16shut2vTpk26ePGiAgMDZbFYdO7cOSckB4CHx5kzZ2SxWOTv76/Tp08rKSlJdrtdtWvXdqhdvXq1AgMDNW7cOL388stKT0+X2WyWyWRyQnIAAAAAAACUFY1vAAAAAADcQZUrVy7eTq9x48Z65plnFBkZqR9//NGhtl27dtq4caPmzJmjuXPnqkmTJrLZbCoqKnJCcgB4cBUVFclut8vX11f/+Mc/NHXqVG3evFkdO3Z0qD1y5IjMZrO6du2qhg0bKi0tTTabTVWqVHFCcgAAAAAAANwqGt8AAAAAALgLnnjiCS1evFiJiYk6cOCAmjdvLqvVqry8vBJ15cqVk9lsVnp6un77299q7NixCgoKUnJyspOSA8CDZcuWLerUqZOGDh2q6OhoHThwQBaLReXKlfzT5+XLl2W1WtWsWTNt2rRJS5YsUUJCgho3buyk5AAAAAAAALgdNL4BAAAAAHAXdevWTbt27dKkSZM0bdo0tWzZUgsWLHCoq1Gjhmw2m1JTU1WrVi099dRTMpvNOnHihBNSA8D97/jx4zKbzWrfvr0qV66s7du3y2azycPDw6E2ISFBzZs319SpUzVu3Djt3r1bPXv2dEJqAAAAAAAA3Ck0vgEAAAAAcJe5urrKYrEoPT1dnTp10oABA9StWzft3bvXodbX11fff/+94uPjtW7dOvn6+iouLk5XrlxxQnIAuP8UFBTIZrPJ19dXa9as0ZdffqmVK1eqZcuWDrUZGRnq3r27oqKiFBwcrP3798tqtcrNzc0JyQEAAAAAAHAn0fgGAAAAAMA9UrduXdntdq1Zs0bZ2dkKDAyUxWLR+fPnHWojIyO1b98+WSwWWa1WtWrVSsuXL3dCagC4f6xYsUKtW7fWhAkTNHr0aGVmZspsNjvUnT17VuPHj1erVq106tQpbdiwQXa7Xd7e3k5IDQAAAAAAgLuBxjcAAAAAAO6xLl26aPv27ZozZ46++eYb+fr6avbs2SoqKipRV6lSJVmtVmVmZiooKEg9evRQZGSkfvjhByclBwDn2L9/v/r376/w8HA1btxY+/btk9VqVcWKFUvUGYYhu90uHx8fzZkzR1OmTNHmzZvVqVMnJyUHAAAAAADA3ULjGwAAAAAATlCuXDmZzWZlZGSoX79+ev3119W+fXulpKQ41D7++OOy2+1asWKFfvjhB7Vo0ULjx4/XhQsXnJAcAO6dS5cuyWq1yt/fX6mpqVq+fLkSEhLUsGFDh9qtW7eqU6dO+t3vfqfevXsrIyNDFotF5cuXv/fBAQAAAAAAcNfR+AYAAAAAgBPVqFFDNptNW7dulbu7u5566imZzWadPHnSoTYsLEw7duzQ5MmT9de//lV+fn6y2+1OSA0Ad19CQoL8/Pxks9n03nvvKTU1Vc8++6xD3fHjxzV8+HC1b99e7u7u2r59u2bNmqVatWo5ITUAAAAAAADuFRrfAAAAAAC4D7Ru3Vrr1q3TokWLtHbtWvn4+CguLk5XrlwpUefq6iqLxaKMjAz17NlTgwcPVteuXZWamuqk5ABwZ+3cuVNdunRR79699fTTTxe/uc3FxaVEXUFBgWw2m3x9fbV06VJ98cUXWrVqlfz9/Z2UHAAAAAAAAPcSjW8AAAAAANxHIiMjlZaWJovFIqvVqlatWun77793qPP29tasWbO0adMmXb58WW3atNHw4cN1+vRpJ6QGgNt35swZWSwWtW3bVnl5eUpKSpLdbpeXl5dD7cqVKxUYGKgJEybotddeU1pamsxmsxNSAwAAAAAAwFlofAMAAAAA4D5TqVIlWa1WpaamqlWrVurevbsiIyN16NAhh9q2bdtq48aN+uyzzxQfHy8fHx/ZbDZdvXr13gcHgFtQVFQku90uHx8fLViwQDNnzlRKSoo6dOjgUHvgwAH1799f3bp1U6NGjbR371699957qlKlihOSAwAAAAAAwJlofAMAAAAA4D7VtGlTzZ8/X4mJiTp48KCaN28uq9WqvLy8EnUmk0lms1np6ekaOnSoxo0bp6CgIG3cuNFJyQGgdNatW6c2bdpo6NChGjhwoNLT0zVs2DCVK1fyz5aXLl2S1WpVy5YttXv3bi1btkwJCQlq1KiRk5IDAAAAAADA2Wh8AwAAAADgPtetWzft3LlTkydP1ocffqgnnnhCdrvdoa569ep67733tHv3bnl6eqpz584ym83KyspyQmoAuLFjx47JbDYrJCREjz32mHbu3CmbzaZq1ao51CYkJKh58+ay2WyyWq3avXu3unfv7oTUAAAAAAAAuJ/Q+AYAAAAAwAPA1dVVFotF6enpCg0N1SuvvKKwsDDt2bPHodbHx0fLly9XfHy81q9fr6ZNm8pqtSo/P98JyQHg/xQUFMhms8nX11cbN27UvHnztGLFCjVv3tyhNj09Xc8++6yioqLUpUsXpaenKzY2VhUqVHBCcgAAAAAAANxvaHwDAAAAAOABUqdOHdntdm3atEkXL15UYGCgLBaLzp0751AbGRmpffv26a233tIHH3ygVq1aaenSpU5IDQDSihUrFBAQoIkTJ2rMmDHas2eP+vXr51B35swZWSwW+fv7KycnR0lJSbLb7apdu7YTUgMAAAAAAOB+ReMbAAAAAAAPoHbt2mnjxo367LPPNHfuXDVp0kQ2m01FRUUl6tzd3RUbG6u0tDS1b99evXr1UmRkpA4ePOik5AAeNf/+978VERGh8PBwNWnSRPv27ZPValXFihVL1BUVFclut8vX11fz58/XJ598ok2bNqljx45OSg4AAAAAAID7GY1vAAAAAAA8oMqVKyez2ayMjAz99re/1dixYxUUFKTk5GSH2vr168tut2vVqlU6dOiQ/Pz8ZLFYlJub64TkAB4FFy9elNVqlb+/v44cOaJ169YpISFBv/nNbxxqt2zZok6dOmno0KGKjo5Wenq6hg0bpnLl+PMlAAAAAAAAro+/HAEAAAAA8ICrXr26bDabUlNTVatWLT311FMym806ceKEQ21oaKh27NihKVOm6KuvvpKfn5/sdrsMw3BCcgAPI8MwtGDBAvn5+Wn69OmKi4vTtm3bFBwc7FB77Ngxmc1mtW/fXpUrV9aOHTtks9nk4eHhhOQAAAAAAAB4kND4BgAAAADAQ8LX11fff/+94uPjtX79ejVt2lRWq1VXrlwpUefi4iKLxaIDBw7ohRde0JAhQxQaGqrdu3c7KTmAh8WOHTsUHBys6OhohYSEKCMjQxaLReXLly9RV1BQIJvNJj8/P61Zs0ZffvmlVq5cqRYtWjgpOQAAAAAAAB40NL4BAAAAAPCQiYyM1N69e/XGG28oLi5O/v7+WrZsmUNdrVq1ZLPZtGnTJhUUFCgwMFBms1nZ2dlOSA3gQZaTkyOLxaJ27dqpoKBAycnJstvt8vT0dKhdsWKFWrdurYkTJ2r06NHKzMyU2Wx2QmoAAAAAAAA8yGh8AwAAAADgIVSpUiVZrVZlZmaqffv26tmzpyIjI/XDDz841D755JPasGGDvvjiC/3P//yPfHx8ZLPZdPXqVSckB/AgKSws1OzZs+Xj46OFCxfq888/V0pKioKCghxq9+/fr8jISIWHh6tx48bau3evrFarKlas6ITkAAAAAAAAeNDR+AYAAAAAwEPs8ccfl91u18qVK/XDDz+oRYsWGj9+vC5cuFCizmQyyWw268CBAxo5cqTGjRundu3aacOGDU5KDuB+t3btWj355JMaMWKEBg0apPT0dJnNZplMphJ1ly5dktVqVcuWLbV//359//33SkhIUMOGDZ0THAAAAAAAAA8FGt8AAAAAAHgEdO3aVTt27NDkyZP16aefytfXV3a73aGucuXKslqtSk1Nlbe3t7p06aL+/fvrP//5jxNSA7gfHT16VGazWaGhofLy8tKuXbtks9lUtWpVh9qEhAT5+fnJZrMpLi5OqampeuaZZ5yQGgAAAAAAAA8bGt8AAAAAAHhEuLq6ymKxKD09Xb169dLgwYMVGhqq1NRUh9pmzZpp6dKlio+P17Zt29S8eXNZrVbl5+c7ITmA+8GVK1dks9nk6+ur5ORkfffdd0pMTJSfn59D7c6dOxUcHKzevXvr6aefVkZGhiwWi1xcXJyQHAAAAAAAAA8jGt8AAAAAAHjEeHt7a9asWdq0aZPy8/PVpk0bDR8+XNnZ2Q61kZGRSktL01/+8hd98MEHatmypRYvXuyE1ACc6dqb2/7whz/ojTfe0J49exQREeFQl5OTI4vForZt2yo/P18bN26U3W6Xl5eXE1IDAAAAAADgYUbjGwAAAAAAj6i2bdsqKSlJn332meLj4+Xj4yObzaarV6+WqKtQoULxm+I6duyo5557TuHh4UpLS3NScgD3SmZmpnr27KmoqCg9+eST2rdvn6xWq9zc3ErUFRUVyW63y9fXVwsWLNDnn3+uTZs2qX379k5KDgAAAAAAgIcdjW8AAAAAADzCTCaTzGaz0tPT9eqrr2rcuHEKCgpSUlKSQ229evVkt9u1atUqnTx5UgEBAbJYLMrNzXVCcgB308WLF2W1WtWqVStlZWVp3bp1mj9/vho0aOBQu3btWgUGBmro0KEaOHCg0tPTZTabZTKZnJAcAAAAAAAAjwoa3wAAAAAAgKpXr6733ntPu3fvlpeXl4KDg9W/f38dPnzYoTYkJETbtm3Txx9/rK+//lq+vr6y2+0yDMMJyQHcSYZhyG63q2nTppoxY4bi4uK0ZcsWde7c2aH22LFjMpvNCg0NlZeXl3bu3CmbzaZq1ao5ITkAAAAAAAAeNTS+AQAAAACAYj4+Plq2bJni4+O1detW+fn5yWq1Kj8/v0Sdi4uLhg0bpoyMDPXt21dDhgxRhw4dtHnzZiclB3C7tm3bps6dO2vw4MEKDw9XRkaGLBaLypcvX6LuypUrstls8vX1VXJysubNm6fExEQ1b97cSckBAAAAAADwKKLxDQAAAAAAOIiMjNTevXv11ltv6YMPPpC/v7+WLl3qUFezZk3ZbDZt3rxZrq6u6tixo8xms06dOuWE1ABuxenTp2WxWNS+fXu5urpqx44dstvteuyxxxxqExIS5Ofnp4kTJ2rMmDFKTU1Vv379nJAaAAAAAAAAjzoa3wAAAAAAwHW5u7srNjZWaWlp6tChg3r16qXIyEgdPHjQobZNmzZav3695s6dqzVr1sjHx0c2m01Xr151QnIApVFYWCibzaYmTZron//8pz7//HOtXr1arVq1cqj997//rV69eum5555T8+bNlZaWJqvVqooVKzohOQAAAAAAAEDjGwAAAAAA+BX169eX3W7XqlWr9OOPP8rPz08Wi0W5ubkl6kwmk/r166e0tDTFxMQoNjZWbdu21fr1652UHMCNrF69WoGBgRo3bpxefvllpaWlyWw2y2Qylai7ePGirFar/P39dezYMa1bt04JCQlq0KCBk5IDAAAAAAAAP6HxDQAAAAAAlEpoaKi2b9+uGTNm6B//+If8/Pxkt9tlGEaJusqVK8tqtSo1NVX16tVTly5dFBkZqR9//NFJyQFcc+TIEZnNZnXt2lUNGzZUWlqabDabqlatWqLOMAwtWLBAfn5+mj59uuLi4rR161YFBwc7KTkAAAAAAABQEo1vAAAAAACg1FxcXDRs2DBlZGTohRde0JAhQxQaGqrdu3c71D7xxBNavHixEhMTtX//fjVv3lxWq1V5eXlOSA482i5fvqy4uDj5+fkpJSVFS5YsUUJCgho3buxQu337dgUHBys6OlohISHKyMiQxWJR+fLlnZAcAAAAAAAAuD4a3wAAAAAAQJnVqlVLNptNmzdvVkFBgQIDA2U2m3Xq1CmH2m7dumn37t2aNGmSpk2bppYtW2rBggVOSA08mhISEtS8eXO9++67euONN5SamqqePXs61OXk5MhisSgoKEjly5fX9u3bZbfb5enp6YTUAAAAAAAAwM3R+AYAAAAAAG5ZmzZttGHDBn3xxRdKTEyUr6+vbDabrl69WqLO1dVVFotF6enp6tSpkwYMGKBu3bpp3759TkoOPPwyMjLUo0cPRUVFKTg4WPv375fVapWbm1uJusLCQs2ePVs+Pj5auHChPv/8c61Zs0YBAQFOSg4AAAAAAAD8OhrfAAAAAADAbTGZTDKbzdq/f79Gjhyp2NhYtWvXThs2bHCorfv/27uXlyr3PY7jHzW0iw26kLUlwjCvrbLITO1CYCWlOclJ0OrioCs+QVIahA9EKzMiFpagCcEKLKRBtLQId2biwHup1FKp6KIgWhB20dBaZ3QG7bUH+5yTPtp5v6bPZ/D+A778nj/+kMvlUm1trd6/f6+4uDgZhqGhoSELyoHf08ePH5Wbm6sVK1ZoYGBA9fX1crlcWrhwoc+2trZWq1ev1rFjx7R79251dXXJbrfLz8/PgnIAAAAAAADgn+PwDQAAAAAA/BKzZs2SaZrq6OjQokWLtGHDBqWnp+vt27c+240bN6qtrU1lZWW6efOmoqKiVFpaqh8/flhQDvwevF6vXC6XoqKidO3aNRUWFqqpqUlJSUk+276+Ptntdm3evFkhISFqb2+X0+nU7NmzLSgHAAAAAAAA/nMcvgEAAAAAgF8qIiJCVVVVunv3rp4/f67o6GiZpqlv3779tPP395fdbld3d7cyMzN15MgRrVu3Tg0NDRaVA1NXS0uLkpKSlJWVpYyMDPX09MgwDAUEBPy0Gx4e1oULFxQVFaWGhgZVVlaqurpa0dHRFpUDAAAAAAAA/x0O3wAAAAAAwLhIT0+Xx+ORw+HQpUuXtHz5clVWVvrs5syZI6fTqZaWFk2fPl3Jycmy2+0aGBiwoBqYWvr7+3Xw4EElJCRoxowZamtrU0lJiebNm+ezdbvdio2N1dmzZ3XixAl1dnZqx44dFlQDAAAAAAAA/zsO3wAAAAAAwLgJDAyUYRjq6upSYmKidu7cqS1btsjj8fhs4+LiVFdXpzt37ujx48eKjIyU0+nU2NiYBeXA5DY6Oiqn06nIyEjdu3dP169fV01NjWw2m8+2p6dH27dvV0ZGhtasWSOPxyPTNBUUFGRBOQAAAAAAAPBrcPgGAAAAAADGXWhoqFwulx49eqSBgQGtXLlShmFoaGjIZ/vvl+IMw1Bubq5sNpsePHhgQTUwOT18+FCrVq1SXl6eDh8+LI/HI7vd7rP7/PmzTNOUzWZTf3+/6urqVFFRocWLF1tQDQAAAAAAAPxaHL4BAAAAAIAJs2nTJj158kRlZWUqLy9XdHS0XC6XvF7vT7uZM2fKNE11dnbKZrMpNTVV6enpev36tTXhwCTw7t072e12paSkKCwsTM+ePVNBQYGCg4N/2nm9XrlcLoWHh6uoqEiFhYVqbm7W+vXrLSoHAAAAAAAAfj0O3wAAAAAAwITy9/eX3W5Xd3e3du3apQMHDighIUGNjY0+2/DwcFVUVKi6ulqvXr1SbGysTNPUyMiIBeWANb5+/SrTNBUREaGmpibdv39fbrdbYWFhPtvW1lYlJycrKytLGRkZ6u7ulmEYCggIsKAcAAAAAAAAGD8cvgEAAAAAAEvMnTtXTqdTzc3NCgoKUlJSkux2uwYHB322KSkpevr0qRwOhy5fvqyIiAi5XC4LqoGJ5Xa7FRMTI6fTKdM01dHRodTUVJ/dhw8fZBiG1q5dq8DAQLW2tqqkpETz58+3oBoAAAAAAAAYf37ev/5LBAAAAAAAYIJ5vV7dvn1bOTk5+vTpk/Lz83X06FFNmzbNZ9vX16dTp06pvLxciYmJCg0NtaAYGH9v3rxRS0uL9u/fL4fDoQULFvhsxsbGdPXqVeXn5ys4OFgOh0N79uyRn5+fBcUAAAAAAADAxOHwDQAAAAAATBpfvnzRxYsXVVBQoLCwMDmdTm3duvVvt/X19SouLtbY2NgEVwITIzAwUIZhKD4+/m+/19TUyDAM9fT06NChQzp37pyCg4MnuBIAAAAAAACwBodvAAAAAABg0nnx4oWOHz+uqqoqpaWl6cqVK1qyZInVWcCk0Nvbq9OnT+vGjRtKS0uT0+nU0qVLrc4CAAAAAAAAJpS/1QEAAAAAAAB/FR4ersrKSlVXV+vly5eKiYmRaZoaGRmxOg2wzPDwsEzT1LJly9TY2Kiqqiq53W6O3gAAAAAAAPB/iRffAAAAAADApDY6Oqri4mKdOXNGCxYs0Pnz55WZmWl1FjCh3G63srOzNTg4qJycHOXl5SkoKMjqLAAAAAAAAMAyHL4BAAAAAIApobe3VydPntStW7e0bds27du3T/7+PGaP39v3799VWlqq2tpa7d27VwUFBQoJCbE6CwAAAAAAALAch28AAAAAAGBKqaurU3Z2ttrb261OASZEfHy8ioqKlJCQYHUKAAAAAAAAMGlw+AYAAAAAAAAAAAAAAAAAmFL4HwgAAAAAAAAAAAAAAAAAYErh8A0AAAAAAAAAAAAAAAAAMKVw+AYAAAAAAAAAAAAAAAAAmFKmSfrT6ggAAAAAAAAAAAAAAAAAAP6pfwF/1CY/JRns/wAAAABJRU5ErkJggg==\n", + "text/plain": "" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualize_last_task_graph()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 51, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "../tmp/gantt_charts/goal_41.pdf\n" + ] + }, + { + "data": { + "text/plain": "", + "image/png": "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", + "image/jpeg": "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" + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "visualize_last_gant_diagram()" + ], "metadata": { "collapsed": false, "pycharm": { From cc56981706ff46b585c3bc56b4a4f190d65055c6 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 13 Aug 2024 15:50:55 +0200 Subject: [PATCH 27/43] launchfile for the vrb notebook --- launch/giskardpy_pr2_standalone_vrb.launch | 7 +++++++ 1 file changed, 7 insertions(+) create mode 100644 launch/giskardpy_pr2_standalone_vrb.launch diff --git a/launch/giskardpy_pr2_standalone_vrb.launch b/launch/giskardpy_pr2_standalone_vrb.launch new file mode 100644 index 0000000000..8c1d769d8d --- /dev/null +++ b/launch/giskardpy_pr2_standalone_vrb.launch @@ -0,0 +1,7 @@ + + + + + + + \ No newline at end of file From d231815e843f97c7398d85143ba7eaca4583a1ec Mon Sep 17 00:00:00 2001 From: malte Date: Wed, 14 Aug 2024 16:51:59 +0200 Subject: [PATCH 28/43] better vrb launch --- launch/giskardpy_pr2_standalone_vrb.launch | 2 +- scripts/iai_robots/pr2/pr2_standalone_vrb.py | 40 ++++++++++++++++++++ 2 files changed, 41 insertions(+), 1 deletion(-) create mode 100644 scripts/iai_robots/pr2/pr2_standalone_vrb.py diff --git a/launch/giskardpy_pr2_standalone_vrb.launch b/launch/giskardpy_pr2_standalone_vrb.launch index 8c1d769d8d..f84ef34f4b 100644 --- a/launch/giskardpy_pr2_standalone_vrb.launch +++ b/launch/giskardpy_pr2_standalone_vrb.launch @@ -2,6 +2,6 @@ - + \ No newline at end of file diff --git a/scripts/iai_robots/pr2/pr2_standalone_vrb.py b/scripts/iai_robots/pr2/pr2_standalone_vrb.py new file mode 100644 index 0000000000..41398be39a --- /dev/null +++ b/scripts/iai_robots/pr2/pr2_standalone_vrb.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python +import rospy + +from giskardpy.configs.behavior_tree_config import StandAloneBTConfig +from giskardpy.configs.giskard import Giskard +from giskardpy.configs.iai_robots.pr2 import PR2CollisionAvoidance, WorldWithPR2Config +from giskardpy.configs.qp_controller_config import QPControllerConfig, SupportedQPSolver +from giskardpy.configs.robot_interface_config import StandAloneRobotInterfaceConfig + +if __name__ == '__main__': + rospy.init_node('giskard') + drive_joint_name = 'brumbrum' + giskard = Giskard(world_config=WorldWithPR2Config(drive_joint_name=drive_joint_name), + collision_avoidance_config=PR2CollisionAvoidance(drive_joint_name=drive_joint_name), + robot_interface_config=StandAloneRobotInterfaceConfig( + [ + 'torso_lift_joint', + 'head_pan_joint', + 'head_tilt_joint', + 'r_shoulder_pan_joint', + 'r_shoulder_lift_joint', + 'r_upper_arm_roll_joint', + 'r_forearm_roll_joint', + 'r_elbow_flex_joint', + 'r_wrist_flex_joint', + 'r_wrist_roll_joint', + 'l_shoulder_pan_joint', + 'l_shoulder_lift_joint', + 'l_upper_arm_roll_joint', + 'l_forearm_roll_joint', + 'l_elbow_flex_joint', + 'l_wrist_flex_joint', + 'l_wrist_roll_joint', + drive_joint_name, + ] + ), + behavior_tree_config=StandAloneBTConfig(publish_tf=False, publish_js=False, debug_mode=True, + simulation_max_hz=20), + qp_controller_config=QPControllerConfig(qp_solver=SupportedQPSolver.qpSWIFT)) + giskard.live() From 2b3be31239c8252ec89bd2c82cf182fbf5ffa1f7 Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 15 Aug 2024 15:19:07 +0200 Subject: [PATCH 29/43] added stretch to notebook --- launch/giskardpy_stretch_standalone.launch | 6 +- .../giskardpy_stretch_standalone_vrb.launch | 7 + scripts/giskard_examples.ipynb | 479 +++++++++++++----- scripts/iai_robots/pr2/pr2_standalone_vrb.py | 0 .../iai_robots/stretch/stretch_standalone.py | 2 +- .../stretch/stretch_standalone_vrb.py | 19 + self_collision_matrices/iai/stretch.srdf | 64 +-- 7 files changed, 398 insertions(+), 179 deletions(-) create mode 100755 launch/giskardpy_stretch_standalone_vrb.launch mode change 100644 => 100755 scripts/iai_robots/pr2/pr2_standalone_vrb.py create mode 100755 scripts/iai_robots/stretch/stretch_standalone_vrb.py diff --git a/launch/giskardpy_stretch_standalone.launch b/launch/giskardpy_stretch_standalone.launch index 3070bfb1ba..45b00882c6 100644 --- a/launch/giskardpy_stretch_standalone.launch +++ b/launch/giskardpy_stretch_standalone.launch @@ -1,14 +1,14 @@ - + False - - [map, stretch/link_grasp_center] - - [map, stretch/base_link] + - [map, link_grasp_center] + - [map, base_link] diff --git a/launch/giskardpy_stretch_standalone_vrb.launch b/launch/giskardpy_stretch_standalone_vrb.launch new file mode 100755 index 0000000000..f8aaf19aa2 --- /dev/null +++ b/launch/giskardpy_stretch_standalone_vrb.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index f4810c2c5f..349c1f54e7 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 8, + "execution_count": 1, "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", @@ -29,10 +29,32 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": 2, + "outputs": [], + "source": [ + "rospy.init_node('giskard_examples')\n" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 3, "outputs": [], "source": [ - "rospy.init_node('giskard_examples')" + "ROBOT = 'stretch'\n", + "if ROBOT == 'stretch':\n", + " single_joint_goal = {'joint_lift': 0.7}\n", + " tool_frame = 'link_grasp_center'\n", + " cam_frame = 'camera_color_optical_frame'\n", + "elif ROBOT == 'pr2':\n", + " single_joint_goal = {'torso_lift_joint': 0.3}\n", + " tool_frame = 'l_gripper_tool_frame'\n", + " cam_frame = 'wide_stereo_optical_frame'" ], "metadata": { "collapsed": false, @@ -43,7 +65,7 @@ }, { "cell_type": "code", - "execution_count": 18, + "execution_count": 4, "outputs": [], "source": [ "# Launch the giskardpy PR2 standalone launch file before this\n", @@ -58,34 +80,50 @@ }, { "cell_type": "code", - "execution_count": 45, + "execution_count": 5, "outputs": [], "source": [ "# Define some helper functions\n", "def reset_giskard():\n", " gs.clear_motion_goals_and_monitors()\n", " gs.world.clear()\n", - " default_pose = {\n", - " 'r_elbow_flex_joint': -0.15,\n", - " 'r_forearm_roll_joint': 0,\n", - " 'r_shoulder_lift_joint': 0,\n", - " 'r_shoulder_pan_joint': 0,\n", - " 'r_upper_arm_roll_joint': 0,\n", - " 'r_wrist_flex_joint': -0.10001,\n", - " 'r_wrist_roll_joint': 0,\n", - " 'l_elbow_flex_joint': -0.15,\n", - " 'l_forearm_roll_joint': 0,\n", - " 'l_shoulder_lift_joint': 0,\n", - " 'l_shoulder_pan_joint': 0,\n", - " 'l_upper_arm_roll_joint': 0,\n", - " 'l_wrist_flex_joint': -0.10001,\n", - " 'l_wrist_roll_joint': 0,\n", - " 'torso_lift_joint': 0.2,\n", - " 'head_pan_joint': 0,\n", - " 'head_tilt_joint': 0,\n", - " 'l_gripper_l_finger_joint': 0.55,\n", - " 'r_gripper_l_finger_joint': 0.55\n", - " }\n", + " if ROBOT == 'stretch':\n", + " default_pose = {\n", + " 'joint_gripper_finger_left': 0.6,\n", + " 'joint_gripper_finger_right': 0.6,\n", + " 'joint_right_wheel': 0.0,\n", + " 'joint_left_wheel': 0.0,\n", + " 'joint_lift': 0.5,\n", + " 'joint_arm_l3': 0.05,\n", + " 'joint_arm_l2': 0.05,\n", + " 'joint_arm_l1': 0.05,\n", + " 'joint_arm_l0': 0.05,\n", + " 'joint_wrist_yaw': 0.0,\n", + " 'joint_head_pan': 0.0,\n", + " 'joint_head_tilt': 0.0\n", + " }\n", + " elif ROBOT == 'pr2':\n", + " default_pose = {\n", + " 'r_elbow_flex_joint': -0.15,\n", + " 'r_forearm_roll_joint': 0,\n", + " 'r_shoulder_lift_joint': 0,\n", + " 'r_shoulder_pan_joint': 0,\n", + " 'r_upper_arm_roll_joint': 0,\n", + " 'r_wrist_flex_joint': -0.10001,\n", + " 'r_wrist_roll_joint': 0,\n", + " 'l_elbow_flex_joint': -0.15,\n", + " 'l_forearm_roll_joint': 0,\n", + " 'l_shoulder_lift_joint': 0,\n", + " 'l_shoulder_pan_joint': 0,\n", + " 'l_upper_arm_roll_joint': 0,\n", + " 'l_wrist_flex_joint': -0.10001,\n", + " 'l_wrist_roll_joint': 0,\n", + " 'torso_lift_joint': 0.2,\n", + " 'head_pan_joint': 0,\n", + " 'head_tilt_joint': 0,\n", + " 'l_gripper_l_finger_joint': 0.55,\n", + " 'r_gripper_l_finger_joint': 0.55\n", + " }\n", " done = gs.monitors.add_set_seed_configuration(default_pose)\n", " base_pose = PoseStamped()\n", " base_pose.header.frame_id = 'map'\n", @@ -157,12 +195,12 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 6, "outputs": [], "source": [ "reset_giskard()\n", "\n", - "joint_goal = {'torso_lift_joint': 0.3}\n", + "joint_goal = single_joint_goal\n", "joint_monitor = gs.monitors.add_joint_position(goal_state=joint_goal)\n", "gs.motion_goals.add_joint_position(goal_state=joint_goal)\n", "gs.monitors.add_end_motion(start_condition=joint_monitor)\n", @@ -189,7 +227,7 @@ }, { "cell_type": "code", - "execution_count": 7, + "execution_count": 8, "outputs": [ { "ename": "AssertionError", @@ -198,7 +236,7 @@ "traceback": [ "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[7], line 21\u001B[0m\n\u001B[1;32m 18\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 19\u001B[0m \u001B[38;5;66;03m# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\u001B[39;00m\n\u001B[1;32m 20\u001B[0m \u001B[38;5;66;03m# gs.add_default_end_motion_conditions()\u001B[39;00m\n\u001B[0;32m---> 21\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m \u001B[38;5;241m1\u001B[39m\n", + "Cell \u001B[0;32mIn[8], line 36\u001B[0m\n\u001B[1;32m 33\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 34\u001B[0m \u001B[38;5;66;03m# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\u001B[39;00m\n\u001B[1;32m 35\u001B[0m \u001B[38;5;66;03m# gs.add_default_end_motion_conditions()\u001B[39;00m\n\u001B[0;32m---> 36\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", "\u001B[0;31mAssertionError\u001B[0m: " ] } @@ -217,10 +255,12 @@ "goal_pose.pose.position.y = -0.2\n", "goal_pose.pose.position.z = 0.7\n", "# specify the cartesian pose goal to move 'l_gripper_tool_frame' towards goal_pose by using the kinematic chain between 'l_gripper_tool_frame' and 'map'\n", - "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", + "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", "# specify monitor that is active when it is below the given thresholds and use it to end the motion\n", - "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01,\n", + "pose_monitor = gs.monitors.add_cartesian_pose('map', tool_frame, goal_pose, position_threshold=0.01,\n", " orientation_threshold=0.01)\n", + "\n", + "gs.monitors.add_max_trajectory_length(30)\n", "gs.monitors.add_end_motion(pose_monitor)\n", "# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\n", "# gs.add_default_end_motion_conditions()\n", @@ -247,8 +287,20 @@ }, { "cell_type": "code", - "execution_count": 8, - "outputs": [], + "execution_count": 9, + "outputs": [ + { + "ename": "AssertionError", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[9], line 24\u001B[0m\n\u001B[1;32m 22\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 23\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_max_trajectory_length(\u001B[38;5;241m30\u001B[39m)\n\u001B[0;32m---> 24\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", + "\u001B[0;31mAssertionError\u001B[0m: " + ] + } + ], "source": [ "reset_giskard()\n", "\n", @@ -268,10 +320,11 @@ "goal_pose.pose.position.x = -0.08\n", "goal_pose.pose.position.y = 0\n", "goal_pose.pose.position.z = 0\n", - "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", - "pose_monitor = gs.monitors.add_cartesian_pose('map', 'l_gripper_tool_frame', goal_pose, position_threshold=0.01,\n", + "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", + "pose_monitor = gs.monitors.add_cartesian_pose('map', tool_frame, goal_pose, position_threshold=0.01,\n", " orientation_threshold=0.01)\n", "gs.monitors.add_end_motion(pose_monitor)\n", + "gs.monitors.add_max_trajectory_length(30)\n", "assert gs.execute().error.code == GiskardError.SUCCESS" ], "metadata": { @@ -309,7 +362,7 @@ }, { "cell_type": "code", - "execution_count": 11, + "execution_count": 10, "outputs": [], "source": [ "reset_giskard()\n", @@ -319,17 +372,18 @@ "\n", "# Define a robot feature as a point at the origin of the right gripper tool frame\n", "robot_feature = PointStamped()\n", - "robot_feature.header.frame_id = 'r_gripper_tool_frame'\n", + "robot_feature.header.frame_id = tool_frame\n", "\n", "# use the distance feature function to constrain the distance between the features to be between 2m and 2.5m\n", "gs.motion_goals.add_distance(root_link='map',\n", - " tip_link='r_gripper_tool_frame',\n", + " tip_link=tool_frame,\n", " reference_point=world_feature,\n", " tip_point=robot_feature,\n", " lower_limit=2,\n", " upper_limit=2.5)\n", "\n", "gs.add_default_end_motion_conditions()\n", + "gs.monitors.add_max_trajectory_length(30)\n", "assert gs.execute().error.code == GiskardError.SUCCESS" ], "metadata": { @@ -357,13 +411,25 @@ }, { "cell_type": "code", - "execution_count": 13, - "outputs": [], + "execution_count": 12, + "outputs": [ + { + "ename": "AssertionError", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[12], line 59\u001B[0m\n\u001B[1;32m 53\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39madd_align_planes(root_link\u001B[38;5;241m=\u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;124mmap\u001B[39m\u001B[38;5;124m'\u001B[39m,\n\u001B[1;32m 54\u001B[0m tip_link\u001B[38;5;241m=\u001B[39mgripper_link,\n\u001B[1;32m 55\u001B[0m goal_normal\u001B[38;5;241m=\u001B[39mworld_cyl_z_axis_feature,\n\u001B[1;32m 56\u001B[0m tip_normal\u001B[38;5;241m=\u001B[39mrobot_gripper_z_axis_feature)\n\u001B[1;32m 58\u001B[0m gs\u001B[38;5;241m.\u001B[39madd_default_end_motion_conditions()\n\u001B[0;32m---> 59\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n\u001B[1;32m 61\u001B[0m \u001B[38;5;66;03m# EXERCISE:\u001B[39;00m\n\u001B[1;32m 62\u001B[0m \u001B[38;5;66;03m# 1. Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.\u001B[39;00m\n\u001B[1;32m 63\u001B[0m \u001B[38;5;66;03m# 2. You might notice that not all poses are feasible. This is due to a missing that constraint that allows the gripper_frame to freely rotate around its x-axis. Try to constrain this using the AlignFeatureFunction\u001B[39;00m\n", + "\u001B[0;31mAssertionError\u001B[0m: " + ] + } + ], "source": [ "reset_giskard()\n", "\n", "# variables\n", - "gripper_link = 'r_gripper_tool_frame'\n", + "gripper_link = tool_frame\n", "\n", "# adding the object\n", "cyl_pose = PoseStamped()\n", @@ -445,13 +511,25 @@ }, { "cell_type": "code", - "execution_count": 14, - "outputs": [], + "execution_count": 24, + "outputs": [ + { + "ename": "AssertionError", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[24], line 64\u001B[0m\n\u001B[1;32m 59\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39madd_align_planes(root_link\u001B[38;5;241m=\u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;124mmap\u001B[39m\u001B[38;5;124m'\u001B[39m,\n\u001B[1;32m 60\u001B[0m tip_link\u001B[38;5;241m=\u001B[39mgripper_link,\n\u001B[1;32m 61\u001B[0m goal_normal\u001B[38;5;241m=\u001B[39mworld_cyl_z_axis_feature,\n\u001B[1;32m 62\u001B[0m tip_normal\u001B[38;5;241m=\u001B[39mrobot_gripper_z_axis_feature)\n\u001B[1;32m 63\u001B[0m gs\u001B[38;5;241m.\u001B[39madd_default_end_motion_conditions()\n\u001B[0;32m---> 64\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n\u001B[1;32m 66\u001B[0m \u001B[38;5;66;03m# EXERCISE:\u001B[39;00m\n\u001B[1;32m 67\u001B[0m \u001B[38;5;66;03m# 1. Change Pose and size of the obstacle and see of the robot behaves.\u001B[39;00m\n", + "\u001B[0;31mAssertionError\u001B[0m: " + ] + } + ], "source": [ "reset_giskard()\n", "\n", "# variables\n", - "gripper_link = 'r_gripper_tool_frame'\n", + "gripper_link = tool_frame\n", "\n", "# adding the object\n", "cyl_pose = PoseStamped()\n", @@ -537,22 +615,21 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 26, "outputs": [ { - "data": { - "text/plain": "{'PointingAt': False, 'Sleep': False}" - }, - "execution_count": 10, - "metadata": {}, - "output_type": "execute_result" + "name": "stdout", + "output_type": "stream", + "text": [ + "{'DistanceMonitor': False, 'PointingAt': False}\n" + ] } ], "source": [ "reset_giskard()\n", "\n", "# variables\n", - "gripper_link = 'r_gripper_tool_frame'\n", + "gripper_link = tool_frame\n", "\n", "# adding the object\n", "cyl_pose = PoseStamped()\n", @@ -641,7 +718,7 @@ " error_message='local minimum reached while monitors are not satisfied')\n", "result = gs.execute()\n", "if result.error.code != GiskardError.SUCCESS:\n", - " gs.get_end_motion_reason(show_all=False)\n", + " print(gs.get_end_motion_reason(show_all=False))\n", "# EXERCISE:\n", "# The output tells you which monitor of the end motion was not successful. Try changing/removing/adding constraint and monitors to realize a successful execution." ], @@ -670,44 +747,47 @@ }, { "cell_type": "code", - "execution_count": 16, + "execution_count": 41, "outputs": [ { - "name": "stderr", - "output_type": "stream", - "text": [ - "\n", - "KeyboardInterrupt\n", - "\n" + "ename": "AssertionError", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[41], line 117\u001B[0m\n\u001B[1;32m 115\u001B[0m gs\u001B[38;5;241m.\u001B[39madd_default_end_motion_conditions()\n\u001B[1;32m 116\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39mallow_all_collisions()\n\u001B[0;32m--> 117\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n\u001B[1;32m 119\u001B[0m \u001B[38;5;66;03m# EXERCISE:\u001B[39;00m\n\u001B[1;32m 120\u001B[0m \u001B[38;5;66;03m# 1.Comment the BaseArmWeightScaling and MaxManipulabilityLinWeight Goals to observe the resulting motions when the cost function is not augmented.\u001B[39;00m\n", + "\u001B[0;31mAssertionError\u001B[0m: " ] } ], "source": [ "reset_giskard()\n", - "\n", - "js = {\n", - " # 'torso_lift_joint': 0.2999225173357618,\n", - " 'head_pan_joint': 0.041880780651479044,\n", - " 'head_tilt_joint': -0.37,\n", - " 'r_upper_arm_roll_joint': -0.9487714747527726,\n", - " 'r_shoulder_pan_joint': -1.0047307505973626,\n", - " 'r_shoulder_lift_joint': 0.48736790658811985,\n", - " 'r_forearm_roll_joint': -14.895833882874182,\n", - " 'r_elbow_flex_joint': -1.392377908925028,\n", - " 'r_wrist_flex_joint': -0.4548695149411013,\n", - " 'r_wrist_roll_joint': 0.11426798984097819,\n", - " 'l_upper_arm_roll_joint': 1.7383062350263658,\n", - " 'l_shoulder_pan_joint': 1.8799810286792007,\n", - " 'l_shoulder_lift_joint': 0.011627231224188975,\n", - " 'l_forearm_roll_joint': 312.67276414458695,\n", - " 'l_elbow_flex_joint': -2.0300928925694675,\n", - " 'l_wrist_flex_joint': -0.10014623223021513,\n", - " 'l_wrist_roll_joint': -6.062015047706399,\n", - "}\n", - "gs.motion_goals.add_joint_position(js)\n", - "gs.motion_goals.allow_all_collisions()\n", - "gs.add_default_end_motion_conditions()\n", - "gs.execute()\n", + "# This is eventually not feasible for the stretch\n", + "if ROBOT == 'pr2':\n", + " js = {\n", + " # 'torso_lift_joint': 0.2999225173357618,\n", + " 'head_pan_joint': 0.041880780651479044,\n", + " 'head_tilt_joint': -0.37,\n", + " 'r_upper_arm_roll_joint': -0.9487714747527726,\n", + " 'r_shoulder_pan_joint': -1.0047307505973626,\n", + " 'r_shoulder_lift_joint': 0.48736790658811985,\n", + " 'r_forearm_roll_joint': -14.895833882874182,\n", + " 'r_elbow_flex_joint': -1.392377908925028,\n", + " 'r_wrist_flex_joint': -0.4548695149411013,\n", + " 'r_wrist_roll_joint': 0.11426798984097819,\n", + " 'l_upper_arm_roll_joint': 1.7383062350263658,\n", + " 'l_shoulder_pan_joint': 1.8799810286792007,\n", + " 'l_shoulder_lift_joint': 0.011627231224188975,\n", + " 'l_forearm_roll_joint': 312.67276414458695,\n", + " 'l_elbow_flex_joint': -2.0300928925694675,\n", + " 'l_wrist_flex_joint': -0.10014623223021513,\n", + " 'l_wrist_roll_joint': -6.062015047706399,\n", + " }\n", + " gs.motion_goals.add_joint_position(js)\n", + " gs.motion_goals.allow_all_collisions()\n", + " gs.add_default_end_motion_conditions()\n", + " gs.execute()\n", "\n", "goal_pose = PoseStamped()\n", "goal_pose.header.frame_id = 'map'\n", @@ -727,16 +807,16 @@ " [-1, 0, 0, 0],\n", " [0, 0, 0, 1]]))\n", "\n", - "gs.motion_goals.add_cartesian_pose(goal_pose, 'l_gripper_tool_frame', 'map')\n", - "gs.motion_goals.add_cartesian_pose(goal_pose2, 'r_gripper_tool_frame', 'map', name='cart2')\n", + "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", + "# gs.motion_goals.add_cartesian_pose(goal_pose2, 'r_gripper_tool_frame', 'map', name='cart2')\n", "\n", "goal_point = PointStamped()\n", "goal_point.header.frame_id = goal_pose.header.frame_id\n", "goal_point.point = goal_pose.pose.position\n", "pointing_axis = Vector3Stamped()\n", - "pointing_axis.header.frame_id = 'wide_stereo_optical_frame'\n", + "pointing_axis.header.frame_id = cam_frame\n", "pointing_axis.vector.z = 1\n", - "gs.motion_goals.add_pointing(goal_point, 'wide_stereo_optical_frame', pointing_axis, 'map')\n", + "gs.motion_goals.add_pointing(goal_point, cam_frame, pointing_axis, 'map')\n", "\n", "x_base = Vector3Stamped()\n", "x_base.header.frame_id = 'base_link'\n", @@ -749,40 +829,53 @@ " tip_normal=x_base,\n", " goal_normal=x_goal)\n", "\n", + "if ROBOT == 'pr2':\n", + " arm_joints = [\n", + " 'torso_lift_joint',\n", + " # 'head_pan_joint',\n", + " # 'head_tilt_joint',\n", + " 'r_upper_arm_roll_joint',\n", + " 'r_shoulder_pan_joint',\n", + " 'r_shoulder_lift_joint',\n", + " 'r_forearm_roll_joint',\n", + " 'r_elbow_flex_joint',\n", + " 'r_wrist_flex_joint',\n", + " 'r_wrist_roll_joint',\n", + " 'l_upper_arm_roll_joint',\n", + " 'l_shoulder_pan_joint',\n", + " 'l_shoulder_lift_joint',\n", + " 'l_forearm_roll_joint',\n", + " 'l_elbow_flex_joint',\n", + " 'l_wrist_flex_joint',\n", + " 'l_wrist_roll_joint']\n", + " gain = 100000\n", + "elif ROBOT == 'stretch':\n", + " arm_joints = ['joint_arm_l3',\n", + " 'joint_arm_l2',\n", + " 'joint_arm_l1',\n", + " 'joint_arm_l0',\n", + " 'joint_wrist_yaw',\n", + " 'joint_wrist_pitch',\n", + " 'joint_wrist_roll']\n", + " gain = 100000\n", + "\n", "tip_goal = PointStamped()\n", "tip_goal.header.frame_id = 'map'\n", "tip_goal.point = goal_pose.pose.position\n", "gs.motion_goals.add_motion_goal(motion_goal_class=BaseArmWeightScaling.__name__,\n", " root_link='map',\n", - " tip_link='l_gripper_tool_frame',\n", + " tip_link=tool_frame,\n", " tip_goal=tip_goal,\n", - " gain=100000,\n", - " arm_joints=[\n", - " 'torso_lift_joint',\n", - " # 'head_pan_joint',\n", - " # 'head_tilt_joint',\n", - " 'r_upper_arm_roll_joint',\n", - " 'r_shoulder_pan_joint',\n", - " 'r_shoulder_lift_joint',\n", - " 'r_forearm_roll_joint',\n", - " 'r_elbow_flex_joint',\n", - " 'r_wrist_flex_joint',\n", - " 'r_wrist_roll_joint',\n", - " 'l_upper_arm_roll_joint',\n", - " 'l_shoulder_pan_joint',\n", - " 'l_shoulder_lift_joint',\n", - " 'l_forearm_roll_joint',\n", - " 'l_elbow_flex_joint',\n", - " 'l_wrist_flex_joint',\n", - " 'l_wrist_roll_joint'],\n", + " gain=gain,\n", + " arm_joints=arm_joints,\n", " base_joints=['brumbrum'])\n", - "gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", - " root_link='torso_lift_link',\n", - " tip_link='r_gripper_tool_frame')\n", - "gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", - " root_link='torso_lift_link',\n", - " tip_link='l_gripper_tool_frame',\n", - " name='MaxMal2')\n", + "# gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", + "# root_link='torso_lift_link',\n", + "# tip_link='r_gripper_tool_frame')\n", + "# gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", + "# root_link='torso_lift_link',\n", + "# tip_link='l_gripper_tool_frame',\n", + "# name='MaxMal2')\n", "gs.add_default_end_motion_conditions()\n", "gs.motion_goals.allow_all_collisions()\n", "assert gs.execute().error.code == GiskardError.SUCCESS\n", @@ -812,7 +905,7 @@ }, { "cell_type": "code", - "execution_count": 27, + "execution_count": 51, "outputs": [], "source": [ "reset_giskard()\n", @@ -832,7 +925,7 @@ "p.pose.position.x = 0.5\n", "p.pose.position.y = 0.2\n", "\n", - "hand = 'r_gripper_tool_frame'\n", + "hand = tool_frame\n", "\n", "goal_angle = np.pi / 4\n", "handle_frame_id = 'sink_area_dish_washer_door_handle'\n", @@ -872,6 +965,20 @@ " root_link='map',\n", " tip_normal=x_gripper,\n", " goal_normal=x_goal)\n", + "\n", + "if ROBOT == 'stretch':\n", + " x_base = Vector3Stamped()\n", + " x_base.header.frame_id = 'base_link'\n", + " x_base.vector.x = 1\n", + " x_goal = Vector3Stamped()\n", + " x_goal.header.frame_id = 'map'\n", + " x_goal.vector.y = 1\n", + " gs.motion_goals.add_align_planes(tip_link='base_link',\n", + " root_link='map',\n", + " tip_normal=x_base,\n", + " goal_normal=x_goal,\n", + " name='align_base')\n", + "\n", "gs.add_default_end_motion_conditions()\n", "gs.execute()\n", "\n", @@ -918,8 +1025,25 @@ }, { "cell_type": "code", - "execution_count": 30, - "outputs": [], + "execution_count": 53, + "outputs": [ + { + "ename": "KeyboardInterrupt", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mKeyboardInterrupt\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[53], line 43\u001B[0m\n\u001B[1;32m 41\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39mallow_all_collisions()\n\u001B[1;32m 42\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(start_condition\u001B[38;5;241m=\u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;124m and \u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;241m.\u001B[39mjoin([end_monitor, monitor2]))\n\u001B[0;32m---> 43\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m \u001B[43mgs\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mexecute\u001B[49m\u001B[43m(\u001B[49m\u001B[43m)\u001B[49m\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", + "File \u001B[0;32m~/workspace/new_giskard_ws/src/giskardpy/src/giskardpy/python_interface/python_interface.py:1992\u001B[0m, in \u001B[0;36mGiskardWrapper.execute\u001B[0;34m(self, wait)\u001B[0m\n\u001B[1;32m 1987\u001B[0m \u001B[38;5;28;01mdef\u001B[39;00m \u001B[38;5;21mexecute\u001B[39m(\u001B[38;5;28mself\u001B[39m, wait: \u001B[38;5;28mbool\u001B[39m \u001B[38;5;241m=\u001B[39m \u001B[38;5;28;01mTrue\u001B[39;00m) \u001B[38;5;241m-\u001B[39m\u001B[38;5;241m>\u001B[39m MoveResult:\n\u001B[1;32m 1988\u001B[0m \u001B[38;5;250m \u001B[39m\u001B[38;5;124;03m\"\"\"\u001B[39;00m\n\u001B[1;32m 1989\u001B[0m \u001B[38;5;124;03m :param wait: this function blocks if wait=True\u001B[39;00m\n\u001B[1;32m 1990\u001B[0m \u001B[38;5;124;03m :return: result from giskard\u001B[39;00m\n\u001B[1;32m 1991\u001B[0m \u001B[38;5;124;03m \"\"\"\u001B[39;00m\n\u001B[0;32m-> 1992\u001B[0m result \u001B[38;5;241m=\u001B[39m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43m_send_action_goal\u001B[49m\u001B[43m(\u001B[49m\u001B[43mMoveGoal\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mEXECUTE\u001B[49m\u001B[43m,\u001B[49m\u001B[43m \u001B[49m\u001B[43mwait\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 1993\u001B[0m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39mlast_execution_state \u001B[38;5;241m=\u001B[39m result\u001B[38;5;241m.\u001B[39mexecution_state\n\u001B[1;32m 1994\u001B[0m \u001B[38;5;28;01mreturn\u001B[39;00m result\n", + "File \u001B[0;32m~/workspace/new_giskard_ws/src/giskardpy/src/giskardpy/python_interface/python_interface.py:2017\u001B[0m, in \u001B[0;36mGiskardWrapper._send_action_goal\u001B[0;34m(self, goal_type, wait)\u001B[0m\n\u001B[1;32m 2015\u001B[0m goal\u001B[38;5;241m.\u001B[39mtype \u001B[38;5;241m=\u001B[39m goal_type\n\u001B[1;32m 2016\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m wait:\n\u001B[0;32m-> 2017\u001B[0m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43m_client\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43msend_goal_and_wait\u001B[49m\u001B[43m(\u001B[49m\u001B[43mgoal\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 2018\u001B[0m \u001B[38;5;28;01mreturn\u001B[39;00m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39m_client\u001B[38;5;241m.\u001B[39mget_result()\n\u001B[1;32m 2019\u001B[0m \u001B[38;5;28;01melse\u001B[39;00m:\n", + "File \u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/actionlib/simple_action_client.py:111\u001B[0m, in \u001B[0;36mSimpleActionClient.send_goal_and_wait\u001B[0;34m(self, goal, execute_timeout, preempt_timeout)\u001B[0m\n\u001B[1;32m 109\u001B[0m \u001B[38;5;28;01mdef\u001B[39;00m \u001B[38;5;21msend_goal_and_wait\u001B[39m(\u001B[38;5;28mself\u001B[39m, goal, execute_timeout\u001B[38;5;241m=\u001B[39mrospy\u001B[38;5;241m.\u001B[39mDuration(), preempt_timeout\u001B[38;5;241m=\u001B[39mrospy\u001B[38;5;241m.\u001B[39mDuration()):\n\u001B[1;32m 110\u001B[0m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39msend_goal(goal)\n\u001B[0;32m--> 111\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m \u001B[38;5;129;01mnot\u001B[39;00m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mwait_for_result\u001B[49m\u001B[43m(\u001B[49m\u001B[43mexecute_timeout\u001B[49m\u001B[43m)\u001B[49m:\n\u001B[1;32m 112\u001B[0m \u001B[38;5;66;03m# preempt action\u001B[39;00m\n\u001B[1;32m 113\u001B[0m rospy\u001B[38;5;241m.\u001B[39mlogdebug(\u001B[38;5;124m\"\u001B[39m\u001B[38;5;124mCanceling goal\u001B[39m\u001B[38;5;124m\"\u001B[39m)\n\u001B[1;32m 114\u001B[0m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39mcancel_goal()\n", + "File \u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/actionlib/simple_action_client.py:143\u001B[0m, in \u001B[0;36mSimpleActionClient.wait_for_result\u001B[0;34m(self, timeout)\u001B[0m\n\u001B[1;32m 140\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m time_left \u001B[38;5;241m>\u001B[39m loop_period \u001B[38;5;129;01mor\u001B[39;00m timeout \u001B[38;5;241m==\u001B[39m rospy\u001B[38;5;241m.\u001B[39mDuration():\n\u001B[1;32m 141\u001B[0m time_left \u001B[38;5;241m=\u001B[39m loop_period\n\u001B[0;32m--> 143\u001B[0m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mdone_condition\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mwait\u001B[49m\u001B[43m(\u001B[49m\u001B[43mtime_left\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mto_sec\u001B[49m\u001B[43m(\u001B[49m\u001B[43m)\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 145\u001B[0m \u001B[38;5;28;01mreturn\u001B[39;00m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39msimple_state \u001B[38;5;241m==\u001B[39m SimpleGoalState\u001B[38;5;241m.\u001B[39mDONE\n", + "File \u001B[0;32m/usr/lib/python3.8/threading.py:306\u001B[0m, in \u001B[0;36mCondition.wait\u001B[0;34m(self, timeout)\u001B[0m\n\u001B[1;32m 304\u001B[0m \u001B[38;5;28;01melse\u001B[39;00m:\n\u001B[1;32m 305\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m timeout \u001B[38;5;241m>\u001B[39m \u001B[38;5;241m0\u001B[39m:\n\u001B[0;32m--> 306\u001B[0m gotit \u001B[38;5;241m=\u001B[39m \u001B[43mwaiter\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43macquire\u001B[49m\u001B[43m(\u001B[49m\u001B[38;5;28;43;01mTrue\u001B[39;49;00m\u001B[43m,\u001B[49m\u001B[43m \u001B[49m\u001B[43mtimeout\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 307\u001B[0m \u001B[38;5;28;01melse\u001B[39;00m:\n\u001B[1;32m 308\u001B[0m gotit \u001B[38;5;241m=\u001B[39m waiter\u001B[38;5;241m.\u001B[39macquire(\u001B[38;5;28;01mFalse\u001B[39;00m)\n", + "\u001B[0;31mKeyboardInterrupt\u001B[0m: " + ] + } + ], "source": [ "reset_giskard()\n", "\n", @@ -929,12 +1053,12 @@ "pose1.pose.orientation.w = 1\n", "\n", "pose2 = PoseStamped()\n", - "pose2.header.frame_id = 'base_footprint'\n", + "pose2.header.frame_id = 'base_link'\n", "pose2.pose.position.y = 1\n", "pose2.pose.orientation.w = 1\n", "\n", "root_link = 'map'\n", - "tip_link = 'base_footprint'\n", + "tip_link = 'base_link'\n", "\n", "monitor1 = gs.monitors.add_cartesian_pose(name='pose1',\n", " root_link=root_link,\n", @@ -1243,6 +1367,117 @@ } } }, + { + "cell_type": "code", + "execution_count": 29, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": 9, + "outputs": [ + { + "data": { + "text/plain": "Dropdown(description='Select Robot:', layout=Layout(width='200px'), options=('PR2', 'Stretch'), style=Descript…", + "application/vnd.jupyter.widget-view+json": { + "version_major": 2, + "version_minor": 0, + "model_id": "8c622ba2e55a45969490f838379d93d4" + } + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "text/plain": "Button(button_style='success', description='Start Launch File', style=ButtonStyle())", + "application/vnd.jupyter.widget-view+json": { + "version_major": 2, + "version_minor": 0, + "model_id": "abd7d7833ae24ffe9b6004b36bc27daf" + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import ipywidgets as widgets\n", + "from IPython.display import display\n", + "from giskardpy.utils.utils import launch_launchfile\n", + "import subprocess\n", + "\n", + "# List of available launch files\n", + "launch_files = {\n", + " 'PR2': 'package://giskardpy/launch/giskardpy_pr2_standalone_vrb.launch',\n", + " 'Stretch': 'package://giskardpy/launch/giskardpy_stretch_standalone_vrb.launch'\n", + "}\n", + "\n", + "# Dropdown widget\n", + "dropdown = widgets.Dropdown(\n", + " options=launch_files.keys(),\n", + " value='PR2',\n", + " description='Select Robot:',\n", + " style={'description_width': 'initial'},\n", + " layout=widgets.Layout(width='200px')\n", + ")\n", + "\n", + "# Button widget\n", + "button = widgets.Button(\n", + " description='Start Launch File',\n", + " button_style='success',\n", + ")\n", + "\n", + "\n", + "# Function to start the selected ROS launch file\n", + "def on_button_click(b):\n", + " selected_launch_file = launch_files[dropdown.value]\n", + "\n", + " try:\n", + " result = subprocess.run('rosnode kill /giskard', shell=True, check=True, stdout=subprocess.PIPE,\n", + " stderr=subprocess.PIPE)\n", + " print(result.stdout.decode())\n", + " print(result.stderr.decode())\n", + " except subprocess.CalledProcessError as e:\n", + " print(f\"Error occurred: {e.stderr.decode()}\")\n", + "\n", + " print(f\"Starting ROS launch file: {selected_launch_file}\")\n", + " launch_launchfile(selected_launch_file)\n", + "\n", + "\n", + "# Attach the event handler to the button\n", + "button.on_click(on_button_click)\n", + "\n", + "# Display widgets\n", + "display(dropdown)\n", + "display(button)" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, { "cell_type": "code", "execution_count": null, diff --git a/scripts/iai_robots/pr2/pr2_standalone_vrb.py b/scripts/iai_robots/pr2/pr2_standalone_vrb.py old mode 100644 new mode 100755 diff --git a/scripts/iai_robots/stretch/stretch_standalone.py b/scripts/iai_robots/stretch/stretch_standalone.py index 22eeb2d73a..ee9d6dcc5f 100755 --- a/scripts/iai_robots/stretch/stretch_standalone.py +++ b/scripts/iai_robots/stretch/stretch_standalone.py @@ -12,5 +12,5 @@ giskard = Giskard(world_config=WorldWithDiffDriveRobot(), collision_avoidance_config=StretchCollisionAvoidanceConfig(), robot_interface_config=StretchStandaloneInterface(), - behavior_tree_config=StandAloneBTConfig()) + behavior_tree_config=StandAloneBTConfig(publish_tf=True, publish_js=True, debug_mode=True)) giskard.live() diff --git a/scripts/iai_robots/stretch/stretch_standalone_vrb.py b/scripts/iai_robots/stretch/stretch_standalone_vrb.py new file mode 100755 index 0000000000..6752227c72 --- /dev/null +++ b/scripts/iai_robots/stretch/stretch_standalone_vrb.py @@ -0,0 +1,19 @@ +#!/usr/bin/env python +import rospy + +from giskardpy.configs.behavior_tree_config import StandAloneBTConfig +from giskardpy.configs.giskard import Giskard +from giskardpy.configs.iai_robots.stretch import StretchCollisionAvoidanceConfig, StretchStandaloneInterface +from giskardpy.configs.world_config import WorldWithDiffDriveRobot +from giskardpy.configs.qp_controller_config import QPControllerConfig, SupportedQPSolver + + +if __name__ == '__main__': + rospy.init_node('giskard') + giskard = Giskard(world_config=WorldWithDiffDriveRobot(), + collision_avoidance_config=StretchCollisionAvoidanceConfig(), + robot_interface_config=StretchStandaloneInterface(), + behavior_tree_config=StandAloneBTConfig(publish_js=False, publish_tf=False, simulation_max_hz=20, + debug_mode=True), + qp_controller_config=QPControllerConfig(qp_solver=SupportedQPSolver.qpSWIFT)) + giskard.live() diff --git a/self_collision_matrices/iai/stretch.srdf b/self_collision_matrices/iai/stretch.srdf index 1d9ab27719..67acab4885 100644 --- a/self_collision_matrices/iai/stretch.srdf +++ b/self_collision_matrices/iai/stretch.srdf @@ -1,5 +1,10 @@ - + + + + + + @@ -14,9 +19,7 @@ - - @@ -41,9 +44,7 @@ - - @@ -67,9 +68,7 @@ - - @@ -92,9 +91,7 @@ - - @@ -116,9 +113,7 @@ - - @@ -139,9 +134,7 @@ - - @@ -161,9 +154,7 @@ - - @@ -182,9 +173,7 @@ - - @@ -202,9 +191,7 @@ - - @@ -221,9 +208,7 @@ - - @@ -239,9 +224,7 @@ - - @@ -256,8 +239,6 @@ - - @@ -271,9 +252,7 @@ - - @@ -286,9 +265,7 @@ - - @@ -300,22 +277,7 @@ - - - - - - - - - - - - - - - @@ -327,16 +289,7 @@ - - - - - - - - - @@ -400,7 +353,12 @@ + + + + + From d6ec5078919e226849dea3fad4d982ed3b931ffb Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 15 Aug 2024 15:22:22 +0200 Subject: [PATCH 30/43] pr2 notebook to 10hz --- scripts/giskard_examples.ipynb | 30 ++++++-------------- scripts/iai_robots/pr2/pr2_standalone_vrb.py | 2 +- 2 files changed, 10 insertions(+), 22 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 349c1f54e7..da76263df5 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 1, + "execution_count": 9, "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", @@ -29,7 +29,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 10, "outputs": [], "source": [ "rospy.init_node('giskard_examples')\n" @@ -43,10 +43,10 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 15, "outputs": [], "source": [ - "ROBOT = 'stretch'\n", + "ROBOT = 'pr2'\n", "if ROBOT == 'stretch':\n", " single_joint_goal = {'joint_lift': 0.7}\n", " tool_frame = 'link_grasp_center'\n", @@ -65,7 +65,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 12, "outputs": [], "source": [ "# Launch the giskardpy PR2 standalone launch file before this\n", @@ -80,7 +80,7 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 16, "outputs": [], "source": [ "# Define some helper functions\n", @@ -195,7 +195,7 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 17, "outputs": [], "source": [ "reset_giskard()\n", @@ -227,20 +227,8 @@ }, { "cell_type": "code", - "execution_count": 8, - "outputs": [ - { - "ename": "AssertionError", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[8], line 36\u001B[0m\n\u001B[1;32m 33\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 34\u001B[0m \u001B[38;5;66;03m# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\u001B[39;00m\n\u001B[1;32m 35\u001B[0m \u001B[38;5;66;03m# gs.add_default_end_motion_conditions()\u001B[39;00m\n\u001B[0;32m---> 36\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", - "\u001B[0;31mAssertionError\u001B[0m: " - ] - } - ], + "execution_count": 18, + "outputs": [], "source": [ "reset_giskard()\n", "\n", diff --git a/scripts/iai_robots/pr2/pr2_standalone_vrb.py b/scripts/iai_robots/pr2/pr2_standalone_vrb.py index 41398be39a..12b478e4c9 100755 --- a/scripts/iai_robots/pr2/pr2_standalone_vrb.py +++ b/scripts/iai_robots/pr2/pr2_standalone_vrb.py @@ -35,6 +35,6 @@ ] ), behavior_tree_config=StandAloneBTConfig(publish_tf=False, publish_js=False, debug_mode=True, - simulation_max_hz=20), + simulation_max_hz=10), qp_controller_config=QPControllerConfig(qp_solver=SupportedQPSolver.qpSWIFT)) giskard.live() From bc26770af236d57829c2262bd27be2bf33c5561f Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 15 Aug 2024 16:44:22 +0200 Subject: [PATCH 31/43] fix --- scripts/iai_robots/pr2/pr2_standalone_vrb.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/iai_robots/pr2/pr2_standalone_vrb.py b/scripts/iai_robots/pr2/pr2_standalone_vrb.py index 12b478e4c9..bfe9e585eb 100755 --- a/scripts/iai_robots/pr2/pr2_standalone_vrb.py +++ b/scripts/iai_robots/pr2/pr2_standalone_vrb.py @@ -34,7 +34,7 @@ drive_joint_name, ] ), - behavior_tree_config=StandAloneBTConfig(publish_tf=False, publish_js=False, debug_mode=True, + behavior_tree_config=StandAloneBTConfig(publish_tf=True, publish_js=False, debug_mode=True, simulation_max_hz=10), qp_controller_config=QPControllerConfig(qp_solver=SupportedQPSolver.qpSWIFT)) giskard.live() From 2af27916f5667dd9c6e35bc64ab9837910554e4f Mon Sep 17 00:00:00 2001 From: malte Date: Fri, 16 Aug 2024 08:39:37 +0200 Subject: [PATCH 32/43] switch pr2 vrb to 20hz --- scripts/giskard_examples.ipynb | 14 +++++++------- scripts/iai_robots/pr2/pr2_standalone_vrb.py | 2 +- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index da76263df5..71485fa2df 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": 9, + "execution_count": 1, "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", @@ -29,7 +29,7 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 2, "outputs": [], "source": [ "rospy.init_node('giskard_examples')\n" @@ -43,7 +43,7 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": 3, "outputs": [], "source": [ "ROBOT = 'pr2'\n", @@ -65,7 +65,7 @@ }, { "cell_type": "code", - "execution_count": 12, + "execution_count": 4, "outputs": [], "source": [ "# Launch the giskardpy PR2 standalone launch file before this\n", @@ -80,7 +80,7 @@ }, { "cell_type": "code", - "execution_count": 16, + "execution_count": 5, "outputs": [], "source": [ "# Define some helper functions\n", @@ -195,7 +195,7 @@ }, { "cell_type": "code", - "execution_count": 17, + "execution_count": 6, "outputs": [], "source": [ "reset_giskard()\n", @@ -227,7 +227,7 @@ }, { "cell_type": "code", - "execution_count": 18, + "execution_count": 7, "outputs": [], "source": [ "reset_giskard()\n", diff --git a/scripts/iai_robots/pr2/pr2_standalone_vrb.py b/scripts/iai_robots/pr2/pr2_standalone_vrb.py index bfe9e585eb..179d9a5e40 100755 --- a/scripts/iai_robots/pr2/pr2_standalone_vrb.py +++ b/scripts/iai_robots/pr2/pr2_standalone_vrb.py @@ -35,6 +35,6 @@ ] ), behavior_tree_config=StandAloneBTConfig(publish_tf=True, publish_js=False, debug_mode=True, - simulation_max_hz=10), + simulation_max_hz=20), qp_controller_config=QPControllerConfig(qp_solver=SupportedQPSolver.qpSWIFT)) giskard.live() From dc29430f9c70fcd61c2bb7a22a3515f6ac33a5e5 Mon Sep 17 00:00:00 2001 From: malte Date: Fri, 16 Aug 2024 08:40:32 +0200 Subject: [PATCH 33/43] configured stretch vrb for new markers --- scripts/iai_robots/stretch/stretch_standalone_vrb.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/scripts/iai_robots/stretch/stretch_standalone_vrb.py b/scripts/iai_robots/stretch/stretch_standalone_vrb.py index 6752227c72..b97b57c275 100755 --- a/scripts/iai_robots/stretch/stretch_standalone_vrb.py +++ b/scripts/iai_robots/stretch/stretch_standalone_vrb.py @@ -13,7 +13,7 @@ giskard = Giskard(world_config=WorldWithDiffDriveRobot(), collision_avoidance_config=StretchCollisionAvoidanceConfig(), robot_interface_config=StretchStandaloneInterface(), - behavior_tree_config=StandAloneBTConfig(publish_js=False, publish_tf=False, simulation_max_hz=20, + behavior_tree_config=StandAloneBTConfig(publish_js=False, publish_tf=True, simulation_max_hz=20, debug_mode=True), qp_controller_config=QPControllerConfig(qp_solver=SupportedQPSolver.qpSWIFT)) giskard.live() From 1e1fcb7583a0886a30cbd1fedfacb9b5f9da31ba Mon Sep 17 00:00:00 2001 From: malte Date: Fri, 16 Aug 2024 10:13:43 +0200 Subject: [PATCH 34/43] notebook changes --- scripts/giskard_examples.ipynb | 135 ++++++++++++++++++++------------- 1 file changed, 81 insertions(+), 54 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 71485fa2df..92ff600de0 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -1,5 +1,20 @@ { "cells": [ + { + "cell_type": "code", + "execution_count": 8, + "outputs": [], + "source": [ + "%%bash --bg\n", + "rviz -d ../launch/../launch/rviz_config/standalone.rviz" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, { "cell_type": "code", "execution_count": 1, @@ -18,7 +33,11 @@ "from IPython.display import display, Image\n", "from pdf2image import convert_from_path\n", "import os\n", - "import glob" + "import glob\n", + "import ipywidgets as widgets\n", + "from IPython.display import display\n", + "from giskardpy.utils.utils import launch_launchfile\n", + "import subprocess" ], "metadata": { "collapsed": false, @@ -32,7 +51,66 @@ "execution_count": 2, "outputs": [], "source": [ - "rospy.init_node('giskard_examples')\n" + "rospy.init_node('giskard_examples')" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [ + "global ROBOT\n", + "# List of available launch files\n", + "launch_files = {\n", + " 'PR2': 'package://giskardpy/launch/giskardpy_pr2_standalone_vrb.launch',\n", + " 'Stretch': 'package://giskardpy/launch/giskardpy_stretch_standalone_vrb.launch'\n", + "}\n", + "\n", + "# Dropdown widget\n", + "dropdown = widgets.Dropdown(\n", + " options=launch_files.keys(),\n", + " value='PR2',\n", + " description='Select Robot:',\n", + " style={'description_width': 'initial'},\n", + " layout=widgets.Layout(width='200px')\n", + ")\n", + "\n", + "# Button widget\n", + "button = widgets.Button(\n", + " description='Start Launch File',\n", + " button_style='success',\n", + ")\n", + "\n", + "\n", + "# Function to start the selected ROS launch file\n", + "def on_button_click(b):\n", + " selected_launch_file = launch_files[dropdown.value]\n", + " global ROBOT\n", + " ROBOT = dropdown.value.lower()\n", + " try:\n", + " result = subprocess.run('rosnode kill /giskard', shell=True, check=True, stdout=subprocess.PIPE,\n", + " stderr=subprocess.PIPE)\n", + " print(result.stdout.decode())\n", + " print(result.stderr.decode())\n", + " except subprocess.CalledProcessError as e:\n", + " print(f\"Error occurred: {e.stderr.decode()}\")\n", + "\n", + " print(f\"Starting ROS launch file: {selected_launch_file}\")\n", + " launch_launchfile(selected_launch_file)\n", + "\n", + "\n", + "# Attach the event handler to the button\n", + "button.on_click(on_button_click)\n", + "\n", + "# Display widgets\n", + "display(dropdown)\n", + "display(button)" ], "metadata": { "collapsed": false, @@ -46,7 +124,6 @@ "execution_count": 3, "outputs": [], "source": [ - "ROBOT = 'pr2'\n", "if ROBOT == 'stretch':\n", " single_joint_goal = {'joint_lift': 0.7}\n", " tool_frame = 'link_grasp_center'\n", @@ -1396,57 +1473,7 @@ "output_type": "display_data" } ], - "source": [ - "import ipywidgets as widgets\n", - "from IPython.display import display\n", - "from giskardpy.utils.utils import launch_launchfile\n", - "import subprocess\n", - "\n", - "# List of available launch files\n", - "launch_files = {\n", - " 'PR2': 'package://giskardpy/launch/giskardpy_pr2_standalone_vrb.launch',\n", - " 'Stretch': 'package://giskardpy/launch/giskardpy_stretch_standalone_vrb.launch'\n", - "}\n", - "\n", - "# Dropdown widget\n", - "dropdown = widgets.Dropdown(\n", - " options=launch_files.keys(),\n", - " value='PR2',\n", - " description='Select Robot:',\n", - " style={'description_width': 'initial'},\n", - " layout=widgets.Layout(width='200px')\n", - ")\n", - "\n", - "# Button widget\n", - "button = widgets.Button(\n", - " description='Start Launch File',\n", - " button_style='success',\n", - ")\n", - "\n", - "\n", - "# Function to start the selected ROS launch file\n", - "def on_button_click(b):\n", - " selected_launch_file = launch_files[dropdown.value]\n", - "\n", - " try:\n", - " result = subprocess.run('rosnode kill /giskard', shell=True, check=True, stdout=subprocess.PIPE,\n", - " stderr=subprocess.PIPE)\n", - " print(result.stdout.decode())\n", - " print(result.stderr.decode())\n", - " except subprocess.CalledProcessError as e:\n", - " print(f\"Error occurred: {e.stderr.decode()}\")\n", - "\n", - " print(f\"Starting ROS launch file: {selected_launch_file}\")\n", - " launch_launchfile(selected_launch_file)\n", - "\n", - "\n", - "# Attach the event handler to the button\n", - "button.on_click(on_button_click)\n", - "\n", - "# Display widgets\n", - "display(dropdown)\n", - "display(button)" - ], + "source": [], "metadata": { "collapsed": false, "pycharm": { From 60bf45be1fbbb106a34f8afc005b025b4d7bddb5 Mon Sep 17 00:00:00 2001 From: malte Date: Fri, 16 Aug 2024 12:50:27 +0200 Subject: [PATCH 35/43] stretch vrb vis collision mesh --- scripts/giskard_examples.ipynb | 60 +++++++++++++++---- .../stretch/stretch_standalone_vrb.py | 5 +- 2 files changed, 51 insertions(+), 14 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 92ff600de0..35ac13a463 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -17,7 +17,7 @@ }, { "cell_type": "code", - "execution_count": 1, + "execution_count": 10, "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", @@ -48,7 +48,7 @@ }, { "cell_type": "code", - "execution_count": 2, + "execution_count": 11, "outputs": [], "source": [ "rospy.init_node('giskard_examples')" @@ -62,10 +62,35 @@ }, { "cell_type": "code", - "execution_count": null, - "outputs": [], + "execution_count": 12, + "outputs": [ + { + "data": { + "text/plain": "Dropdown(description='Select Robot:', layout=Layout(width='200px'), options=('PR2', 'Stretch'), style=Descript…", + "application/vnd.jupyter.widget-view+json": { + "version_major": 2, + "version_minor": 0, + "model_id": "41ecd0f04d9f41eebcad5e9a77faacb2" + } + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "text/plain": "Button(button_style='success', description='Start Launch File', style=ButtonStyle())", + "application/vnd.jupyter.widget-view+json": { + "version_major": 2, + "version_minor": 0, + "model_id": "d778640d72e64143b3c36a52ec4244e2" + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ - "global ROBOT\n", + "ROBOT = 'stretch'\n", "# List of available launch files\n", "launch_files = {\n", " 'PR2': 'package://giskardpy/launch/giskardpy_pr2_standalone_vrb.launch',\n", @@ -91,7 +116,6 @@ "# Function to start the selected ROS launch file\n", "def on_button_click(b):\n", " selected_launch_file = launch_files[dropdown.value]\n", - " global ROBOT\n", " ROBOT = dropdown.value.lower()\n", " try:\n", " result = subprocess.run('rosnode kill /giskard', shell=True, check=True, stdout=subprocess.PIPE,\n", @@ -121,7 +145,7 @@ }, { "cell_type": "code", - "execution_count": 3, + "execution_count": 13, "outputs": [], "source": [ "if ROBOT == 'stretch':\n", @@ -142,7 +166,7 @@ }, { "cell_type": "code", - "execution_count": 4, + "execution_count": 14, "outputs": [], "source": [ "# Launch the giskardpy PR2 standalone launch file before this\n", @@ -157,7 +181,7 @@ }, { "cell_type": "code", - "execution_count": 5, + "execution_count": 15, "outputs": [], "source": [ "# Define some helper functions\n", @@ -272,7 +296,7 @@ }, { "cell_type": "code", - "execution_count": 6, + "execution_count": 16, "outputs": [], "source": [ "reset_giskard()\n", @@ -304,8 +328,20 @@ }, { "cell_type": "code", - "execution_count": 7, - "outputs": [], + "execution_count": 18, + "outputs": [ + { + "ename": "AssertionError", + "evalue": "", + "output_type": "error", + "traceback": [ + "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", + "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", + "Cell \u001B[0;32mIn[18], line 23\u001B[0m\n\u001B[1;32m 20\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 21\u001B[0m \u001B[38;5;66;03m# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\u001B[39;00m\n\u001B[1;32m 22\u001B[0m \u001B[38;5;66;03m# gs.add_default_end_motion_conditions()\u001B[39;00m\n\u001B[0;32m---> 23\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", + "\u001B[0;31mAssertionError\u001B[0m: " + ] + } + ], "source": [ "reset_giskard()\n", "\n", diff --git a/scripts/iai_robots/stretch/stretch_standalone_vrb.py b/scripts/iai_robots/stretch/stretch_standalone_vrb.py index b97b57c275..7e3c7f40b9 100755 --- a/scripts/iai_robots/stretch/stretch_standalone_vrb.py +++ b/scripts/iai_robots/stretch/stretch_standalone_vrb.py @@ -6,7 +6,7 @@ from giskardpy.configs.iai_robots.stretch import StretchCollisionAvoidanceConfig, StretchStandaloneInterface from giskardpy.configs.world_config import WorldWithDiffDriveRobot from giskardpy.configs.qp_controller_config import QPControllerConfig, SupportedQPSolver - +from giskardpy.model.ros_msg_visualization import VisualizationMode if __name__ == '__main__': rospy.init_node('giskard') @@ -14,6 +14,7 @@ collision_avoidance_config=StretchCollisionAvoidanceConfig(), robot_interface_config=StretchStandaloneInterface(), behavior_tree_config=StandAloneBTConfig(publish_js=False, publish_tf=True, simulation_max_hz=20, - debug_mode=True), + debug_mode=True, + visualization_mode=VisualizationMode.CollisionsDecomposedFrameLocked), qp_controller_config=QPControllerConfig(qp_solver=SupportedQPSolver.qpSWIFT)) giskard.live() From cd2cf82e508b8b79a624be8e9cf699538849dad0 Mon Sep 17 00:00:00 2001 From: malte Date: Fri, 16 Aug 2024 14:16:45 +0200 Subject: [PATCH 36/43] started better layout for the notebook --- scripts/giskard_examples.ipynb | 834 ++++++++++++++++----------------- 1 file changed, 412 insertions(+), 422 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 35ac13a463..e986e17124 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -1,8 +1,21 @@ { "cells": [ + { + "cell_type": "markdown", + "source": [ + "# Section 0: Preliminaries\n", + "Please execute the following code blocks to setup the visualization, relevant imports, some helper functions and the robot selector." + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%% md\n" + } + } + }, { "cell_type": "code", - "execution_count": 8, + "execution_count": 18, "outputs": [], "source": [ "%%bash --bg\n", @@ -17,7 +30,7 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 2, "outputs": [], "source": [ "from giskardpy.python_interface.python_interface import GiskardWrapper\n", @@ -48,140 +61,7 @@ }, { "cell_type": "code", - "execution_count": 11, - "outputs": [], - "source": [ - "rospy.init_node('giskard_examples')" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": 12, - "outputs": [ - { - "data": { - "text/plain": "Dropdown(description='Select Robot:', layout=Layout(width='200px'), options=('PR2', 'Stretch'), style=Descript…", - "application/vnd.jupyter.widget-view+json": { - "version_major": 2, - "version_minor": 0, - "model_id": "41ecd0f04d9f41eebcad5e9a77faacb2" - } - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { - "text/plain": "Button(button_style='success', description='Start Launch File', style=ButtonStyle())", - "application/vnd.jupyter.widget-view+json": { - "version_major": 2, - "version_minor": 0, - "model_id": "d778640d72e64143b3c36a52ec4244e2" - } - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "ROBOT = 'stretch'\n", - "# List of available launch files\n", - "launch_files = {\n", - " 'PR2': 'package://giskardpy/launch/giskardpy_pr2_standalone_vrb.launch',\n", - " 'Stretch': 'package://giskardpy/launch/giskardpy_stretch_standalone_vrb.launch'\n", - "}\n", - "\n", - "# Dropdown widget\n", - "dropdown = widgets.Dropdown(\n", - " options=launch_files.keys(),\n", - " value='PR2',\n", - " description='Select Robot:',\n", - " style={'description_width': 'initial'},\n", - " layout=widgets.Layout(width='200px')\n", - ")\n", - "\n", - "# Button widget\n", - "button = widgets.Button(\n", - " description='Start Launch File',\n", - " button_style='success',\n", - ")\n", - "\n", - "\n", - "# Function to start the selected ROS launch file\n", - "def on_button_click(b):\n", - " selected_launch_file = launch_files[dropdown.value]\n", - " ROBOT = dropdown.value.lower()\n", - " try:\n", - " result = subprocess.run('rosnode kill /giskard', shell=True, check=True, stdout=subprocess.PIPE,\n", - " stderr=subprocess.PIPE)\n", - " print(result.stdout.decode())\n", - " print(result.stderr.decode())\n", - " except subprocess.CalledProcessError as e:\n", - " print(f\"Error occurred: {e.stderr.decode()}\")\n", - "\n", - " print(f\"Starting ROS launch file: {selected_launch_file}\")\n", - " launch_launchfile(selected_launch_file)\n", - "\n", - "\n", - "# Attach the event handler to the button\n", - "button.on_click(on_button_click)\n", - "\n", - "# Display widgets\n", - "display(dropdown)\n", - "display(button)" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": 13, - "outputs": [], - "source": [ - "if ROBOT == 'stretch':\n", - " single_joint_goal = {'joint_lift': 0.7}\n", - " tool_frame = 'link_grasp_center'\n", - " cam_frame = 'camera_color_optical_frame'\n", - "elif ROBOT == 'pr2':\n", - " single_joint_goal = {'torso_lift_joint': 0.3}\n", - " tool_frame = 'l_gripper_tool_frame'\n", - " cam_frame = 'wide_stereo_optical_frame'" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": 14, - "outputs": [], - "source": [ - "# Launch the giskardpy PR2 standalone launch file before this\n", - "gs = GiskardWrapper()" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": 15, + "execution_count": 3, "outputs": [], "source": [ "# Define some helper functions\n", @@ -260,16 +140,106 @@ } } }, + { + "cell_type": "code", + "execution_count": null, + "outputs": [], + "source": [ + "# start ros node and robot selector\n", + "\n", + "# global variables\n", + "ROBOT = 'pr2'\n", + "single_joint_goal = {'torso_lift_joint': 0.3}\n", + "tool_frame = 'l_gripper_tool_frame'\n", + "cam_frame = 'wide_stereo_optical_frame'\n", + "base_link = 'base_footprint'\n", + "\n", + "# List of available launch files\n", + "launch_files = {\n", + " 'PR2': 'package://giskardpy/launch/giskardpy_pr2_standalone_vrb.launch',\n", + " 'Stretch': 'package://giskardpy/launch/giskardpy_stretch_standalone_vrb.launch'\n", + "}\n", + "\n", + "# Dropdown widget\n", + "dropdown = widgets.Dropdown(\n", + " options=launch_files.keys(),\n", + " value='PR2',\n", + " description='Select Robot:',\n", + " style={'description_width': 'initial'},\n", + " layout=widgets.Layout(width='200px')\n", + ")\n", + "\n", + "# Button widget\n", + "button = widgets.Button(\n", + " description='Start Launch File',\n", + " button_style='success',\n", + ")\n", + "\n", + "def update_global_variables(robot):\n", + " global ROBOT\n", + " global single_joint_goal\n", + " global tool_frame\n", + " global cam_frame\n", + " global base_link\n", + " if ROBOT == 'stretch':\n", + " single_joint_goal = {'joint_lift': 0.7}\n", + " tool_frame = 'link_grasp_center'\n", + " cam_frame = 'camera_color_optical_frame'\n", + " base_link = 'base_link'\n", + " elif ROBOT == 'pr2':\n", + " single_joint_goal = {'torso_lift_joint': 0.3}\n", + " tool_frame = 'l_gripper_tool_frame'\n", + " cam_frame = 'wide_stereo_optical_frame'\n", + " base_link = 'base_footprint'\n", + "\n", + "\n", + "# Function to start the selected ROS launch file\n", + "def on_button_click(b):\n", + " selected_launch_file = launch_files[dropdown.value]\n", + "\n", + " update_global_variables(dropdown.value.lower())\n", + "\n", + " try:\n", + " result = subprocess.run('rosnode kill /giskard', shell=True, check=True, stdout=subprocess.PIPE,\n", + " stderr=subprocess.PIPE)\n", + " print(result.stdout.decode())\n", + " print(result.stderr.decode())\n", + " except subprocess.CalledProcessError as e:\n", + " print(f\"Error occurred: {e.stderr.decode()}\")\n", + "\n", + " print(f\"Starting ROS launch file: {selected_launch_file}\")\n", + " launch_launchfile(selected_launch_file)\n", + "\n", + "\n", + "# Attach the event handler to the button\n", + "button.on_click(on_button_click)\n", + "\n", + "# Display widgets\n", + "display(dropdown)\n", + "display(button)\n", + "rospy.init_node('giskard_examples')" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n", + "is_executing": true + } + } + }, { "cell_type": "markdown", "source": [ + "# Section 1: Introduction\n", "Giskard is a constraint- and optimization-based whole-body motion planning/control framework.\n", "In short explain the QP...\n", "Explain a constraint and how it influences the QP...\n", "When using the python wrapper you do not specify constraints directly but rather a Motion Goal to parameterize a predefined set of constraints.\n", "Additionally, the python interface allows to specify monitors that monitor a mathematical expression against a threshold and evaluate into a binary value.\n", "They are used to start, stop or interrupt motion goals. More complex motion goals might specify their own monitors to chain constraints together.\n", - "Show picture of PR2 TF Tree..." + "Show picture of PR2 TF Tree...\n", + "\n", + "**Tutorial 1.1: Now initialize the Python Interface. It will connect to the running Giskard instance of your selected robot.**" ], "metadata": { "collapsed": false, @@ -278,14 +248,30 @@ } } }, + { + "cell_type": "code", + "execution_count": 5, + "outputs": [], + "source": [ + "gs = GiskardWrapper()" + ], + "metadata": { + "collapsed": false, + "pycharm": { + "name": "#%%\n" + } + } + }, { "cell_type": "markdown", "source": [ - "The simplest possible motion goal call follows the following schema:\n", + "**Tutorial 1.2: Use the defined motion goal to move a single joint of the robot**\n", + "\n", + "The simplest possible motion goal call follows the schema:\n", "\n", - " - Define a motion goal.\n", - " - Define a monitor that checks if the goal was reached.\n", - " - Define an end motion monitor, which has as start_condition the goal reached monitor.\n" + " 1. Define a motion goal.\n", + " 2. Define a monitor that checks if the goal was reached.\n", + " 3. Define an end motion monitor, which has as start_condition the goal reached monitor." ], "metadata": { "collapsed": false, @@ -296,12 +282,13 @@ }, { "cell_type": "code", - "execution_count": 16, + "execution_count": 6, "outputs": [], "source": [ "reset_giskard()\n", "\n", "joint_goal = single_joint_goal\n", + "print(joint_goal)\n", "joint_monitor = gs.monitors.add_joint_position(goal_state=joint_goal)\n", "gs.motion_goals.add_joint_position(goal_state=joint_goal)\n", "gs.monitors.add_end_motion(start_condition=joint_monitor)\n", @@ -317,7 +304,11 @@ { "cell_type": "markdown", "source": [ - "A commonly used goal is a cartesian pose goal. It is used to move a link of the robot to a specific pose. Frequently used links are the endeffector links or the base link." + "**Tutorial 1.3: Use the defined cartesian pose goal to move the tool frame of the robot**\n", + "\n", + "A commonly used goal is a cartesian pose goal. It is used to move a link of the robot to a specific pose. Frequently used links are the endeffector links or the base link.\n", + "\n", + "**Exercise 1.1: Change the orientation and position of the goal_pose and explore the generated movements**" ], "metadata": { "collapsed": false, @@ -328,20 +319,8 @@ }, { "cell_type": "code", - "execution_count": 18, - "outputs": [ - { - "ename": "AssertionError", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[18], line 23\u001B[0m\n\u001B[1;32m 20\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 21\u001B[0m \u001B[38;5;66;03m# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\u001B[39;00m\n\u001B[1;32m 22\u001B[0m \u001B[38;5;66;03m# gs.add_default_end_motion_conditions()\u001B[39;00m\n\u001B[0;32m---> 23\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", - "\u001B[0;31mAssertionError\u001B[0m: " - ] - } - ], + "execution_count": 7, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -357,11 +336,12 @@ "goal_pose.pose.position.z = 0.7\n", "# specify the cartesian pose goal to move 'l_gripper_tool_frame' towards goal_pose by using the kinematic chain between 'l_gripper_tool_frame' and 'map'\n", "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", - "# specify monitor that is active when it is below the given thresholds and use it to end the motion\n", + "# specify a monitor that is active when it is below the given thresholds and use it to end the motion\n", "pose_monitor = gs.monitors.add_cartesian_pose('map', tool_frame, goal_pose, position_threshold=0.01,\n", " orientation_threshold=0.01)\n", - "\n", + "# add a monitor that automatically stops the motion when the trajectory is too long\n", "gs.monitors.add_max_trajectory_length(30)\n", + "# use the pose monitor to end the motion when it is true\n", "gs.monitors.add_end_motion(pose_monitor)\n", "# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\n", "# gs.add_default_end_motion_conditions()\n", @@ -377,7 +357,12 @@ { "cell_type": "markdown", "source": [ - "When adding an object to the world of giskard one can specify goal poses also in its coordinate frame. This is true for all links that are part of giskards world representation." + "**Tutorial 1.4: Add a box to the world and specify a cartesian pose goal in its coordinate frame**\n", + "\n", + "One can also add different objects, meshes or URDF's to the world representation of Giskard.\n", + "When doing that, you can specify goal poses in the coordinate frames of the new entities.\n", + "\n", + "**Exercise 1.2: Change the box_pose and observe how giskard still reaches the same goal pose relative to the box**" ], "metadata": { "collapsed": false, @@ -388,20 +373,8 @@ }, { "cell_type": "code", - "execution_count": 9, - "outputs": [ - { - "ename": "AssertionError", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[9], line 24\u001B[0m\n\u001B[1;32m 22\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(pose_monitor)\n\u001B[1;32m 23\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_max_trajectory_length(\u001B[38;5;241m30\u001B[39m)\n\u001B[0;32m---> 24\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", - "\u001B[0;31mAssertionError\u001B[0m: " - ] - } - ], + "execution_count": null, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -431,28 +404,33 @@ "metadata": { "collapsed": false, "pycharm": { - "name": "#%%\n" + "name": "#%%\n", + "is_executing": true } } }, { "cell_type": "markdown", "source": [ - "When using the cartesian goals all degrees of freedom of the link are fully constrained. One Advantage of constraint-based control is that one can only constrain neccessary constraints.\n", + "**Tutorial 1.5: Use sets of atomic constraints to specify a motion instead of using a full 6D-Pose**\n", + "\n", + "When using the cartesian pose goals all degrees of freedom of the link are fully constrained. One Advantage of constraint-based control is that one can only constrain necessary constraints.\n", "The unconstrained DOF can then be exploited during the motion, for example in the collision avoidance or other secondary tasks.\n", - "To use this in the python interface one can use motion goals that constrain only a singualar value, here also called constraints on feature functions.\n", - "For a feature function constraint a feature (Point or Vector) related to the robot and one related to the world has to be defined.\n", + "To use this in the python interface one can use motion goals that constrain only a singular value, sometimes called constraints on feature functions ot atomic constraints.\n", + "For a feature function constraint a feature (Point or Vector) related to the robot (it has to be controllable) and one that is used as a reference has to be defined.\n", "The name of the function then defines how they will be combined and 0 or 2 constraint values can be provided.\n", - "Right now we support the following feature functions:\n", + "Right now we support the following atomic constraints:\n", + "\n", + " - Perpendicular(reference_vector, controlled_vector)\n", + " - Height(reference_point, controlled_point, lower_limit, upper_limit)\n", + " - Distance(reference_point, controlled_point, lower_limit, upper_limit)\n", + " - Pointing(reference_point, controlled_vector)\n", + " - Align(reference_vector, controlled_vector)\n", + " - Angle(reference_vector, controlled_vector, lower_limit, upper_limit)\n", "\n", - " - Perpendicular(world_vector, robot_vector)\n", - " - Height(world_point, robot_point, lower_limit, upper_limit)\n", - " - Distance(world_point, robot_point, lower_limit, upper_limit)\n", - " - Pointing(world_point, robot_vector)\n", - " - Align(world_vector, robot_vector)\n", - " - Angle(world_vector, robot_vector, lower_limit, upper_limit)\n", + "The controlled and reference features will be visualized as points or vectors in space.\n", "\n", - "Robot features will be visualized as red points or arrows and world features have the color green." + "Here a distance constraint between the origin points of the tool link and the map coordinate frames is defined." ], "metadata": { "collapsed": false, @@ -463,7 +441,7 @@ }, { "cell_type": "code", - "execution_count": 10, + "execution_count": 9, "outputs": [], "source": [ "reset_giskard()\n", @@ -497,11 +475,16 @@ { "cell_type": "markdown", "source": [ - "Now for positioning the gripper to grasp a cylindrical object one can use three different feature function constraints\n", + "**Tutorial 1.6: Combine atomic constraints for grasping**\n", + "We can exploit the rotational symmetry of a cylinder for grasping it if we specify the grasping motion with atomic constraints instead of with one fixed cartesian pose.\n", + "Here we use three different atomic constraints to achieve this.\n", "\n", "1. Pointing the gripper towards the object center\n", "2. keeping a suitable distance\n", - "3. constrain the height to be within the dimensions of the objects" + "3. constrain the height to be within the dimensions of the objects\n", + "\n", + "**Excercise 1.3: Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.**\n", + "**Excercise 1.4: You might notice that at some positions the rotation of the gripper is not correct. This is due to a missing atomic constraint that allows the gripper_frame to freely rotate around its x-axis. Try to constrain this using the AlignFeatureFunction. You can visualize tf in rviz to see all coordinate frames**" ], "metadata": { "collapsed": false, @@ -512,20 +495,8 @@ }, { "cell_type": "code", - "execution_count": 12, - "outputs": [ - { - "ename": "AssertionError", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[12], line 59\u001B[0m\n\u001B[1;32m 53\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39madd_align_planes(root_link\u001B[38;5;241m=\u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;124mmap\u001B[39m\u001B[38;5;124m'\u001B[39m,\n\u001B[1;32m 54\u001B[0m tip_link\u001B[38;5;241m=\u001B[39mgripper_link,\n\u001B[1;32m 55\u001B[0m goal_normal\u001B[38;5;241m=\u001B[39mworld_cyl_z_axis_feature,\n\u001B[1;32m 56\u001B[0m tip_normal\u001B[38;5;241m=\u001B[39mrobot_gripper_z_axis_feature)\n\u001B[1;32m 58\u001B[0m gs\u001B[38;5;241m.\u001B[39madd_default_end_motion_conditions()\n\u001B[0;32m---> 59\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n\u001B[1;32m 61\u001B[0m \u001B[38;5;66;03m# EXERCISE:\u001B[39;00m\n\u001B[1;32m 62\u001B[0m \u001B[38;5;66;03m# 1. Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.\u001B[39;00m\n\u001B[1;32m 63\u001B[0m \u001B[38;5;66;03m# 2. You might notice that not all poses are feasible. This is due to a missing that constraint that allows the gripper_frame to freely rotate around its x-axis. Try to constrain this using the AlignFeatureFunction\u001B[39;00m\n", - "\u001B[0;31mAssertionError\u001B[0m: " - ] - } - ], + "execution_count": null, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -570,38 +541,28 @@ " tip_link=gripper_link,\n", " goal_point=world_cylinder_center_feature,\n", " pointing_axis=robot_pointing_feature)\n", - "# EXCERCISE SOLUTION:\n", - "# robot_gripper_z_axis_feature = Vector3Stamped()\n", - "# robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", - "# robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "#\n", - "# world_cyl_z_axis_feature = Vector3Stamped()\n", - "# world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", - "# world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "#\n", - "# gs.motion_goals.add_align_planes(root_link='map',\n", - "# tip_link=gripper_link,\n", - "# goal_normal=world_cyl_z_axis_feature,\n", - "# tip_normal=robot_gripper_z_axis_feature)\n", "\n", - "gs.add_default_end_motion_conditions()\n", - "assert gs.execute().error.code == GiskardError.SUCCESS\n", + "#Exercise 1.4: You can define your features and your motion goal here\n", "\n", - "# EXERCISE:\n", - "# 1. Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.\n", - "# 2. You might notice that not all poses are feasible. This is due to a missing that constraint that allows the gripper_frame to freely rotate around its x-axis. Try to constrain this using the AlignFeatureFunction" + "gs.add_default_end_motion_conditions()\n", + "assert gs.execute().error.code == GiskardError.SUCCESS" ], "metadata": { "collapsed": false, "pycharm": { - "name": "#%%\n" + "name": "#%%\n", + "is_executing": true } } }, { "cell_type": "markdown", "source": [ - "Another advantage of having unconstrained DOF in the motion specification can be seen if we put an obstacle in front of the object we want to grasp and configure the collision avoidance to avoid this obstacle with all parts of the robot." + "**Tutorial 1.7:Adding collision avoidance**\n", + "Another advantage of having unconstrained DOF in the motion specification can be seen if we put an obstacle in front of the object we want to grasp and configure the collision avoidance to avoid this obstacle with all parts of the robot.\n", + "\n", + "**Excercise 1.5: change the position and the size of the obstacle and observe the resulting motions**\n", + "PS: this cell includes the solution to the previous exercise" ], "metadata": { "collapsed": false, @@ -612,20 +573,8 @@ }, { "cell_type": "code", - "execution_count": 24, - "outputs": [ - { - "ename": "AssertionError", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[24], line 64\u001B[0m\n\u001B[1;32m 59\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39madd_align_planes(root_link\u001B[38;5;241m=\u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;124mmap\u001B[39m\u001B[38;5;124m'\u001B[39m,\n\u001B[1;32m 60\u001B[0m tip_link\u001B[38;5;241m=\u001B[39mgripper_link,\n\u001B[1;32m 61\u001B[0m goal_normal\u001B[38;5;241m=\u001B[39mworld_cyl_z_axis_feature,\n\u001B[1;32m 62\u001B[0m tip_normal\u001B[38;5;241m=\u001B[39mrobot_gripper_z_axis_feature)\n\u001B[1;32m 63\u001B[0m gs\u001B[38;5;241m.\u001B[39madd_default_end_motion_conditions()\n\u001B[0;32m---> 64\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n\u001B[1;32m 66\u001B[0m \u001B[38;5;66;03m# EXERCISE:\u001B[39;00m\n\u001B[1;32m 67\u001B[0m \u001B[38;5;66;03m# 1. Change Pose and size of the obstacle and see of the robot behaves.\u001B[39;00m\n", - "\u001B[0;31mAssertionError\u001B[0m: " - ] - } - ], + "execution_count": 11, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -705,7 +654,12 @@ { "cell_type": "markdown", "source": [ - "Now, for each constraint a related monitor can be added to observe their progression and collect feedback in the case of failure where one or many constraints cannot be satisfied." + "**Tutorial 1.8: Use monitors to evaluate the success of your specified motion**\n", + "\n", + "For each constraint a related monitor can be added to observe their progression and collect feedback in the case of failure where one or many constraints cannot be satisfied.\n", + "A Motion was not sucessfull if the end motion monitor was not active and the goal was canceled by another monitor. In that case the return value of the execute() call can be passed to the get_end_motion_reason() function to obtain a summary of all monitors that are connected to the end motion that are not active.\n", + "\n", + "**Excercise 1.6: The output tells you which monitor of the end motion was not successful. Try changing/removing/adding constraint and monitors to realize a successful execution.**" ], "metadata": { "collapsed": false, @@ -716,16 +670,8 @@ }, { "cell_type": "code", - "execution_count": 26, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "{'DistanceMonitor': False, 'PointingAt': False}\n" - ] - } - ], + "execution_count": null, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -819,14 +765,13 @@ " error_message='local minimum reached while monitors are not satisfied')\n", "result = gs.execute()\n", "if result.error.code != GiskardError.SUCCESS:\n", - " print(gs.get_end_motion_reason(show_all=False))\n", - "# EXERCISE:\n", - "# The output tells you which monitor of the end motion was not successful. Try changing/removing/adding constraint and monitors to realize a successful execution." + " print(gs.get_end_motion_reason(move_result=result, show_all=False))" ], "metadata": { "collapsed": false, "pycharm": { - "name": "#%%\n" + "name": "#%%\n", + "is_executing": true } } }, @@ -848,20 +793,8 @@ }, { "cell_type": "code", - "execution_count": 41, - "outputs": [ - { - "ename": "AssertionError", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mAssertionError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[41], line 117\u001B[0m\n\u001B[1;32m 115\u001B[0m gs\u001B[38;5;241m.\u001B[39madd_default_end_motion_conditions()\n\u001B[1;32m 116\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39mallow_all_collisions()\n\u001B[0;32m--> 117\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m gs\u001B[38;5;241m.\u001B[39mexecute()\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n\u001B[1;32m 119\u001B[0m \u001B[38;5;66;03m# EXERCISE:\u001B[39;00m\n\u001B[1;32m 120\u001B[0m \u001B[38;5;66;03m# 1.Comment the BaseArmWeightScaling and MaxManipulabilityLinWeight Goals to observe the resulting motions when the cost function is not augmented.\u001B[39;00m\n", - "\u001B[0;31mAssertionError\u001B[0m: " - ] - } - ], + "execution_count": 13, + "outputs": [], "source": [ "reset_giskard()\n", "# This is eventually not feasible for the stretch\n", @@ -1006,8 +939,111 @@ }, { "cell_type": "code", - "execution_count": 51, - "outputs": [], + "execution_count": 15, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[INFO] [1723806571.570577]: [/giskard]: Adding motion goal of type: 'AlignPlanes' named: 'AlignPlanes'\n", + "[INFO] [1723806571.573567]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723806571.682588]: [/giskard]: Adding 27 external collision avoidance constraints.\n", + "[INFO] [1723806572.172306]: [/giskard]: Adding 53 self collision avoidance constraints.\n", + "[INFO] [1723806572.195546]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723806572.211189]: [/giskard]: Using QP Solver 'qpSWIFT'\n", + "[INFO] [1723806572.211939]: [/giskard]: Prediction horizon: '9'\n", + "[INFO] [1723806572.212564]: [/giskard]: Creating controller\n", + "[INFO] [1723806572.539508]: [/giskard]: Done compiling controller:\n", + "[INFO] [1723806572.540666]: [/giskard]: #free variables: 571\n", + "[INFO] [1723806572.541252]: [/giskard]: #equality constraints: 346\n", + "[INFO] [1723806572.541791]: [/giskard]: #inequality constraints: 85\n", + "[INFO] [1723806572.583099]: [/giskard]: Compiled 6 debug expressions.\n", + "[INFO] [1723806572.700569]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_13.png.\n", + "[INFO] [1723806588.615921]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_13.pdf.\n", + "[INFO] [1723806589.766156]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723806590.796143]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/debug.pdf\n", + "[INFO] [1723806590.935641]: [/giskard]: Received new goal.\n", + "[INFO] [1723806590.940352]: [/giskard]: Processing world goal #13.\n", + "[INFO] [1723806591.332973]: [/giskard]: Cleared world.\n", + "[INFO] [1723806591.334426]: [/giskard]: Finished world goal #13.\n", + "[INFO] [1723806591.618341]: [/giskard]: Received new goal.\n", + "[INFO] [1723806591.626747]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723806591.627646]: [/giskard]: Parsing goal #14 message.\n", + "[INFO] [1723806591.628349]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", + "[INFO] [1723806591.629016]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", + "[INFO] [1723806591.629856]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723806591.631047]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723806591.634093]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723806591.686702]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_14.png.\n", + "[INFO] [1723806591.975511]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_14.pdf.\n", + "[INFO] [1723806592.393872]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723806592.421488]: [/giskard]: Planning succeeded.\n", + "[INFO] [1723806592.472902]: [/giskard]: Received new goal.\n", + "[INFO] [1723806592.490695]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723806592.494289]: [/giskard]: Parsing goal #15 message.\n", + "[INFO] [1723806592.497405]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", + "[INFO] [1723806592.499881]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723806592.502301]: [/giskard]: Adding monitor of type: 'CancelMotion'\n", + "[INFO] [1723806592.504028]: [/giskard]: Adding monitor of type: 'SetMaxTrajectoryLength'\n", + "[INFO] [1723806592.505931]: [/giskard]: Adding motion goal of type: 'JointPositionList' named: 'JointPositionList'\n", + "[INFO] [1723806592.520334]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723806592.522767]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723806592.525977]: [/giskard]: Using QP Solver 'qpSWIFT'\n", + "[INFO] [1723806592.526967]: [/giskard]: Prediction horizon: '9'\n", + "[INFO] [1723806592.527739]: [/giskard]: Creating controller\n", + "[INFO] [1723806592.677536]: [/giskard]: Done compiling controller:\n", + "[INFO] [1723806592.678498]: [/giskard]: #free variables: 400\n", + "[INFO] [1723806592.679112]: [/giskard]: #equality constraints: 288\n", + "[INFO] [1723806592.679704]: [/giskard]: #inequality constraints: 0\n", + "[INFO] [1723806592.749687]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_15.png.\n", + "[INFO] [1723806595.746482]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_15.pdf.\n", + "[INFO] [1723806596.347647]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723806596.362730]: [/giskard]: Planning succeeded.\n", + "[INFO] [1723806596.408348]: [/giskard]: Received new goal.\n", + "[INFO] [1723806596.413772]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723806596.414768]: [/giskard]: Parsing goal #16 message.\n", + "[INFO] [1723806596.415663]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", + "[INFO] [1723806596.416599]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723806596.417748]: [/giskard]: Adding monitor of type: 'CancelMotion'\n", + "[INFO] [1723806596.418901]: [/giskard]: Adding monitor of type: 'SetMaxTrajectoryLength'\n", + "[INFO] [1723806596.420061]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'CartesianPose'\n", + "[INFO] [1723806596.434909]: [/giskard]: Adding motion goal of type: 'Pointing' named: 'Pointing'\n", + "[INFO] [1723806596.440115]: [/giskard]: Adding motion goal of type: 'AlignPlanes' named: 'AlignPlanes'\n", + "[INFO] [1723806596.444280]: [/giskard]: Adding motion goal of type: 'BaseArmWeightScaling' named: 'BaseArmWeightScaling'\n", + "[INFO] [1723806596.469411]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723806596.472269]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723806596.474784]: [/giskard]: Using QP Solver 'qpSWIFT'\n", + "[INFO] [1723806596.475383]: [/giskard]: Prediction horizon: '9'\n", + "[INFO] [1723806596.475957]: [/giskard]: Creating controller\n", + "[INFO] [1723806596.579192]: [/giskard]: Done compiling controller:\n", + "[INFO] [1723806596.580118]: [/giskard]: #free variables: 324\n", + "[INFO] [1723806596.580745]: [/giskard]: #equality constraints: 233\n", + "[INFO] [1723806596.581340]: [/giskard]: #inequality constraints: 0\n", + "[INFO] [1723806596.589298]: [/giskard]: Compiled 11 debug expressions.\n", + "[INFO] [1723806596.693300]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_16.png.\n", + "[INFO] [1723806603.775733]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_16.pdf.\n", + "[INFO] [1723806604.629393]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723806605.377060]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/debug.pdf\n", + "[INFO] [1723806605.411690]: [/giskard]: Planning succeeded.\n", + "[INFO] [1723806605.449113]: [/giskard]: Received new goal.\n", + "[INFO] [1723806605.450298]: [/giskard]: Processing world goal #14.\n", + "[INFO] [1723806605.787736]: [/giskard]: Cleared world.\n", + "[INFO] [1723806605.798786]: [/giskard]: Finished world goal #14.\n", + "[INFO] [1723806606.070354]: [/giskard]: Received new goal.\n", + "[INFO] [1723806606.076234]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723806606.077105]: [/giskard]: Parsing goal #17 message.\n", + "[INFO] [1723806606.077890]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", + "[INFO] [1723806606.078654]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", + "[INFO] [1723806606.079538]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723806606.080662]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723806606.083363]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723806606.138460]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_17.png.\n", + "[INFO] [1723806606.432122]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_17.pdf.\n", + "[INFO] [1723806606.857384]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723806606.870070]: [/giskard]: Planning succeeded.\n" + ] + } + ], "source": [ "reset_giskard()\n", "\n", @@ -1126,25 +1162,8 @@ }, { "cell_type": "code", - "execution_count": 53, - "outputs": [ - { - "ename": "KeyboardInterrupt", - "evalue": "", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mKeyboardInterrupt\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[53], line 43\u001B[0m\n\u001B[1;32m 41\u001B[0m gs\u001B[38;5;241m.\u001B[39mmotion_goals\u001B[38;5;241m.\u001B[39mallow_all_collisions()\n\u001B[1;32m 42\u001B[0m gs\u001B[38;5;241m.\u001B[39mmonitors\u001B[38;5;241m.\u001B[39madd_end_motion(start_condition\u001B[38;5;241m=\u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;124m and \u001B[39m\u001B[38;5;124m'\u001B[39m\u001B[38;5;241m.\u001B[39mjoin([end_monitor, monitor2]))\n\u001B[0;32m---> 43\u001B[0m \u001B[38;5;28;01massert\u001B[39;00m \u001B[43mgs\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mexecute\u001B[49m\u001B[43m(\u001B[49m\u001B[43m)\u001B[49m\u001B[38;5;241m.\u001B[39merror\u001B[38;5;241m.\u001B[39mcode \u001B[38;5;241m==\u001B[39m GiskardError\u001B[38;5;241m.\u001B[39mSUCCESS\n", - "File \u001B[0;32m~/workspace/new_giskard_ws/src/giskardpy/src/giskardpy/python_interface/python_interface.py:1992\u001B[0m, in \u001B[0;36mGiskardWrapper.execute\u001B[0;34m(self, wait)\u001B[0m\n\u001B[1;32m 1987\u001B[0m \u001B[38;5;28;01mdef\u001B[39;00m \u001B[38;5;21mexecute\u001B[39m(\u001B[38;5;28mself\u001B[39m, wait: \u001B[38;5;28mbool\u001B[39m \u001B[38;5;241m=\u001B[39m \u001B[38;5;28;01mTrue\u001B[39;00m) \u001B[38;5;241m-\u001B[39m\u001B[38;5;241m>\u001B[39m MoveResult:\n\u001B[1;32m 1988\u001B[0m \u001B[38;5;250m \u001B[39m\u001B[38;5;124;03m\"\"\"\u001B[39;00m\n\u001B[1;32m 1989\u001B[0m \u001B[38;5;124;03m :param wait: this function blocks if wait=True\u001B[39;00m\n\u001B[1;32m 1990\u001B[0m \u001B[38;5;124;03m :return: result from giskard\u001B[39;00m\n\u001B[1;32m 1991\u001B[0m \u001B[38;5;124;03m \"\"\"\u001B[39;00m\n\u001B[0;32m-> 1992\u001B[0m result \u001B[38;5;241m=\u001B[39m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43m_send_action_goal\u001B[49m\u001B[43m(\u001B[49m\u001B[43mMoveGoal\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mEXECUTE\u001B[49m\u001B[43m,\u001B[49m\u001B[43m \u001B[49m\u001B[43mwait\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 1993\u001B[0m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39mlast_execution_state \u001B[38;5;241m=\u001B[39m result\u001B[38;5;241m.\u001B[39mexecution_state\n\u001B[1;32m 1994\u001B[0m \u001B[38;5;28;01mreturn\u001B[39;00m result\n", - "File \u001B[0;32m~/workspace/new_giskard_ws/src/giskardpy/src/giskardpy/python_interface/python_interface.py:2017\u001B[0m, in \u001B[0;36mGiskardWrapper._send_action_goal\u001B[0;34m(self, goal_type, wait)\u001B[0m\n\u001B[1;32m 2015\u001B[0m goal\u001B[38;5;241m.\u001B[39mtype \u001B[38;5;241m=\u001B[39m goal_type\n\u001B[1;32m 2016\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m wait:\n\u001B[0;32m-> 2017\u001B[0m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43m_client\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43msend_goal_and_wait\u001B[49m\u001B[43m(\u001B[49m\u001B[43mgoal\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 2018\u001B[0m \u001B[38;5;28;01mreturn\u001B[39;00m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39m_client\u001B[38;5;241m.\u001B[39mget_result()\n\u001B[1;32m 2019\u001B[0m \u001B[38;5;28;01melse\u001B[39;00m:\n", - "File \u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/actionlib/simple_action_client.py:111\u001B[0m, in \u001B[0;36mSimpleActionClient.send_goal_and_wait\u001B[0;34m(self, goal, execute_timeout, preempt_timeout)\u001B[0m\n\u001B[1;32m 109\u001B[0m \u001B[38;5;28;01mdef\u001B[39;00m \u001B[38;5;21msend_goal_and_wait\u001B[39m(\u001B[38;5;28mself\u001B[39m, goal, execute_timeout\u001B[38;5;241m=\u001B[39mrospy\u001B[38;5;241m.\u001B[39mDuration(), preempt_timeout\u001B[38;5;241m=\u001B[39mrospy\u001B[38;5;241m.\u001B[39mDuration()):\n\u001B[1;32m 110\u001B[0m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39msend_goal(goal)\n\u001B[0;32m--> 111\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m \u001B[38;5;129;01mnot\u001B[39;00m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mwait_for_result\u001B[49m\u001B[43m(\u001B[49m\u001B[43mexecute_timeout\u001B[49m\u001B[43m)\u001B[49m:\n\u001B[1;32m 112\u001B[0m \u001B[38;5;66;03m# preempt action\u001B[39;00m\n\u001B[1;32m 113\u001B[0m rospy\u001B[38;5;241m.\u001B[39mlogdebug(\u001B[38;5;124m\"\u001B[39m\u001B[38;5;124mCanceling goal\u001B[39m\u001B[38;5;124m\"\u001B[39m)\n\u001B[1;32m 114\u001B[0m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39mcancel_goal()\n", - "File \u001B[0;32m/opt/ros/noetic/lib/python3/dist-packages/actionlib/simple_action_client.py:143\u001B[0m, in \u001B[0;36mSimpleActionClient.wait_for_result\u001B[0;34m(self, timeout)\u001B[0m\n\u001B[1;32m 140\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m time_left \u001B[38;5;241m>\u001B[39m loop_period \u001B[38;5;129;01mor\u001B[39;00m timeout \u001B[38;5;241m==\u001B[39m rospy\u001B[38;5;241m.\u001B[39mDuration():\n\u001B[1;32m 141\u001B[0m time_left \u001B[38;5;241m=\u001B[39m loop_period\n\u001B[0;32m--> 143\u001B[0m \u001B[38;5;28;43mself\u001B[39;49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mdone_condition\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mwait\u001B[49m\u001B[43m(\u001B[49m\u001B[43mtime_left\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43mto_sec\u001B[49m\u001B[43m(\u001B[49m\u001B[43m)\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 145\u001B[0m \u001B[38;5;28;01mreturn\u001B[39;00m \u001B[38;5;28mself\u001B[39m\u001B[38;5;241m.\u001B[39msimple_state \u001B[38;5;241m==\u001B[39m SimpleGoalState\u001B[38;5;241m.\u001B[39mDONE\n", - "File \u001B[0;32m/usr/lib/python3.8/threading.py:306\u001B[0m, in \u001B[0;36mCondition.wait\u001B[0;34m(self, timeout)\u001B[0m\n\u001B[1;32m 304\u001B[0m \u001B[38;5;28;01melse\u001B[39;00m:\n\u001B[1;32m 305\u001B[0m \u001B[38;5;28;01mif\u001B[39;00m timeout \u001B[38;5;241m>\u001B[39m \u001B[38;5;241m0\u001B[39m:\n\u001B[0;32m--> 306\u001B[0m gotit \u001B[38;5;241m=\u001B[39m \u001B[43mwaiter\u001B[49m\u001B[38;5;241;43m.\u001B[39;49m\u001B[43macquire\u001B[49m\u001B[43m(\u001B[49m\u001B[38;5;28;43;01mTrue\u001B[39;49;00m\u001B[43m,\u001B[49m\u001B[43m \u001B[49m\u001B[43mtimeout\u001B[49m\u001B[43m)\u001B[49m\n\u001B[1;32m 307\u001B[0m \u001B[38;5;28;01melse\u001B[39;00m:\n\u001B[1;32m 308\u001B[0m gotit \u001B[38;5;241m=\u001B[39m waiter\u001B[38;5;241m.\u001B[39macquire(\u001B[38;5;28;01mFalse\u001B[39;00m)\n", - "\u001B[0;31mKeyboardInterrupt\u001B[0m: " - ] - } - ], + "execution_count": 19, + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -1154,12 +1173,12 @@ "pose1.pose.orientation.w = 1\n", "\n", "pose2 = PoseStamped()\n", - "pose2.header.frame_id = 'base_link'\n", + "pose2.header.frame_id = base_link\n", "pose2.pose.position.y = 1\n", "pose2.pose.orientation.w = 1\n", "\n", "root_link = 'map'\n", - "tip_link = 'base_link'\n", + "tip_link = base_link\n", "\n", "monitor1 = gs.monitors.add_cartesian_pose(name='pose1',\n", " root_link=root_link,\n", @@ -1211,20 +1230,8 @@ }, { "cell_type": "code", - "execution_count": 44, - "outputs": [ - { - "ename": "NameError", - "evalue": "name 'visualize_last_task_graph' is not defined", - "output_type": "error", - "traceback": [ - "\u001B[0;31m---------------------------------------------------------------------------\u001B[0m", - "\u001B[0;31mNameError\u001B[0m Traceback (most recent call last)", - "Cell \u001B[0;32mIn[44], line 1\u001B[0m\n\u001B[0;32m----> 1\u001B[0m \u001B[43mvisualize_last_task_graph\u001B[49m()\n", - "\u001B[0;31mNameError\u001B[0m: name 'visualize_last_task_graph' is not defined" - ] - } - ], + "execution_count": null, + "outputs": [], "source": [ "visualize_last_task_graph()" ], @@ -1249,25 +1256,8 @@ }, { "cell_type": "code", - "execution_count": 41, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "../tmp/gantt_charts/goal_33.pdf\n" - ] - }, - { - "data": { - "text/plain": "", - "image/png": "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", - "image/jpeg": "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" - }, - "metadata": {}, - "output_type": "display_data" - } - ], + "execution_count": null, + "outputs": [], "source": [ "visualize_last_gant_diagram()" ], @@ -1292,8 +1282,102 @@ }, { "cell_type": "code", - "execution_count": 49, - "outputs": [], + "execution_count": 20, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[/unnamed]: Found these qp solvers: ['gurobi', 'qpalm', 'qpSWIFT']\n", + "[INFO] [1723807065.286638]: [/giskard]: Using betterpybullet for collision checking.\n", + "[INFO] [1723807065.859133]: [/giskard]: loading self collision matrix: /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/self_collision_matrices/iai/pr2.srdf\n", + "[INFO] [1723807065.937747]: [/giskard]: Loaded self collision matrix: /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/self_collision_matrices/iai/pr2.srdf\n", + "[INFO] [1723807065.960007]: [/giskard]: The following joints are non-fixed according to the urdf, but not flagged as controlled: {'pr2/fl_caster_rotation_joint', 'pr2/laser_tilt_mount_joint', 'pr2/br_caster_r_wheel_joint', 'pr2/torso_lift_motor_screw_joint', 'pr2/fl_caster_r_wheel_joint', 'pr2/r_gripper_motor_slider_joint', 'pr2/r_gripper_l_finger_joint', 'pr2/l_gripper_l_finger_joint', 'pr2/r_gripper_r_finger_joint', 'pr2/bl_caster_r_wheel_joint', 'pr2/l_gripper_r_finger_joint', 'pr2/bl_caster_l_wheel_joint', 'pr2/br_caster_rotation_joint', 'pr2/fl_caster_l_wheel_joint', 'pr2/l_gripper_l_finger_tip_joint', 'pr2/fr_caster_rotation_joint', 'pr2/l_gripper_motor_slider_joint', 'pr2/l_gripper_motor_screw_joint', 'pr2/r_gripper_l_finger_tip_joint', 'pr2/l_gripper_joint', 'pr2/r_gripper_motor_screw_joint', 'pr2/fr_caster_l_wheel_joint', 'pr2/fr_caster_r_wheel_joint', 'pr2/bl_caster_rotation_joint', 'pr2/r_gripper_r_finger_tip_joint', 'pr2/r_gripper_joint', 'pr2/br_caster_l_wheel_joint', 'pr2/l_gripper_r_finger_tip_joint'}.\n", + "[INFO] [1723807065.981247]: [/giskard]: giskard is ready\n", + "[INFO] [1723807086.831508]: [/giskard]: Received new goal.\n", + "[INFO] [1723807086.832688]: [/giskard]: Processing world goal #0.\n", + "[INFO] [1723807087.210308]: [/giskard]: Cleared world.\n", + "[INFO] [1723807087.231439]: [/giskard]: Finished world goal #0.\n", + "[INFO] [1723807087.512594]: [/giskard]: Received new goal.\n", + "[INFO] [1723807087.519318]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723807087.519993]: [/giskard]: Parsing goal #0 message.\n", + "[INFO] [1723807087.520574]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", + "[INFO] [1723807087.521179]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", + "[INFO] [1723807087.521962]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723807087.522996]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723807087.525968]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723807087.569212]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_0.png.\n", + "[INFO] [1723807088.031554]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_0.pdf.\n", + "[INFO] [1723807088.433189]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723807088.466379]: [/giskard]: Planning succeeded.\n", + "[INFO] [1723807088.516594]: [/giskard]: Received new goal.\n", + "[INFO] [1723807088.584568]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723807088.585489]: [/giskard]: Parsing goal #1 message.\n", + "[INFO] [1723807088.586139]: [/giskard]: Adding monitor of type: 'PoseReached'\n", + "[INFO] [1723807088.591531]: [/giskard]: Adding monitor of type: 'PoseReached'\n", + "[INFO] [1723807088.596630]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", + "[INFO] [1723807088.597322]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723807088.598286]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'g1'\n", + "[INFO] [1723807088.606436]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'g2'\n", + "[INFO] [1723807088.615076]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723807088.617663]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723807088.620088]: [/giskard]: Using QP Solver 'qpSWIFT'\n", + "[INFO] [1723807088.620681]: [/giskard]: Prediction horizon: '9'\n", + "[INFO] [1723807088.621227]: [/giskard]: Creating controller\n", + "[INFO] [1723807088.644418]: [/giskard]: Done compiling controller:\n", + "[INFO] [1723807088.645182]: [/giskard]: #free variables: 84\n", + "[INFO] [1723807088.645770]: [/giskard]: #equality constraints: 63\n", + "[INFO] [1723807088.646387]: [/giskard]: #inequality constraints: 0\n", + "[INFO] [1723807088.651133]: [/giskard]: Compiled 6 debug expressions.\n", + "[INFO] [1723807088.735526]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_1.png.\n", + "[INFO] [1723807099.747908]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_1.pdf.\n", + "[INFO] [1723807100.435799]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723807101.156740]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/debug.pdf\n", + "[INFO] [1723807101.177870]: [/giskard]: Planning succeeded.\n", + "[INFO] [1723807103.308165]: [/giskard]: Received new goal.\n", + "[INFO] [1723807103.309293]: [/giskard]: Processing world goal #1.\n", + "[INFO] [1723807103.700113]: [/giskard]: Cleared world.\n", + "[INFO] [1723807103.708117]: [/giskard]: Finished world goal #1.\n", + "[INFO] [1723807103.989186]: [/giskard]: Received new goal.\n", + "[INFO] [1723807103.993939]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723807103.994824]: [/giskard]: Parsing goal #2 message.\n", + "[INFO] [1723807103.995546]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", + "[INFO] [1723807103.996361]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", + "[INFO] [1723807103.997400]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723807103.998626]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723807104.000816]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723807104.046964]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_2.png.\n", + "[INFO] [1723807104.324322]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_2.pdf.\n", + "[INFO] [1723807104.741644]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", + "[INFO] [1723807104.789128]: [/giskard]: Planning succeeded.\n", + "[INFO] [1723807104.839212]: [/giskard]: Received new goal.\n", + "[INFO] [1723807104.841910]: [/giskard]: Goal is of type EXECUTE\n", + "[INFO] [1723807104.842540]: [/giskard]: Parsing goal #3 message.\n", + "[INFO] [1723807104.843135]: [/giskard]: Adding monitor of type: 'Alternator'\n", + "[INFO] [1723807104.843887]: [/giskard]: Adding monitor of type: 'Sleep'\n", + "[INFO] [1723807104.844481]: [/giskard]: Adding monitor of type: 'Print'\n", + "[INFO] [1723807104.845099]: [/giskard]: Adding monitor of type: 'Sleep'\n", + "[INFO] [1723807104.846026]: [/giskard]: Adding monitor of type: 'JointGoalReached'\n", + "[INFO] [1723807104.847848]: [/giskard]: Adding monitor of type: 'JointGoalReached'\n", + "[INFO] [1723807104.849583]: [/giskard]: Adding monitor of type: 'PoseReached'\n", + "[INFO] [1723807104.855056]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", + "[INFO] [1723807104.855710]: [/giskard]: Adding monitor of type: 'EndMotion'\n", + "[INFO] [1723807104.857883]: [/giskard]: Adding monitor of type: 'SetMaxTrajectoryLength'\n", + "[INFO] [1723807104.858615]: [/giskard]: Adding motion goal of type: 'JointPositionList' named: 'right pose'\n", + "[INFO] [1723807104.862720]: [/giskard]: Adding motion goal of type: 'JointPositionList' named: 'left pose'\n", + "[INFO] [1723807104.866613]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'CartesianPose'\n", + "[INFO] [1723807104.875589]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", + "[INFO] [1723807104.878219]: [/giskard]: Done parsing goal message.\n", + "[INFO] [1723807104.881163]: [/giskard]: Using QP Solver 'qpSWIFT'\n", + "[INFO] [1723807104.881735]: [/giskard]: Prediction horizon: '9'\n", + "[INFO] [1723807104.882364]: [/giskard]: Creating controller\n", + "[INFO] [1723807105.216862]: [/giskard]: Done compiling controller:\n", + "[INFO] [1723807105.217743]: [/giskard]: #free variables: 428\n", + "[INFO] [1723807105.218383]: [/giskard]: #equality constraints: 309\n", + "[INFO] [1723807105.218974]: [/giskard]: #inequality constraints: 0\n" + ] + } + ], "source": [ "reset_giskard()\n", "\n", @@ -1409,24 +1493,8 @@ }, { "cell_type": "code", - "execution_count": 50, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "../tmp/task_graphs/goal_41.png\n" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": "" - }, - "metadata": {}, - "output_type": "display_data" - } - ], + "execution_count": null, + "outputs": [], "source": [ "visualize_last_task_graph()" ], @@ -1439,25 +1507,8 @@ }, { "cell_type": "code", - "execution_count": 51, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "../tmp/gantt_charts/goal_41.pdf\n" - ] - }, - { - "data": { - "text/plain": "", - "image/png": "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", - "image/jpeg": "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" - }, - "metadata": {}, - "output_type": "display_data" - } - ], + "execution_count": null, + "outputs": [], "source": [ "visualize_last_gant_diagram()" ], @@ -1468,67 +1519,6 @@ } } }, - { - "cell_type": "code", - "execution_count": 29, - "outputs": [], - "source": [], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": 9, - "outputs": [ - { - "data": { - "text/plain": "Dropdown(description='Select Robot:', layout=Layout(width='200px'), options=('PR2', 'Stretch'), style=Descript…", - "application/vnd.jupyter.widget-view+json": { - "version_major": 2, - "version_minor": 0, - "model_id": "8c622ba2e55a45969490f838379d93d4" - } - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { - "text/plain": "Button(button_style='success', description='Start Launch File', style=ButtonStyle())", - "application/vnd.jupyter.widget-view+json": { - "version_major": 2, - "version_minor": 0, - "model_id": "abd7d7833ae24ffe9b6004b36bc27daf" - } - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": null, - "outputs": [], - "source": [], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, { "cell_type": "code", "execution_count": null, From f9b922880376314e001f4471bd66a4bfe79b2d61 Mon Sep 17 00:00:00 2001 From: maltehue Date: Sat, 17 Aug 2024 21:15:30 +0200 Subject: [PATCH 37/43] completed notebook with tutorial and exercise texts --- scripts/giskard_examples.ipynb | 611 +++++++++++++++++++-------------- 1 file changed, 358 insertions(+), 253 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index e986e17124..95a45f8934 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -2,38 +2,54 @@ "cells": [ { "cell_type": "markdown", - "source": [ - "# Section 0: Preliminaries\n", - "Please execute the following code blocks to setup the visualization, relevant imports, some helper functions and the robot selector." - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%% md\n" } - } + }, + "source": [ + "# Section 0: Preliminaries\n", + "Please execute the following code blocks to setup the visualization, relevant imports, some helper functions and the robot selector." + ] }, { "cell_type": "code", "execution_count": 18, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [], "source": [ "%%bash --bg\n", "rviz -d ../launch/../launch/rviz_config/standalone.rviz" - ], + ] + }, + { + "cell_type": "code", + "execution_count": null, "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { + "is_executing": true, "name": "#%%\n" } - } - }, - { - "cell_type": "code", - "execution_count": 2, + }, "outputs": [], "source": [ - "from giskardpy.python_interface.python_interface import GiskardWrapper\n", + "# imports and helper functions\n", "import rospy\n", "from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, Vector3\n", "from tf.transformations import quaternion_from_matrix, quaternion_about_axis\n", @@ -50,20 +66,8 @@ "import ipywidgets as widgets\n", "from IPython.display import display\n", "from giskardpy.utils.utils import launch_launchfile\n", - "import subprocess" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": 3, - "outputs": [], - "source": [ + "import subprocess\n", + "\n", "# Define some helper functions\n", "def reset_giskard():\n", " gs.clear_motion_goals_and_monitors()\n", @@ -131,21 +135,7 @@ " latest_file = max(files, key=os.path.getmtime)\n", " images = convert_from_path(latest_file)\n", " print(latest_file)\n", - " display(images[0])" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } - }, - { - "cell_type": "code", - "execution_count": null, - "outputs": [], - "source": [ - "# start ros node and robot selector\n", + " display(images[0])\n", "\n", "# global variables\n", "ROBOT = 'pr2'\n", @@ -218,17 +208,19 @@ "display(dropdown)\n", "display(button)\n", "rospy.init_node('giskard_examples')" - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n", - "is_executing": true + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ "# Section 1: Introduction\n", "Giskard is a constraint- and optimization-based whole-body motion planning/control framework.\n", @@ -240,30 +232,37 @@ "Show picture of PR2 TF Tree...\n", "\n", "**Tutorial 1.1: Now initialize the Python Interface. It will connect to the running Giskard instance of your selected robot.**" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": 5, - "outputs": [], - "source": [ - "gs = GiskardWrapper()" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%%\n" } - } + }, + "outputs": [], + "source": [ + "from giskardpy.python_interface.python_interface import GiskardWrapper\n", + "gs = GiskardWrapper()" + ] }, { "cell_type": "markdown", + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%% md\n" + } + }, "source": [ "**Tutorial 1.2: Use the defined motion goal to move a single joint of the robot**\n", "\n", @@ -272,17 +271,20 @@ " 1. Define a motion goal.\n", " 2. Define a monitor that checks if the goal was reached.\n", " 3. Define an end motion monitor, which has as start_condition the goal reached monitor." - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": 6, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -293,33 +295,39 @@ "gs.motion_goals.add_joint_position(goal_state=joint_goal)\n", "gs.monitors.add_end_motion(start_condition=joint_monitor)\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n" + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ "**Tutorial 1.3: Use the defined cartesian pose goal to move the tool frame of the robot**\n", "\n", "A commonly used goal is a cartesian pose goal. It is used to move a link of the robot to a specific pose. Frequently used links are the endeffector links or the base link.\n", "\n", "**Exercise 1.1: Change the orientation and position of the goal_pose and explore the generated movements**" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": 7, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -346,16 +354,19 @@ "# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\n", "# gs.add_default_end_motion_conditions()\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n" + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ "**Tutorial 1.4: Add a box to the world and specify a cartesian pose goal in its coordinate frame**\n", "\n", @@ -363,17 +374,21 @@ "When doing that, you can specify goal poses in the coordinate frames of the new entities.\n", "\n", "**Exercise 1.2: Change the box_pose and observe how giskard still reaches the same goal pose relative to the box**" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": null, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "is_executing": true, + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -400,17 +415,19 @@ "gs.monitors.add_end_motion(pose_monitor)\n", "gs.monitors.add_max_trajectory_length(30)\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n", - "is_executing": true + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ "**Tutorial 1.5: Use sets of atomic constraints to specify a motion instead of using a full 6D-Pose**\n", "\n", @@ -431,17 +448,20 @@ "The controlled and reference features will be visualized as points or vectors in space.\n", "\n", "Here a distance constraint between the origin points of the tool link and the map coordinate frames is defined." - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": 9, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -464,18 +484,22 @@ "gs.add_default_end_motion_conditions()\n", "gs.monitors.add_max_trajectory_length(30)\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n" + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ "**Tutorial 1.6: Combine atomic constraints for grasping**\n", + "\n", "We can exploit the rotational symmetry of a cylinder for grasping it if we specify the grasping motion with atomic constraints instead of with one fixed cartesian pose.\n", "Here we use three different atomic constraints to achieve this.\n", "\n", @@ -484,18 +508,23 @@ "3. constrain the height to be within the dimensions of the objects\n", "\n", "**Excercise 1.3: Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.**\n", + "\n", "**Excercise 1.4: You might notice that at some positions the rotation of the gripper is not correct. This is due to a missing atomic constraint that allows the gripper_frame to freely rotate around its x-axis. Try to constrain this using the AlignFeatureFunction. You can visualize tf in rviz to see all coordinate frames**" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": null, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "is_executing": true, + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -546,34 +575,40 @@ "\n", "gs.add_default_end_motion_conditions()\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n", - "is_executing": true + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ "**Tutorial 1.7:Adding collision avoidance**\n", + "\n", "Another advantage of having unconstrained DOF in the motion specification can be seen if we put an obstacle in front of the object we want to grasp and configure the collision avoidance to avoid this obstacle with all parts of the robot.\n", "\n", "**Excercise 1.5: change the position and the size of the obstacle and observe the resulting motions**\n", "PS: this cell includes the solution to the previous exercise" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": 11, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -643,16 +678,19 @@ "\n", "# EXERCISE:\n", "# 1. Change Pose and size of the obstacle and see of the robot behaves." - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n" + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ "**Tutorial 1.8: Use monitors to evaluate the success of your specified motion**\n", "\n", @@ -660,17 +698,21 @@ "A Motion was not sucessfull if the end motion monitor was not active and the goal was canceled by another monitor. In that case the return value of the execute() call can be passed to the get_end_motion_reason() function to obtain a summary of all monitors that are connected to the end motion that are not active.\n", "\n", "**Excercise 1.6: The output tells you which monitor of the end motion was not successful. Try changing/removing/adding constraint and monitors to realize a successful execution.**" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": null, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "is_executing": true, + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -765,35 +807,48 @@ " error_message='local minimum reached while monitors are not satisfied')\n", "result = gs.execute()\n", "if result.error.code != GiskardError.SUCCESS:\n", - " print(gs.get_end_motion_reason(move_result=result, show_all=False))" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n", - "is_executing": true - } - } + " print(gs.get_end_motion_reason(move_result=result, show_all=False)) " + ] }, { "cell_type": "markdown", - "source": [ - "Combination of constraints and cost function augmentations to\n", - "- place both grippers at specific poses (2 6D Pose Constraints)\n", - "- keep the line of sight on the left gripper (Pointing Constraint)\n", - "- prefer using base movements if the grippers are further away from their goal poses and avoid base movements if they are close to their goals (Quadratic Weight Scaling)\n", - "- maximize the manipulability in each arm (Linear weight term in the cost function)" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%% md\n" } - } + }, + "source": [ + "**Tutorial 1.9: Beyond constraints. Adapting the cost function to change behaviour.**\n", + "\n", + "The cost function of Giskard consists of a quadratic and a linear term. The quadartic term weights all control, slack variables against each other user using a weight matrix. Normally all control variables realted to joints a weight the same. With the BaseArmWeightScaling Goal we can define to joint groups (base joints and arm joints) and change their weights depending on the euclidean distance between the defined tip link and its goal position. Doing this the base joints will be preffered to satisfy all other goals/constraints when the distance is larger. When the distance becomes smaller the base joints will be used less and the arm joints will be used more. But there is nor hard cut, meaning the base joints can also used when distance is small if it is needed.\n", + "\n", + "The linear weight is normally not used, but by using the MaxManipulabilityLinWeight Goal a linear weight term is created that maximiyes the manipulability of the kinematic chain whic is defined by the root link and tip link parameters.\n", + "\n", + "In this tutorial we use the presented goals to show a combination of constraints and cost function augmentations to:\n", + "- place both grippers at specific poses (2 6D Pose Constraints)\n", + "- keep the line of sight on the left gripper (Pointing Constraint)\n", + "- prefer using base movements if the grippers are further away from their goal poses and avoid base movements if they are close to their goals (Quadratic Weight Scaling)\n", + "- maximize the manipulability in each arm (Linear weight term in the cost function)\n", + "\n", + "**Exercise 1.6: Comment out the goals for the cost function augmentation to compare the crated motions with and without**" + ] }, { "cell_type": "code", "execution_count": 13, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -903,43 +958,58 @@ " gain=gain,\n", " arm_joints=arm_joints,\n", " base_joints=['brumbrum'])\n", - "# gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", - "# root_link='torso_lift_link',\n", - "# tip_link='r_gripper_tool_frame')\n", - "# gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", - "# root_link='torso_lift_link',\n", - "# tip_link='l_gripper_tool_frame',\n", - "# name='MaxMal2')\n", + "if ROBOT == 'pr2':\n", + " gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", + " root_link='torso_lift_link',\n", + " tip_link='r_gripper_tool_frame')\n", + " gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", + " root_link='torso_lift_link',\n", + " tip_link='l_gripper_tool_frame',\n", + " name='MaxMal2')\n", "gs.add_default_end_motion_conditions()\n", "gs.motion_goals.allow_all_collisions()\n", "assert gs.execute().error.code == GiskardError.SUCCESS\n", "\n", "# EXERCISE:\n", "# 1.Comment the BaseArmWeightScaling and MaxManipulabilityLinWeight Goals to observe the resulting motions when the cost function is not augmented." - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } + ] }, { "cell_type": "markdown", - "source": [ - "### Environment Manipulation\n", - "If an environment is modelled as articulated links in an URDF Giskard can load it and control the joint states of the environment when it is connected to links of the robot." - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%% md\n" } - } + }, + "source": [ + "# Section 2: Environment Manipulation\n", + "**Tutorial 2.1: Opening a dishwasher**\n", + "\n", + "If an environment is modelled as articulated links in an URDF Giskard can load it and control the joint states of the environment when it is connected to links of the robot.\n", + "Here we had already loaded a URDF description of the iai_kitchen onto the parameter server. WE now read this from the parameter server to add it to the world model of Giskard.\n", + "\n", + "Then we grasp the dishwasher handle and open the dishwasher by defining a joint goal for its door joint.\n", + "the open_container goal adds constraints to keep the robot gripper at the same pose relative to the door handle. This then causes the whole robot to move when the movements of the dishwasher joint are calculated to achieve the joint goal.\n", + "\n", + "**Exercise 2.1: try different joint goals**" + ] }, { "cell_type": "code", "execution_count": 15, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [ { "name": "stdout", @@ -1134,35 +1204,43 @@ "gs.motion_goals.allow_all_collisions()\n", "gs.add_default_end_motion_conditions()\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], + ] + }, + { + "cell_type": "markdown", "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { - "name": "#%%\n" + "name": "#%% md\n" } - } - }, - { - "cell_type": "markdown", + }, "source": [ - "### Monitors and Giskard Task Graphs\n", + "# Section 3: Monitors and Giskard Task Graphs\n", + "**Tutorial 3.1: Simple sequencing of to cartesian pose goals in one controller**\n", + "\n", "Until now, we have seen different motion goals and monitors to observe the success of the specified Motion Goals, i.e. constraints.\n", "Another way to specify a motion with giskard is to utilize monitors and the start-, to_hold- and end_condition's each motion goal and monitor offer.\n", - "Doing this a chain, or more specifically a graph (task graph in Giskard terms), of motion goals is build up.\n", + "Doing this, a chain, or more specifically a graph (task graph in Giskard terms), of motion goals is build up.\n", "The task graph will be executed as one continuous controller (no need to recompile a new one for each goal).\n", "After execution a picture of the task graph and a Gant diagram visualizing the execution order of goals and monitors can be inspected.\n", "Next we will see simple example to execute two cartesian poses after each other." - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%% md\n" - } - } + ] }, { "cell_type": "code", "execution_count": 19, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [], "source": [ "reset_giskard()\n", @@ -1208,81 +1286,105 @@ "gs.motion_goals.allow_all_collisions()\n", "gs.monitors.add_end_motion(start_condition=' and '.join([end_monitor, monitor2]))\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } + ] }, { "cell_type": "markdown", - "source": [ - "**Visualize the Task Graph**" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%% md\n" } - } + }, + "source": [ + "**Visualize the Task Graph**" + ] }, { "cell_type": "code", "execution_count": null, - "outputs": [], - "source": [ - "visualize_last_task_graph()" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%%\n" } - } + }, + "outputs": [], + "source": [ + "visualize_last_task_graph()" + ] }, { "cell_type": "markdown", - "source": [ - "**Visualize the Gant diagramm**" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%% md\n" } - } + }, + "source": [ + "**Visualize the Gant diagramm**" + ] }, { "cell_type": "code", "execution_count": null, - "outputs": [], - "source": [ - "visualize_last_gant_diagram()" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%%\n" } - } + }, + "outputs": [], + "source": [ + "visualize_last_gant_diagram()" + ] }, { "cell_type": "markdown", - "source": [ - "This can be utilized for arbitrary complex goals." - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%% md\n" } - } + }, + "source": [ + "**Tutorial 3.2: Complex Sequencing**\n", + "\n", + "This can be utilized to build arbitrary complex task graphs.\n", + "\n", + "**Excersise 3.1: Read the code and compare your expectations with the execution, the printed out task graph and the Gantt diagramm.**\n", + "\n", + "**Excercise 3.2: Come up with your own sequences using everything we have looked at so far**" + ] }, { "cell_type": "code", "execution_count": 20, + "metadata": { + "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, + "pycharm": { + "name": "#%%\n" + } + }, "outputs": [ { "name": "stdout", @@ -1483,74 +1585,77 @@ "gs.motion_goals.allow_all_collisions()\n", "# And execute the goal.\n", "assert gs.execute().error.code == GiskardError.SUCCESS" - ], - "metadata": { - "collapsed": false, - "pycharm": { - "name": "#%%\n" - } - } + ] }, { "cell_type": "code", "execution_count": null, - "outputs": [], - "source": [ - "visualize_last_task_graph()" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%%\n" } - } + }, + "outputs": [], + "source": [ + "visualize_last_task_graph()" + ] }, { "cell_type": "code", "execution_count": null, - "outputs": [], - "source": [ - "visualize_last_gant_diagram()" - ], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%%\n" } - } + }, + "outputs": [], + "source": [ + "visualize_last_gant_diagram()" + ] }, { "cell_type": "code", "execution_count": null, - "outputs": [], - "source": [], "metadata": { "collapsed": false, + "jupyter": { + "outputs_hidden": false + }, "pycharm": { "name": "#%%\n" } - } + }, + "outputs": [], + "source": [] } ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "Python 3 (ipykernel)", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", - "version": 2 + "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.6" + "pygments_lexer": "ipython3", + "version": "3.8.10" } }, "nbformat": 4, - "nbformat_minor": 0 -} \ No newline at end of file + "nbformat_minor": 4 +} From cb5e13e2f6c0a761edd262129d1e31e4896fd48d Mon Sep 17 00:00:00 2001 From: malte Date: Mon, 19 Aug 2024 14:44:18 +0200 Subject: [PATCH 38/43] made notebook more stretch friendly --- scripts/giskard_examples.ipynb | 227 +++------------------------------ 1 file changed, 17 insertions(+), 210 deletions(-) diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb index 95a45f8934..6083f8f14f 100644 --- a/scripts/giskard_examples.ipynb +++ b/scripts/giskard_examples.ipynb @@ -171,6 +171,7 @@ " global tool_frame\n", " global cam_frame\n", " global base_link\n", + " ROBOT = robot\n", " if ROBOT == 'stretch':\n", " single_joint_goal = {'joint_lift': 0.7}\n", " tool_frame = 'link_grasp_center'\n", @@ -339,7 +340,7 @@ " [0, 1, 0, 0],\n", " [0, 0, 1, 0],\n", " [0, 0, 0, 1]]))\n", - "goal_pose.pose.position.x = 2.01\n", + "goal_pose.pose.position.x = 1.2\n", "goal_pose.pose.position.y = -0.2\n", "goal_pose.pose.position.z = 0.7\n", "# specify the cartesian pose goal to move 'l_gripper_tool_frame' towards goal_pose by using the kinematic chain between 'l_gripper_tool_frame' and 'map'\n", @@ -397,7 +398,7 @@ "box_pose = PoseStamped()\n", "box_pose.header.frame_id = 'map'\n", "box_pose.pose.orientation.w = 1\n", - "box_pose.pose.position.x = 2\n", + "box_pose.pose.position.x = 1.2\n", "box_pose.pose.position.y = -0.2\n", "box_pose.pose.position.z = 0.7\n", "gs.world.add_box('mybox', size=(0.1, 0.05, 0.2), pose=box_pose, parent_link='map')\n", @@ -536,7 +537,7 @@ "cyl_pose = PoseStamped()\n", "cyl_pose.header.frame_id = 'map'\n", "cyl_pose.pose.orientation.w = 1\n", - "cyl_pose.pose.position = Point(2, -0.2, 1.2)\n", + "cyl_pose.pose.position = Point(1.2, -0.2, 1.2)\n", "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", "\n", "# define the robot features\n", @@ -620,7 +621,7 @@ "cyl_pose = PoseStamped()\n", "cyl_pose.header.frame_id = 'map'\n", "cyl_pose.pose.orientation.w = 1\n", - "cyl_pose.pose.position = Point(2, -0.2, 1.2)\n", + "cyl_pose.pose.position = Point(1.2, -0.2, 1.2)\n", "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", "\n", "obstacle_pose = PoseStamped()\n", @@ -724,7 +725,7 @@ "cyl_pose = PoseStamped()\n", "cyl_pose.header.frame_id = 'map'\n", "cyl_pose.pose.orientation.w = 1\n", - "cyl_pose.pose.position = Point(2, -0.2, 1.2)\n", + "cyl_pose.pose.position = Point(1.2, -0.2, 1.2)\n", "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", "\n", "obstacle_pose = PoseStamped()\n", @@ -897,7 +898,8 @@ " [0, 0, 0, 1]]))\n", "\n", "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", - "# gs.motion_goals.add_cartesian_pose(goal_pose2, 'r_gripper_tool_frame', 'map', name='cart2')\n", + "if ROBOT == 'pr2':\n", + " gs.motion_goals.add_cartesian_pose(goal_pose2, 'r_gripper_tool_frame', 'map', name='cart2')\n", "\n", "goal_point = PointStamped()\n", "goal_point.header.frame_id = goal_pose.header.frame_id\n", @@ -1000,120 +1002,18 @@ }, { "cell_type": "code", - "execution_count": 15, + "execution_count": null, "metadata": { "collapsed": false, "jupyter": { "outputs_hidden": false }, "pycharm": { - "name": "#%%\n" + "name": "#%%\n", + "is_executing": true } }, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "[INFO] [1723806571.570577]: [/giskard]: Adding motion goal of type: 'AlignPlanes' named: 'AlignPlanes'\n", - "[INFO] [1723806571.573567]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723806571.682588]: [/giskard]: Adding 27 external collision avoidance constraints.\n", - "[INFO] [1723806572.172306]: [/giskard]: Adding 53 self collision avoidance constraints.\n", - "[INFO] [1723806572.195546]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723806572.211189]: [/giskard]: Using QP Solver 'qpSWIFT'\n", - "[INFO] [1723806572.211939]: [/giskard]: Prediction horizon: '9'\n", - "[INFO] [1723806572.212564]: [/giskard]: Creating controller\n", - "[INFO] [1723806572.539508]: [/giskard]: Done compiling controller:\n", - "[INFO] [1723806572.540666]: [/giskard]: #free variables: 571\n", - "[INFO] [1723806572.541252]: [/giskard]: #equality constraints: 346\n", - "[INFO] [1723806572.541791]: [/giskard]: #inequality constraints: 85\n", - "[INFO] [1723806572.583099]: [/giskard]: Compiled 6 debug expressions.\n", - "[INFO] [1723806572.700569]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_13.png.\n", - "[INFO] [1723806588.615921]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_13.pdf.\n", - "[INFO] [1723806589.766156]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723806590.796143]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/debug.pdf\n", - "[INFO] [1723806590.935641]: [/giskard]: Received new goal.\n", - "[INFO] [1723806590.940352]: [/giskard]: Processing world goal #13.\n", - "[INFO] [1723806591.332973]: [/giskard]: Cleared world.\n", - "[INFO] [1723806591.334426]: [/giskard]: Finished world goal #13.\n", - "[INFO] [1723806591.618341]: [/giskard]: Received new goal.\n", - "[INFO] [1723806591.626747]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723806591.627646]: [/giskard]: Parsing goal #14 message.\n", - "[INFO] [1723806591.628349]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", - "[INFO] [1723806591.629016]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", - "[INFO] [1723806591.629856]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723806591.631047]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723806591.634093]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723806591.686702]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_14.png.\n", - "[INFO] [1723806591.975511]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_14.pdf.\n", - "[INFO] [1723806592.393872]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723806592.421488]: [/giskard]: Planning succeeded.\n", - "[INFO] [1723806592.472902]: [/giskard]: Received new goal.\n", - "[INFO] [1723806592.490695]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723806592.494289]: [/giskard]: Parsing goal #15 message.\n", - "[INFO] [1723806592.497405]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", - "[INFO] [1723806592.499881]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723806592.502301]: [/giskard]: Adding monitor of type: 'CancelMotion'\n", - "[INFO] [1723806592.504028]: [/giskard]: Adding monitor of type: 'SetMaxTrajectoryLength'\n", - "[INFO] [1723806592.505931]: [/giskard]: Adding motion goal of type: 'JointPositionList' named: 'JointPositionList'\n", - "[INFO] [1723806592.520334]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723806592.522767]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723806592.525977]: [/giskard]: Using QP Solver 'qpSWIFT'\n", - "[INFO] [1723806592.526967]: [/giskard]: Prediction horizon: '9'\n", - "[INFO] [1723806592.527739]: [/giskard]: Creating controller\n", - "[INFO] [1723806592.677536]: [/giskard]: Done compiling controller:\n", - "[INFO] [1723806592.678498]: [/giskard]: #free variables: 400\n", - "[INFO] [1723806592.679112]: [/giskard]: #equality constraints: 288\n", - "[INFO] [1723806592.679704]: [/giskard]: #inequality constraints: 0\n", - "[INFO] [1723806592.749687]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_15.png.\n", - "[INFO] [1723806595.746482]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_15.pdf.\n", - "[INFO] [1723806596.347647]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723806596.362730]: [/giskard]: Planning succeeded.\n", - "[INFO] [1723806596.408348]: [/giskard]: Received new goal.\n", - "[INFO] [1723806596.413772]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723806596.414768]: [/giskard]: Parsing goal #16 message.\n", - "[INFO] [1723806596.415663]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", - "[INFO] [1723806596.416599]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723806596.417748]: [/giskard]: Adding monitor of type: 'CancelMotion'\n", - "[INFO] [1723806596.418901]: [/giskard]: Adding monitor of type: 'SetMaxTrajectoryLength'\n", - "[INFO] [1723806596.420061]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'CartesianPose'\n", - "[INFO] [1723806596.434909]: [/giskard]: Adding motion goal of type: 'Pointing' named: 'Pointing'\n", - "[INFO] [1723806596.440115]: [/giskard]: Adding motion goal of type: 'AlignPlanes' named: 'AlignPlanes'\n", - "[INFO] [1723806596.444280]: [/giskard]: Adding motion goal of type: 'BaseArmWeightScaling' named: 'BaseArmWeightScaling'\n", - "[INFO] [1723806596.469411]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723806596.472269]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723806596.474784]: [/giskard]: Using QP Solver 'qpSWIFT'\n", - "[INFO] [1723806596.475383]: [/giskard]: Prediction horizon: '9'\n", - "[INFO] [1723806596.475957]: [/giskard]: Creating controller\n", - "[INFO] [1723806596.579192]: [/giskard]: Done compiling controller:\n", - "[INFO] [1723806596.580118]: [/giskard]: #free variables: 324\n", - "[INFO] [1723806596.580745]: [/giskard]: #equality constraints: 233\n", - "[INFO] [1723806596.581340]: [/giskard]: #inequality constraints: 0\n", - "[INFO] [1723806596.589298]: [/giskard]: Compiled 11 debug expressions.\n", - "[INFO] [1723806596.693300]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_16.png.\n", - "[INFO] [1723806603.775733]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_16.pdf.\n", - "[INFO] [1723806604.629393]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723806605.377060]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/debug.pdf\n", - "[INFO] [1723806605.411690]: [/giskard]: Planning succeeded.\n", - "[INFO] [1723806605.449113]: [/giskard]: Received new goal.\n", - "[INFO] [1723806605.450298]: [/giskard]: Processing world goal #14.\n", - "[INFO] [1723806605.787736]: [/giskard]: Cleared world.\n", - "[INFO] [1723806605.798786]: [/giskard]: Finished world goal #14.\n", - "[INFO] [1723806606.070354]: [/giskard]: Received new goal.\n", - "[INFO] [1723806606.076234]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723806606.077105]: [/giskard]: Parsing goal #17 message.\n", - "[INFO] [1723806606.077890]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", - "[INFO] [1723806606.078654]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", - "[INFO] [1723806606.079538]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723806606.080662]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723806606.083363]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723806606.138460]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_17.png.\n", - "[INFO] [1723806606.432122]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_17.pdf.\n", - "[INFO] [1723806606.857384]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723806606.870070]: [/giskard]: Planning succeeded.\n" - ] - } - ], + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -1375,111 +1275,18 @@ }, { "cell_type": "code", - "execution_count": 20, + "execution_count": null, "metadata": { "collapsed": false, "jupyter": { "outputs_hidden": false }, "pycharm": { - "name": "#%%\n" + "name": "#%%\n", + "is_executing": true } }, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "[/unnamed]: Found these qp solvers: ['gurobi', 'qpalm', 'qpSWIFT']\n", - "[INFO] [1723807065.286638]: [/giskard]: Using betterpybullet for collision checking.\n", - "[INFO] [1723807065.859133]: [/giskard]: loading self collision matrix: /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/self_collision_matrices/iai/pr2.srdf\n", - "[INFO] [1723807065.937747]: [/giskard]: Loaded self collision matrix: /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/self_collision_matrices/iai/pr2.srdf\n", - "[INFO] [1723807065.960007]: [/giskard]: The following joints are non-fixed according to the urdf, but not flagged as controlled: {'pr2/fl_caster_rotation_joint', 'pr2/laser_tilt_mount_joint', 'pr2/br_caster_r_wheel_joint', 'pr2/torso_lift_motor_screw_joint', 'pr2/fl_caster_r_wheel_joint', 'pr2/r_gripper_motor_slider_joint', 'pr2/r_gripper_l_finger_joint', 'pr2/l_gripper_l_finger_joint', 'pr2/r_gripper_r_finger_joint', 'pr2/bl_caster_r_wheel_joint', 'pr2/l_gripper_r_finger_joint', 'pr2/bl_caster_l_wheel_joint', 'pr2/br_caster_rotation_joint', 'pr2/fl_caster_l_wheel_joint', 'pr2/l_gripper_l_finger_tip_joint', 'pr2/fr_caster_rotation_joint', 'pr2/l_gripper_motor_slider_joint', 'pr2/l_gripper_motor_screw_joint', 'pr2/r_gripper_l_finger_tip_joint', 'pr2/l_gripper_joint', 'pr2/r_gripper_motor_screw_joint', 'pr2/fr_caster_l_wheel_joint', 'pr2/fr_caster_r_wheel_joint', 'pr2/bl_caster_rotation_joint', 'pr2/r_gripper_r_finger_tip_joint', 'pr2/r_gripper_joint', 'pr2/br_caster_l_wheel_joint', 'pr2/l_gripper_r_finger_tip_joint'}.\n", - "[INFO] [1723807065.981247]: [/giskard]: giskard is ready\n", - "[INFO] [1723807086.831508]: [/giskard]: Received new goal.\n", - "[INFO] [1723807086.832688]: [/giskard]: Processing world goal #0.\n", - "[INFO] [1723807087.210308]: [/giskard]: Cleared world.\n", - "[INFO] [1723807087.231439]: [/giskard]: Finished world goal #0.\n", - "[INFO] [1723807087.512594]: [/giskard]: Received new goal.\n", - "[INFO] [1723807087.519318]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723807087.519993]: [/giskard]: Parsing goal #0 message.\n", - "[INFO] [1723807087.520574]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", - "[INFO] [1723807087.521179]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", - "[INFO] [1723807087.521962]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723807087.522996]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723807087.525968]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723807087.569212]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_0.png.\n", - "[INFO] [1723807088.031554]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_0.pdf.\n", - "[INFO] [1723807088.433189]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723807088.466379]: [/giskard]: Planning succeeded.\n", - "[INFO] [1723807088.516594]: [/giskard]: Received new goal.\n", - "[INFO] [1723807088.584568]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723807088.585489]: [/giskard]: Parsing goal #1 message.\n", - "[INFO] [1723807088.586139]: [/giskard]: Adding monitor of type: 'PoseReached'\n", - "[INFO] [1723807088.591531]: [/giskard]: Adding monitor of type: 'PoseReached'\n", - "[INFO] [1723807088.596630]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", - "[INFO] [1723807088.597322]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723807088.598286]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'g1'\n", - "[INFO] [1723807088.606436]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'g2'\n", - "[INFO] [1723807088.615076]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723807088.617663]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723807088.620088]: [/giskard]: Using QP Solver 'qpSWIFT'\n", - "[INFO] [1723807088.620681]: [/giskard]: Prediction horizon: '9'\n", - "[INFO] [1723807088.621227]: [/giskard]: Creating controller\n", - "[INFO] [1723807088.644418]: [/giskard]: Done compiling controller:\n", - "[INFO] [1723807088.645182]: [/giskard]: #free variables: 84\n", - "[INFO] [1723807088.645770]: [/giskard]: #equality constraints: 63\n", - "[INFO] [1723807088.646387]: [/giskard]: #inequality constraints: 0\n", - "[INFO] [1723807088.651133]: [/giskard]: Compiled 6 debug expressions.\n", - "[INFO] [1723807088.735526]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_1.png.\n", - "[INFO] [1723807099.747908]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_1.pdf.\n", - "[INFO] [1723807100.435799]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723807101.156740]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/debug.pdf\n", - "[INFO] [1723807101.177870]: [/giskard]: Planning succeeded.\n", - "[INFO] [1723807103.308165]: [/giskard]: Received new goal.\n", - "[INFO] [1723807103.309293]: [/giskard]: Processing world goal #1.\n", - "[INFO] [1723807103.700113]: [/giskard]: Cleared world.\n", - "[INFO] [1723807103.708117]: [/giskard]: Finished world goal #1.\n", - "[INFO] [1723807103.989186]: [/giskard]: Received new goal.\n", - "[INFO] [1723807103.993939]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723807103.994824]: [/giskard]: Parsing goal #2 message.\n", - "[INFO] [1723807103.995546]: [/giskard]: Adding monitor of type: 'SetSeedConfiguration'\n", - "[INFO] [1723807103.996361]: [/giskard]: Adding monitor of type: 'SetOdometry'\n", - "[INFO] [1723807103.997400]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723807103.998626]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723807104.000816]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723807104.046964]: [/giskard]: Saved task graph at /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/task_graphs/goal_2.png.\n", - "[INFO] [1723807104.324322]: [/giskard]: Saved gantt chart to /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/gantt_charts/goal_2.pdf.\n", - "[INFO] [1723807104.741644]: [/giskard]: saved /home/huerkamp/workspace/new_giskard_ws/src/giskardpy/tmp/trajectory.pdf\n", - "[INFO] [1723807104.789128]: [/giskard]: Planning succeeded.\n", - "[INFO] [1723807104.839212]: [/giskard]: Received new goal.\n", - "[INFO] [1723807104.841910]: [/giskard]: Goal is of type EXECUTE\n", - "[INFO] [1723807104.842540]: [/giskard]: Parsing goal #3 message.\n", - "[INFO] [1723807104.843135]: [/giskard]: Adding monitor of type: 'Alternator'\n", - "[INFO] [1723807104.843887]: [/giskard]: Adding monitor of type: 'Sleep'\n", - "[INFO] [1723807104.844481]: [/giskard]: Adding monitor of type: 'Print'\n", - "[INFO] [1723807104.845099]: [/giskard]: Adding monitor of type: 'Sleep'\n", - "[INFO] [1723807104.846026]: [/giskard]: Adding monitor of type: 'JointGoalReached'\n", - "[INFO] [1723807104.847848]: [/giskard]: Adding monitor of type: 'JointGoalReached'\n", - "[INFO] [1723807104.849583]: [/giskard]: Adding monitor of type: 'PoseReached'\n", - "[INFO] [1723807104.855056]: [/giskard]: Adding monitor of type: 'LocalMinimumReached'\n", - "[INFO] [1723807104.855710]: [/giskard]: Adding monitor of type: 'EndMotion'\n", - "[INFO] [1723807104.857883]: [/giskard]: Adding monitor of type: 'SetMaxTrajectoryLength'\n", - "[INFO] [1723807104.858615]: [/giskard]: Adding motion goal of type: 'JointPositionList' named: 'right pose'\n", - "[INFO] [1723807104.862720]: [/giskard]: Adding motion goal of type: 'JointPositionList' named: 'left pose'\n", - "[INFO] [1723807104.866613]: [/giskard]: Adding motion goal of type: 'CartesianPose' named: 'CartesianPose'\n", - "[INFO] [1723807104.875589]: [/giskard]: Adding motion goal of type: 'CollisionAvoidance' named: 'collision avoidance'\n", - "[INFO] [1723807104.878219]: [/giskard]: Done parsing goal message.\n", - "[INFO] [1723807104.881163]: [/giskard]: Using QP Solver 'qpSWIFT'\n", - "[INFO] [1723807104.881735]: [/giskard]: Prediction horizon: '9'\n", - "[INFO] [1723807104.882364]: [/giskard]: Creating controller\n", - "[INFO] [1723807105.216862]: [/giskard]: Done compiling controller:\n", - "[INFO] [1723807105.217743]: [/giskard]: #free variables: 428\n", - "[INFO] [1723807105.218383]: [/giskard]: #equality constraints: 309\n", - "[INFO] [1723807105.218974]: [/giskard]: #inequality constraints: 0\n" - ] - } - ], + "outputs": [], "source": [ "reset_giskard()\n", "\n", @@ -1658,4 +1465,4 @@ }, "nbformat": 4, "nbformat_minor": 4 -} +} \ No newline at end of file From a1a01ba5915777da735da82bf17aa09acac46c34 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 20 Aug 2024 16:46:40 +0200 Subject: [PATCH 39/43] first try of devel merge after new monitor conditions --- src/giskardpy/goals/feature_functions.py | 2 +- .../motion_graph/monitors/feature_monitors.py | 29 +++++++++++++++---- 2 files changed, 25 insertions(+), 6 deletions(-) diff --git a/src/giskardpy/goals/feature_functions.py b/src/giskardpy/goals/feature_functions.py index fae7610690..5945293f6e 100644 --- a/src/giskardpy/goals/feature_functions.py +++ b/src/giskardpy/goals/feature_functions.py @@ -6,7 +6,7 @@ from giskardpy.goals.goal import Goal from giskardpy.god_map import god_map from giskardpy.symbol_manager import symbol_manager -from giskardpy.tasks.task import Task, WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE +from giskardpy.motion_graph.tasks.task import Task, WEIGHT_BELOW_CA, WEIGHT_ABOVE_CA, WEIGHT_COLLISION_AVOIDANCE from giskardpy.goals.pointing import Pointing from giskardpy.goals.align_planes import AlignPlanes diff --git a/src/giskardpy/motion_graph/monitors/feature_monitors.py b/src/giskardpy/motion_graph/monitors/feature_monitors.py index 41b1876ae1..efe4d63c58 100644 --- a/src/giskardpy/motion_graph/monitors/feature_monitors.py +++ b/src/giskardpy/motion_graph/monitors/feature_monitors.py @@ -3,7 +3,7 @@ from geometry_msgs.msg import PointStamped, QuaternionStamped, PoseStamped, Vector3Stamped import giskardpy.casadi_wrapper as cas -from giskardpy.monitors.monitors import ExpressionMonitor, Monitor +from giskardpy.motion_graph.monitors.monitors import ExpressionMonitor, Monitor from giskardpy.god_map import god_map import giskardpy.utils.tfwrapper as tf from giskardpy.utils.expression_definition_utils import transform_msg, transform_msg_and_turn_to_expr @@ -17,9 +17,12 @@ def __init__(self, root_group: Optional[str] = None, tip_group: Optional[str] = None, name: Optional[str] = None, - stay_true: bool = True, - start_condition: cas.Expression = cas.TrueSymbol): - super().__init__(name=name, stay_true=stay_true, start_condition=start_condition) + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.FalseSymbol): + super().__init__(name=name, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition) self.root = god_map.world.search_for_link_name(root_link, root_group) self.tip = god_map.world.search_for_link_name(tip_link, tip_group) @@ -52,9 +55,13 @@ def __init__(self, tip_group: Optional[str] = None, name: Optional[str] = None, stay_true: bool = True, - start_condition: cas.Expression = cas.TrueSymbol): + start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.FalseSymbol): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group) distance = cas.distance_projected_on_vector(self.root_P_controlled_feature, self.root_P_reference_feature, @@ -73,9 +80,13 @@ def __init__(self, tip_link: str, root_link: str, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.FalseSymbol ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_normal, controlled_feature=tip_normal, name=name, stay_true=stay_true, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group) expr = cas.dot(self.root_V_reference_feature[:3], self.root_V_controlled_feature[:3]) @@ -93,9 +104,13 @@ def __init__(self, tip_link: str, root_link: str, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.FalseSymbol ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group) distance = cas.norm( @@ -115,9 +130,13 @@ def __init__(self, tip_link: str, root_link: str, name: str = None, stay_true: bool = True, start_condition: cas.Expression = cas.TrueSymbol, + hold_condition: cas.Expression = cas.FalseSymbol, + end_condition: cas.Expression = cas.FalseSymbol ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_vector, controlled_feature=tip_vector, name=name, stay_true=stay_true, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group) expr = cas.angle_between_vector(self.root_V_reference_feature, self.root_V_controlled_feature) From 48220a657a45eaf27e0096ab7ca083203a86ee95 Mon Sep 17 00:00:00 2001 From: malte Date: Tue, 20 Aug 2024 17:10:03 +0200 Subject: [PATCH 40/43] fixed wrong import --- scripts/giskard_examples.ipynb | 1468 ----------------- .../python_interface/python_interface.py | 2 +- 2 files changed, 1 insertion(+), 1469 deletions(-) delete mode 100644 scripts/giskard_examples.ipynb diff --git a/scripts/giskard_examples.ipynb b/scripts/giskard_examples.ipynb deleted file mode 100644 index 6083f8f14f..0000000000 --- a/scripts/giskard_examples.ipynb +++ /dev/null @@ -1,1468 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "# Section 0: Preliminaries\n", - "Please execute the following code blocks to setup the visualization, relevant imports, some helper functions and the robot selector." - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "%%bash --bg\n", - "rviz -d ../launch/../launch/rviz_config/standalone.rviz" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "is_executing": true, - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "# imports and helper functions\n", - "import rospy\n", - "from geometry_msgs.msg import PoseStamped, Point, Quaternion, Vector3Stamped, PointStamped, Vector3\n", - "from tf.transformations import quaternion_from_matrix, quaternion_about_axis\n", - "from giskardpy.goals.weight_scaling_goals import MaxManipulabilityLinWeight, BaseArmWeightScaling\n", - "from copy import deepcopy\n", - "from giskard_msgs.msg import WorldBody, CollisionEntry, WorldGoal, GiskardError\n", - "import numpy as np\n", - "from giskardpy.goals.joint_goals import JointPositionList\n", - "from giskardpy.monitors.joint_monitors import JointGoalReached\n", - "from IPython.display import display, Image\n", - "from pdf2image import convert_from_path\n", - "import os\n", - "import glob\n", - "import ipywidgets as widgets\n", - "from IPython.display import display\n", - "from giskardpy.utils.utils import launch_launchfile\n", - "import subprocess\n", - "\n", - "# Define some helper functions\n", - "def reset_giskard():\n", - " gs.clear_motion_goals_and_monitors()\n", - " gs.world.clear()\n", - " if ROBOT == 'stretch':\n", - " default_pose = {\n", - " 'joint_gripper_finger_left': 0.6,\n", - " 'joint_gripper_finger_right': 0.6,\n", - " 'joint_right_wheel': 0.0,\n", - " 'joint_left_wheel': 0.0,\n", - " 'joint_lift': 0.5,\n", - " 'joint_arm_l3': 0.05,\n", - " 'joint_arm_l2': 0.05,\n", - " 'joint_arm_l1': 0.05,\n", - " 'joint_arm_l0': 0.05,\n", - " 'joint_wrist_yaw': 0.0,\n", - " 'joint_head_pan': 0.0,\n", - " 'joint_head_tilt': 0.0\n", - " }\n", - " elif ROBOT == 'pr2':\n", - " default_pose = {\n", - " 'r_elbow_flex_joint': -0.15,\n", - " 'r_forearm_roll_joint': 0,\n", - " 'r_shoulder_lift_joint': 0,\n", - " 'r_shoulder_pan_joint': 0,\n", - " 'r_upper_arm_roll_joint': 0,\n", - " 'r_wrist_flex_joint': -0.10001,\n", - " 'r_wrist_roll_joint': 0,\n", - " 'l_elbow_flex_joint': -0.15,\n", - " 'l_forearm_roll_joint': 0,\n", - " 'l_shoulder_lift_joint': 0,\n", - " 'l_shoulder_pan_joint': 0,\n", - " 'l_upper_arm_roll_joint': 0,\n", - " 'l_wrist_flex_joint': -0.10001,\n", - " 'l_wrist_roll_joint': 0,\n", - " 'torso_lift_joint': 0.2,\n", - " 'head_pan_joint': 0,\n", - " 'head_tilt_joint': 0,\n", - " 'l_gripper_l_finger_joint': 0.55,\n", - " 'r_gripper_l_finger_joint': 0.55\n", - " }\n", - " done = gs.monitors.add_set_seed_configuration(default_pose)\n", - " base_pose = PoseStamped()\n", - " base_pose.header.frame_id = 'map'\n", - " base_pose.pose.position = Point(0, 0, 0)\n", - " base_pose.pose.orientation.w = 1\n", - " done2 = gs.monitors.add_set_seed_odometry(base_pose=base_pose)\n", - " gs.motion_goals.allow_all_collisions()\n", - " gs.monitors.add_end_motion(start_condition=f'{done} and {done2}')\n", - " gs.execute()\n", - " gs.clear_motion_goals_and_monitors()\n", - "\n", - "\n", - "def visualize_last_task_graph():\n", - " folder_path = '../tmp/task_graphs'\n", - " files = glob.glob((os.path.join(folder_path, '*')))\n", - " latest_file = max(files, key=os.path.getmtime)\n", - " print(latest_file)\n", - " display(Image(filename=latest_file))\n", - "\n", - "\n", - "def visualize_last_gant_diagram():\n", - " folder_path = '../tmp/gantt_charts'\n", - " files = glob.glob((os.path.join(folder_path, '*')))\n", - " latest_file = max(files, key=os.path.getmtime)\n", - " images = convert_from_path(latest_file)\n", - " print(latest_file)\n", - " display(images[0])\n", - "\n", - "# global variables\n", - "ROBOT = 'pr2'\n", - "single_joint_goal = {'torso_lift_joint': 0.3}\n", - "tool_frame = 'l_gripper_tool_frame'\n", - "cam_frame = 'wide_stereo_optical_frame'\n", - "base_link = 'base_footprint'\n", - "\n", - "# List of available launch files\n", - "launch_files = {\n", - " 'PR2': 'package://giskardpy/launch/giskardpy_pr2_standalone_vrb.launch',\n", - " 'Stretch': 'package://giskardpy/launch/giskardpy_stretch_standalone_vrb.launch'\n", - "}\n", - "\n", - "# Dropdown widget\n", - "dropdown = widgets.Dropdown(\n", - " options=launch_files.keys(),\n", - " value='PR2',\n", - " description='Select Robot:',\n", - " style={'description_width': 'initial'},\n", - " layout=widgets.Layout(width='200px')\n", - ")\n", - "\n", - "# Button widget\n", - "button = widgets.Button(\n", - " description='Start Launch File',\n", - " button_style='success',\n", - ")\n", - "\n", - "def update_global_variables(robot):\n", - " global ROBOT\n", - " global single_joint_goal\n", - " global tool_frame\n", - " global cam_frame\n", - " global base_link\n", - " ROBOT = robot\n", - " if ROBOT == 'stretch':\n", - " single_joint_goal = {'joint_lift': 0.7}\n", - " tool_frame = 'link_grasp_center'\n", - " cam_frame = 'camera_color_optical_frame'\n", - " base_link = 'base_link'\n", - " elif ROBOT == 'pr2':\n", - " single_joint_goal = {'torso_lift_joint': 0.3}\n", - " tool_frame = 'l_gripper_tool_frame'\n", - " cam_frame = 'wide_stereo_optical_frame'\n", - " base_link = 'base_footprint'\n", - "\n", - "\n", - "# Function to start the selected ROS launch file\n", - "def on_button_click(b):\n", - " selected_launch_file = launch_files[dropdown.value]\n", - "\n", - " update_global_variables(dropdown.value.lower())\n", - "\n", - " try:\n", - " result = subprocess.run('rosnode kill /giskard', shell=True, check=True, stdout=subprocess.PIPE,\n", - " stderr=subprocess.PIPE)\n", - " print(result.stdout.decode())\n", - " print(result.stderr.decode())\n", - " except subprocess.CalledProcessError as e:\n", - " print(f\"Error occurred: {e.stderr.decode()}\")\n", - "\n", - " print(f\"Starting ROS launch file: {selected_launch_file}\")\n", - " launch_launchfile(selected_launch_file)\n", - "\n", - "\n", - "# Attach the event handler to the button\n", - "button.on_click(on_button_click)\n", - "\n", - "# Display widgets\n", - "display(dropdown)\n", - "display(button)\n", - "rospy.init_node('giskard_examples')" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "# Section 1: Introduction\n", - "Giskard is a constraint- and optimization-based whole-body motion planning/control framework.\n", - "In short explain the QP...\n", - "Explain a constraint and how it influences the QP...\n", - "When using the python wrapper you do not specify constraints directly but rather a Motion Goal to parameterize a predefined set of constraints.\n", - "Additionally, the python interface allows to specify monitors that monitor a mathematical expression against a threshold and evaluate into a binary value.\n", - "They are used to start, stop or interrupt motion goals. More complex motion goals might specify their own monitors to chain constraints together.\n", - "Show picture of PR2 TF Tree...\n", - "\n", - "**Tutorial 1.1: Now initialize the Python Interface. It will connect to the running Giskard instance of your selected robot.**" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "from giskardpy.python_interface.python_interface import GiskardWrapper\n", - "gs = GiskardWrapper()" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.2: Use the defined motion goal to move a single joint of the robot**\n", - "\n", - "The simplest possible motion goal call follows the schema:\n", - "\n", - " 1. Define a motion goal.\n", - " 2. Define a monitor that checks if the goal was reached.\n", - " 3. Define an end motion monitor, which has as start_condition the goal reached monitor." - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "joint_goal = single_joint_goal\n", - "print(joint_goal)\n", - "joint_monitor = gs.monitors.add_joint_position(goal_state=joint_goal)\n", - "gs.motion_goals.add_joint_position(goal_state=joint_goal)\n", - "gs.monitors.add_end_motion(start_condition=joint_monitor)\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.3: Use the defined cartesian pose goal to move the tool frame of the robot**\n", - "\n", - "A commonly used goal is a cartesian pose goal. It is used to move a link of the robot to a specific pose. Frequently used links are the endeffector links or the base link.\n", - "\n", - "**Exercise 1.1: Change the orientation and position of the goal_pose and explore the generated movements**" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "# Define a goal pose in the map coordinate system\n", - "goal_pose = PoseStamped()\n", - "goal_pose.header.frame_id = 'map'\n", - "goal_pose.pose.orientation = Quaternion(*quaternion_from_matrix([[1, 0, 0, 0],\n", - " [0, 1, 0, 0],\n", - " [0, 0, 1, 0],\n", - " [0, 0, 0, 1]]))\n", - "goal_pose.pose.position.x = 1.2\n", - "goal_pose.pose.position.y = -0.2\n", - "goal_pose.pose.position.z = 0.7\n", - "# specify the cartesian pose goal to move 'l_gripper_tool_frame' towards goal_pose by using the kinematic chain between 'l_gripper_tool_frame' and 'map'\n", - "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", - "# specify a monitor that is active when it is below the given thresholds and use it to end the motion\n", - "pose_monitor = gs.monitors.add_cartesian_pose('map', tool_frame, goal_pose, position_threshold=0.01,\n", - " orientation_threshold=0.01)\n", - "# add a monitor that automatically stops the motion when the trajectory is too long\n", - "gs.monitors.add_max_trajectory_length(30)\n", - "# use the pose monitor to end the motion when it is true\n", - "gs.monitors.add_end_motion(pose_monitor)\n", - "# in the case that there is no specific end motion condition the default end motion condition stops the motion when the robot stops moving i.e. the QP is in a local minimum.\n", - "# gs.add_default_end_motion_conditions()\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.4: Add a box to the world and specify a cartesian pose goal in its coordinate frame**\n", - "\n", - "One can also add different objects, meshes or URDF's to the world representation of Giskard.\n", - "When doing that, you can specify goal poses in the coordinate frames of the new entities.\n", - "\n", - "**Exercise 1.2: Change the box_pose and observe how giskard still reaches the same goal pose relative to the box**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "is_executing": true, - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "# adding a box to the world\n", - "box_pose = PoseStamped()\n", - "box_pose.header.frame_id = 'map'\n", - "box_pose.pose.orientation.w = 1\n", - "box_pose.pose.position.x = 1.2\n", - "box_pose.pose.position.y = -0.2\n", - "box_pose.pose.position.z = 0.7\n", - "gs.world.add_box('mybox', size=(0.1, 0.05, 0.2), pose=box_pose, parent_link='map')\n", - "\n", - "# specfy a goal pose 8cm in front of the box origin frame\n", - "goal_pose = PoseStamped()\n", - "goal_pose.header.frame_id = 'mybox'\n", - "goal_pose.pose.orientation.w = 1\n", - "goal_pose.pose.position.x = -0.08\n", - "goal_pose.pose.position.y = 0\n", - "goal_pose.pose.position.z = 0\n", - "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", - "pose_monitor = gs.monitors.add_cartesian_pose('map', tool_frame, goal_pose, position_threshold=0.01,\n", - " orientation_threshold=0.01)\n", - "gs.monitors.add_end_motion(pose_monitor)\n", - "gs.monitors.add_max_trajectory_length(30)\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.5: Use sets of atomic constraints to specify a motion instead of using a full 6D-Pose**\n", - "\n", - "When using the cartesian pose goals all degrees of freedom of the link are fully constrained. One Advantage of constraint-based control is that one can only constrain necessary constraints.\n", - "The unconstrained DOF can then be exploited during the motion, for example in the collision avoidance or other secondary tasks.\n", - "To use this in the python interface one can use motion goals that constrain only a singular value, sometimes called constraints on feature functions ot atomic constraints.\n", - "For a feature function constraint a feature (Point or Vector) related to the robot (it has to be controllable) and one that is used as a reference has to be defined.\n", - "The name of the function then defines how they will be combined and 0 or 2 constraint values can be provided.\n", - "Right now we support the following atomic constraints:\n", - "\n", - " - Perpendicular(reference_vector, controlled_vector)\n", - " - Height(reference_point, controlled_point, lower_limit, upper_limit)\n", - " - Distance(reference_point, controlled_point, lower_limit, upper_limit)\n", - " - Pointing(reference_point, controlled_vector)\n", - " - Align(reference_vector, controlled_vector)\n", - " - Angle(reference_vector, controlled_vector, lower_limit, upper_limit)\n", - "\n", - "The controlled and reference features will be visualized as points or vectors in space.\n", - "\n", - "Here a distance constraint between the origin points of the tool link and the map coordinate frames is defined." - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "# Define a world feature as a point at the origin of map\n", - "world_feature = PointStamped()\n", - "world_feature.header.frame_id = 'map'\n", - "\n", - "# Define a robot feature as a point at the origin of the right gripper tool frame\n", - "robot_feature = PointStamped()\n", - "robot_feature.header.frame_id = tool_frame\n", - "\n", - "# use the distance feature function to constrain the distance between the features to be between 2m and 2.5m\n", - "gs.motion_goals.add_distance(root_link='map',\n", - " tip_link=tool_frame,\n", - " reference_point=world_feature,\n", - " tip_point=robot_feature,\n", - " lower_limit=2,\n", - " upper_limit=2.5)\n", - "\n", - "gs.add_default_end_motion_conditions()\n", - "gs.monitors.add_max_trajectory_length(30)\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.6: Combine atomic constraints for grasping**\n", - "\n", - "We can exploit the rotational symmetry of a cylinder for grasping it if we specify the grasping motion with atomic constraints instead of with one fixed cartesian pose.\n", - "Here we use three different atomic constraints to achieve this.\n", - "\n", - "1. Pointing the gripper towards the object center\n", - "2. keeping a suitable distance\n", - "3. constrain the height to be within the dimensions of the objects\n", - "\n", - "**Excercise 1.3: Change the position of the cylinder and the constraint values, and observe the resulting grasp poses.**\n", - "\n", - "**Excercise 1.4: You might notice that at some positions the rotation of the gripper is not correct. This is due to a missing atomic constraint that allows the gripper_frame to freely rotate around its x-axis. Try to constrain this using the AlignFeatureFunction. You can visualize tf in rviz to see all coordinate frames**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "is_executing": true, - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "# variables\n", - "gripper_link = tool_frame\n", - "\n", - "# adding the object\n", - "cyl_pose = PoseStamped()\n", - "cyl_pose.header.frame_id = 'map'\n", - "cyl_pose.pose.orientation.w = 1\n", - "cyl_pose.pose.position = Point(1.2, -0.2, 1.2)\n", - "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", - "\n", - "# define the robot features\n", - "robot_pointing_feature = Vector3Stamped()\n", - "robot_pointing_feature.header.frame_id = gripper_link\n", - "robot_pointing_feature.vector = Vector3(1, 0, 0)\n", - "\n", - "robot_point_feature = PointStamped()\n", - "robot_point_feature.header.frame_id = gripper_link\n", - "robot_point_feature.point = Point(0, 0, 0)\n", - "\n", - "# define the world features\n", - "world_cylinder_center_feature = PointStamped()\n", - "world_cylinder_center_feature.header.frame_id = 'mycyl'\n", - "world_cylinder_center_feature.point = Point(0, 0, 0)\n", - "\n", - "# define the constraints\n", - "gs.motion_goals.add_distance(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=0.03,\n", - " upper_limit=0.03)\n", - "gs.motion_goals.add_height(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=-0.05,\n", - " upper_limit=0.05)\n", - "gs.motion_goals.add_pointing(root_link='map',\n", - " tip_link=gripper_link,\n", - " goal_point=world_cylinder_center_feature,\n", - " pointing_axis=robot_pointing_feature)\n", - "\n", - "#Exercise 1.4: You can define your features and your motion goal here\n", - "\n", - "gs.add_default_end_motion_conditions()\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.7:Adding collision avoidance**\n", - "\n", - "Another advantage of having unconstrained DOF in the motion specification can be seen if we put an obstacle in front of the object we want to grasp and configure the collision avoidance to avoid this obstacle with all parts of the robot.\n", - "\n", - "**Excercise 1.5: change the position and the size of the obstacle and observe the resulting motions**\n", - "PS: this cell includes the solution to the previous exercise" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "# variables\n", - "gripper_link = tool_frame\n", - "\n", - "# adding the object\n", - "cyl_pose = PoseStamped()\n", - "cyl_pose.header.frame_id = 'map'\n", - "cyl_pose.pose.orientation.w = 1\n", - "cyl_pose.pose.position = Point(1.2, -0.2, 1.2)\n", - "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", - "\n", - "obstacle_pose = PoseStamped()\n", - "obstacle_pose.header.frame_id = 'mycyl'\n", - "obstacle_pose.pose.orientation.w = 1\n", - "obstacle_pose.pose.position = Point(-0.1, 0.1, 0)\n", - "gs.world.add_box('obstacle', size=(0.02, 0.06, 0.05), pose=obstacle_pose, parent_link='mycyl')\n", - "\n", - "# define the robot features\n", - "robot_pointing_feature = Vector3Stamped()\n", - "robot_pointing_feature.header.frame_id = gripper_link\n", - "robot_pointing_feature.vector = Vector3(1, 0, 0)\n", - "\n", - "robot_point_feature = PointStamped()\n", - "robot_point_feature.header.frame_id = gripper_link\n", - "robot_point_feature.point = Point(0, 0, 0)\n", - "\n", - "robot_gripper_z_axis_feature = Vector3Stamped()\n", - "robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", - "robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "\n", - "# define the world features\n", - "world_cylinder_center_feature = PointStamped()\n", - "world_cylinder_center_feature.header.frame_id = 'mycyl'\n", - "world_cylinder_center_feature.point = Point(0, 0, 0)\n", - "\n", - "world_cyl_z_axis_feature = Vector3Stamped()\n", - "world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", - "world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "\n", - "# define the constraints\n", - "gs.motion_goals.add_distance(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=0.03,\n", - " upper_limit=0.03)\n", - "gs.motion_goals.add_height(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=-0.05,\n", - " upper_limit=0.05)\n", - "gs.motion_goals.add_pointing(root_link='map',\n", - " tip_link=gripper_link,\n", - " goal_point=world_cylinder_center_feature,\n", - " pointing_axis=robot_pointing_feature)\n", - "gs.motion_goals.avoid_collision(min_distance=0.1, group1='obstacle')\n", - "gs.motion_goals.add_align_planes(root_link='map',\n", - " tip_link=gripper_link,\n", - " goal_normal=world_cyl_z_axis_feature,\n", - " tip_normal=robot_gripper_z_axis_feature)\n", - "gs.add_default_end_motion_conditions()\n", - "assert gs.execute().error.code == GiskardError.SUCCESS\n", - "\n", - "# EXERCISE:\n", - "# 1. Change Pose and size of the obstacle and see of the robot behaves." - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.8: Use monitors to evaluate the success of your specified motion**\n", - "\n", - "For each constraint a related monitor can be added to observe their progression and collect feedback in the case of failure where one or many constraints cannot be satisfied.\n", - "A Motion was not sucessfull if the end motion monitor was not active and the goal was canceled by another monitor. In that case the return value of the execute() call can be passed to the get_end_motion_reason() function to obtain a summary of all monitors that are connected to the end motion that are not active.\n", - "\n", - "**Excercise 1.6: The output tells you which monitor of the end motion was not successful. Try changing/removing/adding constraint and monitors to realize a successful execution.**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "is_executing": true, - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "# variables\n", - "gripper_link = tool_frame\n", - "\n", - "# adding the object\n", - "cyl_pose = PoseStamped()\n", - "cyl_pose.header.frame_id = 'map'\n", - "cyl_pose.pose.orientation.w = 1\n", - "cyl_pose.pose.position = Point(1.2, -0.2, 1.2)\n", - "gs.world.add_cylinder('mycyl', height=0.2, radius=0.02, pose=cyl_pose, parent_link='map')\n", - "\n", - "obstacle_pose = PoseStamped()\n", - "obstacle_pose.header.frame_id = 'mycyl'\n", - "obstacle_pose.pose.orientation.w = 1\n", - "obstacle_pose.pose.position = Point(-0.1, 0.1, 0)\n", - "gs.world.add_box('obstacle', size=(0.02, 0.06, 0.05), pose=obstacle_pose, parent_link='mycyl')\n", - "\n", - "# define the robot features\n", - "robot_pointing_feature = Vector3Stamped()\n", - "robot_pointing_feature.header.frame_id = gripper_link\n", - "robot_pointing_feature.vector = Vector3(1, 0, 0)\n", - "\n", - "robot_point_feature = PointStamped()\n", - "robot_point_feature.header.frame_id = gripper_link\n", - "robot_point_feature.point = Point(0, 0, 0)\n", - "\n", - "robot_gripper_z_axis_feature = Vector3Stamped()\n", - "robot_gripper_z_axis_feature.header.frame_id = gripper_link\n", - "robot_gripper_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "\n", - "# define the world features\n", - "world_cylinder_center_feature = PointStamped()\n", - "world_cylinder_center_feature.header.frame_id = 'mycyl'\n", - "world_cylinder_center_feature.point = Point(0, 0, 0)\n", - "\n", - "world_cyl_z_axis_feature = Vector3Stamped()\n", - "world_cyl_z_axis_feature.header.frame_id = 'mycyl'\n", - "world_cyl_z_axis_feature.vector = Vector3(0, 0, 1)\n", - "\n", - "# define the constraints\n", - "gs.motion_goals.add_distance(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=0.0,\n", - " upper_limit=0.0)\n", - "mon_dist = gs.monitors.add_distance(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=-0.001,\n", - " upper_limit=0.001)\n", - "\n", - "gs.motion_goals.add_height(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=-0.05,\n", - " upper_limit=0.05)\n", - "mon_height = gs.monitors.add_height(root_link='map',\n", - " tip_link=gripper_link,\n", - " reference_point=world_cylinder_center_feature,\n", - " tip_point=robot_point_feature,\n", - " lower_limit=-0.05,\n", - " upper_limit=0.05)\n", - "\n", - "gs.motion_goals.add_pointing(root_link='map',\n", - " tip_link=gripper_link,\n", - " goal_point=world_cylinder_center_feature,\n", - " pointing_axis=robot_pointing_feature)\n", - "mon_pointing = gs.monitors.add_pointing_at(root_link='map',\n", - " tip_link=gripper_link,\n", - " goal_point=world_cylinder_center_feature,\n", - " pointing_axis=robot_pointing_feature)\n", - "\n", - "gs.motion_goals.add_align_planes(root_link='map',\n", - " tip_link=gripper_link,\n", - " goal_normal=world_cyl_z_axis_feature,\n", - " tip_normal=robot_gripper_z_axis_feature)\n", - "mon_align = gs.monitors.add_vectors_aligned(root_link='map',\n", - " tip_link=gripper_link,\n", - " goal_normal=world_cyl_z_axis_feature,\n", - " tip_normal=robot_gripper_z_axis_feature)\n", - "\n", - "gs.motion_goals.allow_all_collisions()\n", - "gs.motion_goals.avoid_collision(min_distance=0.08, group1='obstacle')\n", - "gs.monitors.add_end_motion(f'{mon_dist} and {mon_height} and {mon_align} and {mon_pointing}')\n", - "gs.monitors.add_cancel_motion(gs.monitors.add_local_minimum_reached(),\n", - " error_message='local minimum reached while monitors are not satisfied')\n", - "result = gs.execute()\n", - "if result.error.code != GiskardError.SUCCESS:\n", - " print(gs.get_end_motion_reason(move_result=result, show_all=False)) " - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 1.9: Beyond constraints. Adapting the cost function to change behaviour.**\n", - "\n", - "The cost function of Giskard consists of a quadratic and a linear term. The quadartic term weights all control, slack variables against each other user using a weight matrix. Normally all control variables realted to joints a weight the same. With the BaseArmWeightScaling Goal we can define to joint groups (base joints and arm joints) and change their weights depending on the euclidean distance between the defined tip link and its goal position. Doing this the base joints will be preffered to satisfy all other goals/constraints when the distance is larger. When the distance becomes smaller the base joints will be used less and the arm joints will be used more. But there is nor hard cut, meaning the base joints can also used when distance is small if it is needed.\n", - "\n", - "The linear weight is normally not used, but by using the MaxManipulabilityLinWeight Goal a linear weight term is created that maximiyes the manipulability of the kinematic chain whic is defined by the root link and tip link parameters.\n", - "\n", - "In this tutorial we use the presented goals to show a combination of constraints and cost function augmentations to:\n", - "- place both grippers at specific poses (2 6D Pose Constraints)\n", - "- keep the line of sight on the left gripper (Pointing Constraint)\n", - "- prefer using base movements if the grippers are further away from their goal poses and avoid base movements if they are close to their goals (Quadratic Weight Scaling)\n", - "- maximize the manipulability in each arm (Linear weight term in the cost function)\n", - "\n", - "**Exercise 1.6: Comment out the goals for the cost function augmentation to compare the crated motions with and without**" - ] - }, - { - "cell_type": "code", - "execution_count": 13, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "# This is eventually not feasible for the stretch\n", - "if ROBOT == 'pr2':\n", - " js = {\n", - " # 'torso_lift_joint': 0.2999225173357618,\n", - " 'head_pan_joint': 0.041880780651479044,\n", - " 'head_tilt_joint': -0.37,\n", - " 'r_upper_arm_roll_joint': -0.9487714747527726,\n", - " 'r_shoulder_pan_joint': -1.0047307505973626,\n", - " 'r_shoulder_lift_joint': 0.48736790658811985,\n", - " 'r_forearm_roll_joint': -14.895833882874182,\n", - " 'r_elbow_flex_joint': -1.392377908925028,\n", - " 'r_wrist_flex_joint': -0.4548695149411013,\n", - " 'r_wrist_roll_joint': 0.11426798984097819,\n", - " 'l_upper_arm_roll_joint': 1.7383062350263658,\n", - " 'l_shoulder_pan_joint': 1.8799810286792007,\n", - " 'l_shoulder_lift_joint': 0.011627231224188975,\n", - " 'l_forearm_roll_joint': 312.67276414458695,\n", - " 'l_elbow_flex_joint': -2.0300928925694675,\n", - " 'l_wrist_flex_joint': -0.10014623223021513,\n", - " 'l_wrist_roll_joint': -6.062015047706399,\n", - " }\n", - " gs.motion_goals.add_joint_position(js)\n", - " gs.motion_goals.allow_all_collisions()\n", - " gs.add_default_end_motion_conditions()\n", - " gs.execute()\n", - "\n", - "goal_pose = PoseStamped()\n", - "goal_pose.header.frame_id = 'map'\n", - "goal_pose.pose.orientation = Quaternion(*quaternion_from_matrix([[1, 0, 0, 0],\n", - " [0, 1, 0, 0],\n", - " [0, 0, 1, 0],\n", - " [0, 0, 0, 1]]))\n", - "goal_pose.pose.position.x = 2.01\n", - "goal_pose.pose.position.y = -0.2\n", - "goal_pose.pose.position.z = 0.7\n", - "\n", - "goal_pose2 = deepcopy(goal_pose)\n", - "goal_pose2.pose.position.y = -0.6\n", - "goal_pose2.pose.position.z = 0.8\n", - "goal_pose2.pose.orientation = Quaternion(*quaternion_from_matrix([[0, 0, 1, 0],\n", - " [0, 1, 0, 0],\n", - " [-1, 0, 0, 0],\n", - " [0, 0, 0, 1]]))\n", - "\n", - "gs.motion_goals.add_cartesian_pose(goal_pose, tool_frame, 'map')\n", - "if ROBOT == 'pr2':\n", - " gs.motion_goals.add_cartesian_pose(goal_pose2, 'r_gripper_tool_frame', 'map', name='cart2')\n", - "\n", - "goal_point = PointStamped()\n", - "goal_point.header.frame_id = goal_pose.header.frame_id\n", - "goal_point.point = goal_pose.pose.position\n", - "pointing_axis = Vector3Stamped()\n", - "pointing_axis.header.frame_id = cam_frame\n", - "pointing_axis.vector.z = 1\n", - "gs.motion_goals.add_pointing(goal_point, cam_frame, pointing_axis, 'map')\n", - "\n", - "x_base = Vector3Stamped()\n", - "x_base.header.frame_id = 'base_link'\n", - "x_base.vector.x = 1\n", - "x_goal = Vector3Stamped()\n", - "x_goal.header.frame_id = 'map'\n", - "x_goal.vector.x = 1\n", - "gs.motion_goals.add_align_planes(tip_link='base_link',\n", - " root_link='map',\n", - " tip_normal=x_base,\n", - " goal_normal=x_goal)\n", - "\n", - "if ROBOT == 'pr2':\n", - " arm_joints = [\n", - " 'torso_lift_joint',\n", - " # 'head_pan_joint',\n", - " # 'head_tilt_joint',\n", - " 'r_upper_arm_roll_joint',\n", - " 'r_shoulder_pan_joint',\n", - " 'r_shoulder_lift_joint',\n", - " 'r_forearm_roll_joint',\n", - " 'r_elbow_flex_joint',\n", - " 'r_wrist_flex_joint',\n", - " 'r_wrist_roll_joint',\n", - " 'l_upper_arm_roll_joint',\n", - " 'l_shoulder_pan_joint',\n", - " 'l_shoulder_lift_joint',\n", - " 'l_forearm_roll_joint',\n", - " 'l_elbow_flex_joint',\n", - " 'l_wrist_flex_joint',\n", - " 'l_wrist_roll_joint']\n", - " gain = 100000\n", - "elif ROBOT == 'stretch':\n", - " arm_joints = ['joint_arm_l3',\n", - " 'joint_arm_l2',\n", - " 'joint_arm_l1',\n", - " 'joint_arm_l0',\n", - " 'joint_wrist_yaw',\n", - " 'joint_wrist_pitch',\n", - " 'joint_wrist_roll']\n", - " gain = 100000\n", - "\n", - "tip_goal = PointStamped()\n", - "tip_goal.header.frame_id = 'map'\n", - "tip_goal.point = goal_pose.pose.position\n", - "gs.motion_goals.add_motion_goal(motion_goal_class=BaseArmWeightScaling.__name__,\n", - " root_link='map',\n", - " tip_link=tool_frame,\n", - " tip_goal=tip_goal,\n", - " gain=gain,\n", - " arm_joints=arm_joints,\n", - " base_joints=['brumbrum'])\n", - "if ROBOT == 'pr2':\n", - " gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", - " root_link='torso_lift_link',\n", - " tip_link='r_gripper_tool_frame')\n", - " gs.motion_goals.add_motion_goal(motion_goal_class=MaxManipulabilityLinWeight.__name__,\n", - " root_link='torso_lift_link',\n", - " tip_link='l_gripper_tool_frame',\n", - " name='MaxMal2')\n", - "gs.add_default_end_motion_conditions()\n", - "gs.motion_goals.allow_all_collisions()\n", - "assert gs.execute().error.code == GiskardError.SUCCESS\n", - "\n", - "# EXERCISE:\n", - "# 1.Comment the BaseArmWeightScaling and MaxManipulabilityLinWeight Goals to observe the resulting motions when the cost function is not augmented." - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "# Section 2: Environment Manipulation\n", - "**Tutorial 2.1: Opening a dishwasher**\n", - "\n", - "If an environment is modelled as articulated links in an URDF Giskard can load it and control the joint states of the environment when it is connected to links of the robot.\n", - "Here we had already loaded a URDF description of the iai_kitchen onto the parameter server. WE now read this from the parameter server to add it to the world model of Giskard.\n", - "\n", - "Then we grasp the dishwasher handle and open the dishwasher by defining a joint goal for its door joint.\n", - "the open_container goal adds constraints to keep the robot gripper at the same pose relative to the door handle. This then causes the whole robot to move when the movements of the dishwasher joint are calculated to achieve the joint goal.\n", - "\n", - "**Exercise 2.1: try different joint goals**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n", - "is_executing": true - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "# load the kitchen environment\n", - "kitchen_pose = PoseStamped()\n", - "kitchen_pose.header.frame_id = 'map'\n", - "kitchen_pose.pose.orientation.w = 1\n", - "gs.world.add_urdf(name='iai_kitchen',\n", - " urdf=rospy.get_param('kitchen_description'),\n", - " pose=kitchen_pose)\n", - "\n", - "# Define poses and groups\n", - "p = PoseStamped()\n", - "p.header.frame_id = 'map'\n", - "p.pose.orientation.w = 1\n", - "p.pose.position.x = 0.5\n", - "p.pose.position.y = 0.2\n", - "\n", - "hand = tool_frame\n", - "\n", - "goal_angle = np.pi / 4\n", - "handle_frame_id = 'sink_area_dish_washer_door_handle'\n", - "handle_name = 'sink_area_dish_washer_door_handle'\n", - "gs.world.register_group('dishwasher', root_link_name='sink_area_dish_washer_main',\n", - " root_link_group_name='iai_kitchen')\n", - "gs.world.register_group('handle', root_link_name=handle_name,\n", - " root_link_group_name='iai_kitchen')\n", - "\n", - "# grasp the dishwasher handle\n", - "bar_axis = Vector3Stamped()\n", - "bar_axis.header.frame_id = handle_frame_id\n", - "bar_axis.vector.y = 1\n", - "\n", - "bar_center = PointStamped()\n", - "bar_center.header.frame_id = handle_frame_id\n", - "\n", - "tip_grasp_axis = Vector3Stamped()\n", - "tip_grasp_axis.header.frame_id = hand\n", - "tip_grasp_axis.vector.z = 1\n", - "\n", - "gs.motion_goals.add_grasp_bar(root_link='map',\n", - " tip_link=hand,\n", - " tip_grasp_axis=tip_grasp_axis,\n", - " bar_center=bar_center,\n", - " bar_axis=bar_axis,\n", - " bar_length=.3)\n", - "\n", - "x_gripper = Vector3Stamped()\n", - "x_gripper.header.frame_id = hand\n", - "x_gripper.vector.x = 1\n", - "\n", - "x_goal = Vector3Stamped()\n", - "x_goal.header.frame_id = handle_frame_id\n", - "x_goal.vector.x = -1\n", - "gs.motion_goals.add_align_planes(tip_link=hand,\n", - " root_link='map',\n", - " tip_normal=x_gripper,\n", - " goal_normal=x_goal)\n", - "\n", - "if ROBOT == 'stretch':\n", - " x_base = Vector3Stamped()\n", - " x_base.header.frame_id = 'base_link'\n", - " x_base.vector.x = 1\n", - " x_goal = Vector3Stamped()\n", - " x_goal.header.frame_id = 'map'\n", - " x_goal.vector.y = 1\n", - " gs.motion_goals.add_align_planes(tip_link='base_link',\n", - " root_link='map',\n", - " tip_normal=x_base,\n", - " goal_normal=x_goal,\n", - " name='align_base')\n", - "\n", - "gs.add_default_end_motion_conditions()\n", - "gs.execute()\n", - "\n", - "# open the dishwasher\n", - "gs.motion_goals.add_open_container(tip_link=hand,\n", - " environment_link=handle_name,\n", - " goal_joint_state=goal_angle)\n", - "gs.motion_goals.allow_all_collisions()\n", - "gs.add_default_end_motion_conditions()\n", - "gs.execute()\n", - "\n", - "# close the dishwasher\n", - "gs.motion_goals.add_open_container(tip_link=hand,\n", - " environment_link=handle_name,\n", - " goal_joint_state=0)\n", - "gs.motion_goals.allow_all_collisions()\n", - "gs.add_default_end_motion_conditions()\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "# Section 3: Monitors and Giskard Task Graphs\n", - "**Tutorial 3.1: Simple sequencing of to cartesian pose goals in one controller**\n", - "\n", - "Until now, we have seen different motion goals and monitors to observe the success of the specified Motion Goals, i.e. constraints.\n", - "Another way to specify a motion with giskard is to utilize monitors and the start-, to_hold- and end_condition's each motion goal and monitor offer.\n", - "Doing this, a chain, or more specifically a graph (task graph in Giskard terms), of motion goals is build up.\n", - "The task graph will be executed as one continuous controller (no need to recompile a new one for each goal).\n", - "After execution a picture of the task graph and a Gant diagram visualizing the execution order of goals and monitors can be inspected.\n", - "Next we will see simple example to execute two cartesian poses after each other." - ] - }, - { - "cell_type": "code", - "execution_count": 19, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "pose1 = PoseStamped()\n", - "pose1.header.frame_id = 'map'\n", - "pose1.pose.position.x = 1\n", - "pose1.pose.orientation.w = 1\n", - "\n", - "pose2 = PoseStamped()\n", - "pose2.header.frame_id = base_link\n", - "pose2.pose.position.y = 1\n", - "pose2.pose.orientation.w = 1\n", - "\n", - "root_link = 'map'\n", - "tip_link = base_link\n", - "\n", - "monitor1 = gs.monitors.add_cartesian_pose(name='pose1',\n", - " root_link=root_link,\n", - " tip_link=tip_link,\n", - " goal_pose=pose1)\n", - "\n", - "monitor2 = gs.monitors.add_cartesian_pose(name='pose2',\n", - " root_link=root_link,\n", - " tip_link=tip_link,\n", - " goal_pose=pose2,\n", - " absolute=True,\n", - " start_condition=monitor1)\n", - "end_monitor = gs.monitors.add_local_minimum_reached()\n", - "\n", - "gs.motion_goals.add_cartesian_pose(goal_pose=pose1,\n", - " name='g1',\n", - " root_link=root_link,\n", - " tip_link=tip_link,\n", - " end_condition=monitor1)\n", - "gs.motion_goals.add_cartesian_pose(goal_pose=pose2,\n", - " name='g2',\n", - " root_link=root_link,\n", - " tip_link=tip_link,\n", - " absolute=True,\n", - " start_condition=monitor1,\n", - " end_condition=f'{monitor2} and {end_monitor}')\n", - "gs.motion_goals.allow_all_collisions()\n", - "gs.monitors.add_end_motion(start_condition=' and '.join([end_monitor, monitor2]))\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Visualize the Task Graph**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "visualize_last_task_graph()" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Visualize the Gant diagramm**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "visualize_last_gant_diagram()" - ] - }, - { - "cell_type": "markdown", - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "**Tutorial 3.2: Complex Sequencing**\n", - "\n", - "This can be utilized to build arbitrary complex task graphs.\n", - "\n", - "**Excersise 3.1: Read the code and compare your expectations with the execution, the printed out task graph and the Gantt diagramm.**\n", - "\n", - "**Excercise 3.2: Come up with your own sequences using everything we have looked at so far**" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n", - "is_executing": true - } - }, - "outputs": [], - "source": [ - "reset_giskard()\n", - "\n", - "# %% Define goals for later\n", - "right_arm_goal = {'r_shoulder_pan_joint': -1.7125,\n", - " 'r_shoulder_lift_joint': -0.25672,\n", - " 'r_upper_arm_roll_joint': -1.46335,\n", - " 'r_elbow_flex_joint': -2.12,\n", - " 'r_forearm_roll_joint': 1.76632,\n", - " 'r_wrist_flex_joint': -0.10001,\n", - " 'r_wrist_roll_joint': 0.05106}\n", - "\n", - "left_arm_goal = {'l_shoulder_pan_joint': 1.9652,\n", - " 'l_shoulder_lift_joint': - 0.26499,\n", - " 'l_upper_arm_roll_joint': 1.3837,\n", - " 'l_elbow_flex_joint': -2.12,\n", - " 'l_forearm_roll_joint': 16.99,\n", - " 'l_wrist_flex_joint': - 0.10001,\n", - " 'l_wrist_roll_joint': 0}\n", - "\n", - "base_goal = PoseStamped()\n", - "base_goal.header.frame_id = 'map'\n", - "base_goal.pose.position.x = 2\n", - "base_goal.pose.orientation.w = 1\n", - "\n", - "# %% Monitors observe something and turn to True, if the condition is met. They don't cause any motions.\n", - "# All monitor related operations are grouped under giskard_wrapper.monitors.\n", - "# Let's define a few\n", - "# This one turns True when the length of the current trajectory % mod = 0\n", - "alternator = gs.monitors.add_alternator(mod=2)\n", - "# This one sleeps and then turns True\n", - "sleep1 = gs.monitors.add_sleep(1, name='sleep1')\n", - "# This prints a message and then turns True.\n", - "# With start_condition you can define which monitors need to be True in order for this one to become active\n", - "print1 = gs.monitors.add_print(message=f'{sleep1} done', start_condition=sleep1)\n", - "# You can also write logical expressions using \"and\", \"or\" and \"not\" to combine multiple monitors\n", - "sleep2 = gs.monitors.add_sleep(1.5, name='sleep2', start_condition=f'{print1} or not {sleep1}')\n", - "\n", - "# %% Now Let's define some motion goals.\n", - "# We want to reach two joint goals, so we first define monitors for checking that end condition.\n", - "right_monitor = gs.monitors.add_joint_position(goal_state=right_arm_goal,\n", - " name='right pose reached',\n", - " start_condition=sleep1)\n", - "# You can use add_motion_goal to add any monitor implemented in giskardpy.monitor.\n", - "# All remaining parameters are forwarded to the __init__ function of that class.\n", - "# All specialized add_ functions are just wrappers for add_monitor.\n", - "left_monitor = gs.monitors.add_monitor(monitor_class=JointGoalReached.__name__,\n", - " goal_state=left_arm_goal,\n", - " name='left pose reached',\n", - " start_condition=sleep1,\n", - " threshold=0.01)\n", - "\n", - "# We set two separate motion goals for the joints of the left and right arm.\n", - "# All motion goal related operations are groups under gs.motion_goals.\n", - "# The one for the right arm starts when the sleep2 monitor is done and ends, when the right_monitor is done,\n", - "# meaning it continues until the joint goal was reached.\n", - "gs.motion_goals.add_joint_position(goal_state=right_arm_goal,\n", - " name='right pose',\n", - " start_condition=sleep2,\n", - " end_condition=right_monitor)\n", - "# You can use add_motion_goal to add any motion goal implemented in giskardpy.goals.\n", - "# All remaining parameters are forwarded to the __init__ function of that class.\n", - "gs.motion_goals.add_motion_goal(motion_goal_class=JointPositionList.__name__,\n", - " goal_state=left_arm_goal,\n", - " name='left pose',\n", - " end_condition=left_monitor)\n", - "\n", - "# %% Now let's define a goal for the base, 2m in front of it.\n", - "# First we define a monitor which checks if that pose was reached.\n", - "base_monitor = gs.monitors.add_cartesian_pose(root_link='map',\n", - " tip_link='base_footprint',\n", - " goal_pose=base_goal)\n", - "\n", - "# and then we define a motion goal for it.\n", - "# The hold_condition causes the motion goal to hold as long as the condition is True.\n", - "# In this case, the cart pose is halted if time % 2 == 1 and active if time % 2 == 0.\n", - "gs.motion_goals.add_cartesian_pose(root_link='map',\n", - " tip_link='base_footprint',\n", - " goal_pose=base_goal,\n", - " hold_condition=f'not {alternator}',\n", - " end_condition=base_monitor)\n", - "\n", - "# %% Define when the motion should end.\n", - "# Usually you'd use the local minimum reached monitor for this.\n", - "# Most monitors also have a stay_true parameter (when it makes sense), with reasonable default values.\n", - "# In this case, we don't want the local minimum reached monitor to stay True, because it might get triggered during\n", - "# the sleeps and therefore set it to False.\n", - "local_min = gs.monitors.add_local_minimum_reached(stay_true=False)\n", - "\n", - "# Giskard will only end the motion generation and return Success, if an end monitor becomes True.\n", - "# We do this by defining one that gets triggered, when a local minimum was reached, sleep2 is done and the motion goals\n", - "# were reached.\n", - "gs.monitors.add_end_motion(start_condition=' and '.join([local_min,\n", - " sleep2,\n", - " right_monitor,\n", - " left_monitor,\n", - " base_monitor]))\n", - "# It's good to also add a cancel condition in case something went wrong and the end motion monitor is unable to become\n", - "# True. Currently, the only predefined specialized cancel monitor is max trajectory length.\n", - "# Alternative you can use monitor.add_cancel_motion similar to end_motion.\n", - "gs.monitors.add_max_trajectory_length(120)\n", - "# Lastly we allow all collisions\n", - "gs.motion_goals.allow_all_collisions()\n", - "# And execute the goal.\n", - "assert gs.execute().error.code == GiskardError.SUCCESS" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "visualize_last_task_graph()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [ - "visualize_last_gant_diagram()" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": { - "collapsed": false, - "jupyter": { - "outputs_hidden": false - }, - "pycharm": { - "name": "#%%\n" - } - }, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3 (ipykernel)", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.8.10" - } - }, - "nbformat": 4, - "nbformat_minor": 4 -} \ No newline at end of file diff --git a/src/giskardpy/python_interface/python_interface.py b/src/giskardpy/python_interface/python_interface.py index d0bdd7f0c6..e71387a090 100644 --- a/src/giskardpy/python_interface/python_interface.py +++ b/src/giskardpy/python_interface/python_interface.py @@ -40,7 +40,7 @@ PayloadAlternator from giskardpy.utils.utils import kwargs_to_json, get_all_classes_in_package from giskardpy.goals.feature_functions import AlignPerpendicular, HeightGoal, AngleGoal, DistanceGoal -from giskardpy.monitors.feature_monitors import PerpendicularMonitor, AngleMonitor, HeightMonitor, DistanceMonitor +from giskardpy.motion_graph.monitors.feature_monitors import PerpendicularMonitor, AngleMonitor, HeightMonitor, DistanceMonitor from giskard_msgs.msg import ExecutionState From b909ce904cb41671a4606f6584a964db13fbf4b5 Mon Sep 17 00:00:00 2001 From: malte Date: Wed, 21 Aug 2024 07:55:15 +0200 Subject: [PATCH 41/43] adapted feature monitors --- .../motion_graph/monitors/feature_monitors.py | 8 ++++---- .../python_interface/python_interface.py | 16 ++++++++++++++++ 2 files changed, 20 insertions(+), 4 deletions(-) diff --git a/src/giskardpy/motion_graph/monitors/feature_monitors.py b/src/giskardpy/motion_graph/monitors/feature_monitors.py index efe4d63c58..854e251330 100644 --- a/src/giskardpy/motion_graph/monitors/feature_monitors.py +++ b/src/giskardpy/motion_graph/monitors/feature_monitors.py @@ -59,7 +59,7 @@ def __init__(self, hold_condition: cas.Expression = cas.FalseSymbol, end_condition: cas.Expression = cas.FalseSymbol): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, - controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition, + controlled_feature=tip_point, name=name, start_condition=start_condition, hold_condition=hold_condition, end_condition=end_condition, root_group=root_group, tip_group=tip_group) @@ -84,7 +84,7 @@ def __init__(self, tip_link: str, root_link: str, end_condition: cas.Expression = cas.FalseSymbol ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_normal, - controlled_feature=tip_normal, name=name, stay_true=stay_true, start_condition=start_condition, + controlled_feature=tip_normal, name=name, start_condition=start_condition, hold_condition=hold_condition, end_condition=end_condition, root_group=root_group, tip_group=tip_group) @@ -108,7 +108,7 @@ def __init__(self, tip_link: str, root_link: str, end_condition: cas.Expression = cas.FalseSymbol ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_point, - controlled_feature=tip_point, name=name, stay_true=stay_true, start_condition=start_condition, + controlled_feature=tip_point, name=name, start_condition=start_condition, hold_condition=hold_condition, end_condition=end_condition, root_group=root_group, tip_group=tip_group) @@ -134,7 +134,7 @@ def __init__(self, tip_link: str, root_link: str, end_condition: cas.Expression = cas.FalseSymbol ): super().__init__(tip_link=tip_link, root_link=root_link, reference_feature=reference_vector, - controlled_feature=tip_vector, name=name, stay_true=stay_true, start_condition=start_condition, + controlled_feature=tip_vector, name=name, start_condition=start_condition, hold_condition=hold_condition, end_condition=end_condition, root_group=root_group, tip_group=tip_group) diff --git a/src/giskardpy/python_interface/python_interface.py b/src/giskardpy/python_interface/python_interface.py index e71387a090..d598e6a89b 100644 --- a/src/giskardpy/python_interface/python_interface.py +++ b/src/giskardpy/python_interface/python_interface.py @@ -1879,6 +1879,8 @@ def add_vectors_perpendicular(self, tip_normal: Vector3Stamped, name: Optional[str] = None, start_condition: str = '', + hold_condition: str = '', + end_condition: Optional[str] = None, root_group: Optional[str] = None, tip_group: Optional[str] = None, threshold: float = 0.01) -> str: @@ -1892,6 +1894,8 @@ def add_vectors_perpendicular(self, reference_normal=reference_normal, tip_normal=tip_normal, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group, threshold=threshold) @@ -1905,6 +1909,8 @@ def add_angle(self, upper_angle: float, name: Optional[str] = None, start_condition: str = '', + hold_condition: str = '', + end_condition: Optional[str] = None, root_group: Optional[str] = None, tip_group: Optional[str] = None) -> str: """ @@ -1919,6 +1925,8 @@ def add_angle(self, lower_limit=lower_angle, upper_limit=upper_angle, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group) @@ -1931,6 +1939,8 @@ def add_height(self, upper_limit: float, name: Optional[str] = None, start_condition: str = '', + hold_condition: str = '', + end_condition: Optional[str] = None, root_group: Optional[str] = None, tip_group: Optional[str] = None) -> str: """ @@ -1946,6 +1956,8 @@ def add_height(self, lower_limit=lower_limit, upper_limit=upper_limit, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group) @@ -1958,6 +1970,8 @@ def add_distance(self, upper_limit: float, name: Optional[str] = None, start_condition: str = '', + hold_condition: str = '', + end_condition: Optional[str] = None, root_group: Optional[str] = None, tip_group: Optional[str] = None) -> str: """ @@ -1973,6 +1987,8 @@ def add_distance(self, lower_limit=lower_limit, upper_limit=upper_limit, start_condition=start_condition, + hold_condition=hold_condition, + end_condition=end_condition, root_group=root_group, tip_group=tip_group) From c733cf97ea217d3d6af2f9cf65e2ae97bcf5610e Mon Sep 17 00:00:00 2001 From: malte Date: Thu, 22 Aug 2024 09:23:38 +0200 Subject: [PATCH 42/43] addressed most comments for the PR --- src/giskardpy/goals/pointing.py | 5 +- .../python_interface/python_interface.py | 76 +++++++++---------- test/test_integration_pr2.py | 34 ++++++++- 3 files changed, 75 insertions(+), 40 deletions(-) diff --git a/src/giskardpy/goals/pointing.py b/src/giskardpy/goals/pointing.py index dafff1067a..ca9fff4b1a 100644 --- a/src/giskardpy/goals/pointing.py +++ b/src/giskardpy/goals/pointing.py @@ -59,7 +59,10 @@ def __init__(self, self.tip_V_pointing_axis.vector.z = 1 root_T_tip = god_map.world.compose_fk_expression(self.root, self.tip) - root_P_goal_point = cas.Point3(self.root_P_goal_point) + root_P_goal_point = symbol_manager.get_expr(f'god_map.motion_goal_manager.motion_goals[\'{str(self)}\']' + f'.root_P_goal_point', + input_type_hint=PointStamped, + output_type_hint=cas.Point3) root_P_goal_point.reference_frame = self.root tip_V_pointing_axis = cas.Vector3(self.tip_V_pointing_axis) diff --git a/src/giskardpy/python_interface/python_interface.py b/src/giskardpy/python_interface/python_interface.py index d598e6a89b..e0e6b4ac6f 100644 --- a/src/giskardpy/python_interface/python_interface.py +++ b/src/giskardpy/python_interface/python_interface.py @@ -40,7 +40,8 @@ PayloadAlternator from giskardpy.utils.utils import kwargs_to_json, get_all_classes_in_package from giskardpy.goals.feature_functions import AlignPerpendicular, HeightGoal, AngleGoal, DistanceGoal -from giskardpy.motion_graph.monitors.feature_monitors import PerpendicularMonitor, AngleMonitor, HeightMonitor, DistanceMonitor +from giskardpy.motion_graph.monitors.feature_monitors import PerpendicularMonitor, AngleMonitor, HeightMonitor, \ + DistanceMonitor from giskard_msgs.msg import ExecutionState @@ -2056,9 +2057,7 @@ def execute(self, wait: bool = True) -> MoveResult: :param wait: this function blocks if wait=True :return: result from giskard """ - result = self._send_action_goal(MoveGoal.EXECUTE, wait) - self.last_execution_state = result.execution_state - return result + return self._send_action_goal(MoveGoal.EXECUTE, wait) def projection(self, wait: bool = True) -> MoveResult: """ @@ -2066,9 +2065,7 @@ def projection(self, wait: bool = True) -> MoveResult: :param wait: this function blocks if wait=True :return: result from Giskard """ - result = self._send_action_goal(MoveGoal.PROJECTION, wait) - self.last_execution_state = result.execution_state - return result + return self._send_action_goal(MoveGoal.PROJECTION, wait) def _send_action_goal(self, goal_type: int, wait: bool = True) -> Optional[MoveResult]: """ @@ -2082,7 +2079,9 @@ def _send_action_goal(self, goal_type: int, wait: bool = True) -> Optional[MoveR goal.type = goal_type if wait: self._client.send_goal_and_wait(goal) - return self._client.get_result() + result = self._client.get_result() + self.last_execution_state = result + return result else: self._client.send_goal(goal, feedback_cb=self._feedback_cb) @@ -2117,7 +2116,15 @@ def get_result(self, timeout: rospy.Duration = rospy.Duration()) -> MoveResult: def _feedback_cb(self, msg: MoveFeedback): self.last_feedback = msg - def get_end_motion_reason(self, move_result: MoveResult = None, show_all=False): + def get_end_motion_reason(self, move_result: Optional[MoveResult] = None, show_all: bool = False) -> Dict[ + str, bool]: + """ + Analyzes a MoveResult msg to return a list of all monitors that hindered the EndMotion Monitors from becoming active. + Uses the last received MoveResult msg from execute() or projection() when not explicitly given. + :param move_result: the move_result msg to analyze + :param show_all: returns the state of all monitors when show_all==True + :return: Dict with monitor name as key and True or False as value + """ if not move_result and not self.last_execution_state: raise Exception('No MoveResult available to analyze') elif not move_result: @@ -2126,44 +2133,37 @@ def get_end_motion_reason(self, move_result: MoveResult = None, show_all=False): execution_state = move_result.execution_state result = {} + if show_all: + return {monitor.name: state for monitor, state in + zip(execution_state.monitors, execution_state.monitor_state)} - endMotion_idx = 0 - cancelMotion_idx = 0 - idx = 0 - for monitor in execution_state.monitors: - if monitor.monitor_class == 'CancelMotion': - cancelMotion_idx = idx - if monitor.monitor_class == 'EndMotion': - endMotion_idx = idx - idx += 1 - - if execution_state.monitor_state[endMotion_idx] == 1: - # the end motion was successful - return result + failedEndMotion_ids = [] + for idx, monitor in enumerate(execution_state.monitors): + if monitor.monitor_class == 'EndMotion' and execution_state.monitor_state[idx] == 0: + failedEndMotion_ids.append(idx) - if show_all: - for monitor, state in zip(execution_state.monitors, execution_state.monitor_state): - result[monitor.name] = state + if len(failedEndMotion_ids) == 0: + # the end motion was successful return result def search_for_monitor_values_in_start_condition(start_condition: str): res = [] for monitor, state in zip(execution_state.monitors, execution_state.monitor_state): - if monitor.name in start_condition and state == 0: + if f'\'{monitor.name}\'' in start_condition and state == 0: res.append(monitor) return res - start_condition = execution_state.monitors[endMotion_idx].start_condition - false_monitors = search_for_monitor_values_in_start_condition(start_condition=start_condition) - idx = 0 - # repeatedly search for all inactive monitors in all start_conditions directly - # connected to the endMotion start_condition - while idx < len(false_monitors): - if false_monitors[idx].start_condition != '1.0': - false_monitors.extend(search_for_monitor_values_in_start_condition(false_monitors[idx].start_condition)) - idx += 1 - - for mon in false_monitors: - result[mon.name] = False + for endMotion_idx in failedEndMotion_ids: + start_condition = execution_state.monitors[endMotion_idx].start_condition + false_monitors = search_for_monitor_values_in_start_condition(start_condition=start_condition) + # repeatedly search for all inactive monitors in all start_conditions directly + # connected to the endMotion start_condition + for idx, false_monitor in enumerate(false_monitors): + if false_monitors[idx].start_condition != '1.0': + false_monitors.extend( + search_for_monitor_values_in_start_condition(false_monitor.start_condition)) + + for mon in false_monitors: + result[mon.name] = False return result diff --git a/test/test_integration_pr2.py b/test/test_integration_pr2.py index 2842009e42..b024727bf7 100644 --- a/test/test_integration_pr2.py +++ b/test/test_integration_pr2.py @@ -4862,7 +4862,39 @@ def test_get_end_motion_reason_convoluted(self, zero_pose: PR2TestWrapper): assert len(reason) == 3 and list(reason.keys())[0] == 'M2 DistanceMonitor' \ and list(reason.keys())[2] == 'M0 sleep1' and list(reason.keys())[1] == 'M1 sleep2' -# kernprof -lv py.test -s test/test_integration_pr2.py + def test_multiple_end_motion_monitors(self, zero_pose: PR2TestWrapper): + goal_point = PointStamped() + goal_point.header.frame_id = 'map' + goal_point.point = Point(2, 2, 2) + controlled_point = PointStamped() + controlled_point.header.frame_id = zero_pose.r_tip + + mon_sleep1 = zero_pose.monitors.add_sleep(10, name='sleep1') + mon_sleep2 = zero_pose.monitors.add_sleep(10, start_condition=mon_sleep1, name='sleep2') + mon_distance = zero_pose.monitors.add_distance(root_link='map', tip_link=zero_pose.r_tip, + reference_point=goal_point, + tip_point=controlled_point, lower_limit=0, upper_limit=0, + start_condition=mon_sleep2) + zero_pose.motion_goals.add_distance(root_link='base_link', tip_link=zero_pose.r_tip, reference_point=goal_point, + tip_point=controlled_point, lower_limit=0, upper_limit=0) + + mon_trajectory = zero_pose.monitors.add_max_trajectory_length(max_trajectory_length=1) + zero_pose.monitors.add_cancel_motion(mon_trajectory, error_message='stop motion') + zero_pose.monitors.add_end_motion(mon_distance) + + mon_sleep3 = zero_pose.monitors.add_sleep(20, name='sleep3') + mon_sleep4 = zero_pose.monitors.add_sleep(20, start_condition=mon_sleep3, name='sleep4') + zero_pose.monitors.add_end_motion(mon_sleep4) + + result = zero_pose.execute(expected_error_code=GiskardError.MAX_TRAJECTORY_LENGTH, + add_local_minimum_reached=False) + reason = zero_pose.get_end_motion_reason(move_result=result) + print(reason) + assert len(reason) == 5 and list(reason.keys())[0] == 'M2 DistanceMonitor' \ + and list(reason.keys())[1] == 'M1 sleep2' and list(reason.keys())[2] == 'M0 sleep1' and \ + list(reason.keys())[3] == 'M7 sleep4' and list(reason.keys())[4] == 'M6 sleep3' + + # kernprof -lv py.test -s test/test_integration_pr2.py # time: [1-9][1-9]*.[1-9]* s # import pytest # pytest.main(['-s', __file__ + '::TestManipulability::test_manip1']) From 70867e6fa2d3ec14402b0ec74a4fef457cbfc45e Mon Sep 17 00:00:00 2001 From: maltehue <122607802+maltehue@users.noreply.github.com> Date: Thu, 22 Aug 2024 10:25:32 +0200 Subject: [PATCH 43/43] Update reusable_robot_ci.yml go back to devel branch in giskard_msgs --- .github/workflows/reusable_robot_ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/reusable_robot_ci.yml b/.github/workflows/reusable_robot_ci.yml index 7b33757fba..4c5f82ecee 100644 --- a/.github/workflows/reusable_robot_ci.yml +++ b/.github/workflows/reusable_robot_ci.yml @@ -93,7 +93,7 @@ jobs: with: path: 'ros_ws/src/giskard_msgs' repository: SemRoCo/giskard_msgs - ref: monitor_result_feedback + ref: devel - name: Checkout iai_maps uses: actions/checkout@v3 with: