diff --git a/.envrc b/.envrc new file mode 100644 index 0000000..3550a30 --- /dev/null +++ b/.envrc @@ -0,0 +1 @@ +use flake diff --git a/.gitignore b/.gitignore index 960675a..71add28 100644 --- a/.gitignore +++ b/.gitignore @@ -10,4 +10,7 @@ log/ .vscode/ #Pycache folder -__pycache__/ \ No newline at end of file +__pycache__/ + +#Direnv +.direnv/ diff --git a/.gitmodules b/.gitmodules index ccd1110..3c3b3a3 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,3 +1,6 @@ [submodule "src/ros2_interfaces_pkg"] path = src/ros2_interfaces_pkg - url = git@github.com:SHC-ASTRA/ros2_interfaces_pkg.git + url = ../ros2_interfaces_pkg +[submodule "src/astra_description"] + path = src/astra_descriptions + url = ../astra_descriptions diff --git a/auto_start/auto_start_anchor.sh b/auto_start/auto_start_anchor.sh index 724062c..0d7e9c2 100755 --- a/auto_start/auto_start_anchor.sh +++ b/auto_start/auto_start_anchor.sh @@ -21,4 +21,4 @@ source /home/clucky/rover-ros2/install/setup.bash cd /home/clucky/rover-ros2/ # Launch the ROS 2 node with the desired mode -ros2 launch rover_launch.py mode:=anchor +ros2 launch anchor_pkg rover.launch.py mode:=anchor diff --git a/flake.nix b/flake.nix index 52c2c74..8e7b60f 100644 --- a/flake.nix +++ b/flake.nix @@ -1,30 +1,72 @@ { + description = "Development environment for ASTRA Anchor"; + inputs = { nix-ros-overlay.url = "github:lopsided98/nix-ros-overlay/master"; - nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!! + nixpkgs.follows = "nix-ros-overlay/nixpkgs"; # IMPORTANT!!! }; - outputs = { self, nix-ros-overlay, nixpkgs }: - nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem (system: + + outputs = + { + self, + nix-ros-overlay, + nixpkgs, + }: + nix-ros-overlay.inputs.flake-utils.lib.eachDefaultSystem ( + system: let pkgs = import nixpkgs { inherit system; overlays = [ nix-ros-overlay.overlays.default ]; }; - in { + in + { devShells.default = pkgs.mkShell { name = "ASTRA Anchor"; - packages = [ - pkgs.colcon - pkgs.python312Packages.pyserial - pkgs.python312Packages.pygame - (with pkgs.rosPackages.humble; buildEnv { - paths = [ - ros-core ros2cli ros2run ros2bag ament-cmake-core python-cmake-module - ]; - }) + packages = with pkgs; [ + colcon + (python312.withPackages ( + p: with p; [ + pyserial + pygame + scipy + crccheck + black + ] + )) + ( + with rosPackages.humble; + buildEnv { + paths = [ + ros-core + ros2cli + ros2run + ros2bag + rviz2 + xacro + ament-cmake-core + python-cmake-module + diff-drive-controller + parameter-traits + generate-parameter-library + joint-state-publisher-gui + robot-state-publisher + ros2-control + controller-manager + # ros2-controllers nixpkg does not build :( + ]; + } + ) ]; + shellHook = '' + # Display stuff + export DISPLAY=''${DISPLAY:-:0} + export QT_X11_NO_MITSHM=1 + ''; }; - }); + } + ); + nixConfig = { extra-substituters = [ "https://ros.cachix.org" ]; extra-trusted-public-keys = [ "ros.cachix.org-1:dSyZxI8geDCJrwgvCOHDoAfOm5sV1wCPjBkKL+38Rvo=" ]; diff --git a/src/anchor_pkg/anchor_pkg/anchor_node.py b/src/anchor_pkg/anchor_pkg/anchor_node.py index aa46fdb..e4d1ff5 100644 --- a/src/anchor_pkg/anchor_pkg/anchor_node.py +++ b/src/anchor_pkg/anchor_pkg/anchor_node.py @@ -43,30 +43,10 @@ class SerialRelay(Node): # Initalize node with name super().__init__("anchor_node")#previously 'serial_publisher' - # New pub/sub with VicCAN - self.fromvic_debug_pub_ = self.create_publisher(String, '/anchor/from_vic/debug', 20) - self.fromvic_core_pub_ = self.create_publisher(VicCAN, '/anchor/from_vic/core', 20) - self.fromvic_arm_pub_ = self.create_publisher(VicCAN, '/anchor/from_vic/arm', 20) - self.fromvic_bio_pub_ = self.create_publisher(VicCAN, '/anchor/from_vic/bio', 20) - - self.mock_mcu_sub_ = self.create_subscription(String, '/anchor/from_vic/mock_mcu', self.on_mock_fromvic, 20) - self.tovic_sub_ = self.create_subscription(VicCAN, '/anchor/to_vic/relay', self.on_relay_tovic_viccan, 20) - self.tovic_debug_sub_ = self.create_subscription(String, '/anchor/to_vic/relay_string', self.on_relay_tovic_string, 20) - - - # Create publishers - self.arm_pub = self.create_publisher(String, '/anchor/arm/feedback', 10) - self.core_pub = self.create_publisher(String, '/anchor/core/feedback', 10) - self.bio_pub = self.create_publisher(String, '/anchor/bio/feedback', 10) - - self.debug_pub = self.create_publisher(String, '/anchor/debug', 10) - - # Create a subscriber - self.relay_sub = self.create_subscription(String, '/anchor/relay', self.on_relay_tovic_string, 10) - # Loop through all serial devices on the computer to check for the MCU self.port = None - # self.port = "/tmp/ttyACM9" # Fake port, for debugging + if port_override := os.getenv("PORT_OVERRIDE"): + self.port = port_override ports = SerialRelay.list_serial_ports() for i in range(4): if self.port is not None: @@ -97,6 +77,27 @@ class SerialRelay(Node): self.ser.write(b"can_relay_mode,on\n") atexit.register(self.cleanup) + # New pub/sub with VicCAN + self.fromvic_debug_pub_ = self.create_publisher(String, '/anchor/from_vic/debug', 20) + self.fromvic_core_pub_ = self.create_publisher(VicCAN, '/anchor/from_vic/core', 20) + self.fromvic_arm_pub_ = self.create_publisher(VicCAN, '/anchor/from_vic/arm', 20) + self.fromvic_bio_pub_ = self.create_publisher(VicCAN, '/anchor/from_vic/bio', 20) + + self.mock_mcu_sub_ = self.create_subscription(String, '/anchor/from_vic/mock_mcu', self.on_mock_fromvic, 20) + self.tovic_sub_ = self.create_subscription(VicCAN, '/anchor/to_vic/relay', self.on_relay_tovic_viccan, 20) + self.tovic_debug_sub_ = self.create_subscription(String, '/anchor/to_vic/relay_string', self.on_relay_tovic_string, 20) + + + # Create publishers + self.arm_pub = self.create_publisher(String, '/anchor/arm/feedback', 10) + self.core_pub = self.create_publisher(String, '/anchor/core/feedback', 10) + self.bio_pub = self.create_publisher(String, '/anchor/bio/feedback', 10) + + self.debug_pub = self.create_publisher(String, '/anchor/debug', 10) + + # Create a subscriber + self.relay_sub = self.create_subscription(String, '/anchor/relay', self.on_relay_tovic_string, 10) + def run(self): # This thread makes all the update processes run in the background @@ -171,9 +172,37 @@ class SerialRelay(Node): """ Relay a string message from the MCU to the appropriate VicCAN topic """ self.fromvic_debug_pub_.publish(String(data=msg)) parts = msg.strip().split(",") - if len(parts) < 3 or parts[0] != "can_relay_fromvic": + if len(parts) > 0 and parts[0] != "can_relay_fromvic": + self.get_logger().debug(f"Ignoring non-VicCAN message: '{msg.strip()}'") return + # String validation + malformed: bool = False + malformed_reason: str = "" + if len(parts) < 3 or len(parts) > 7: + malformed = True + malformed_reason = f"invalid argument count (expected [3,7], got {len(parts)})" + elif parts[1] not in ["core", "arm", "digit", "citadel", "broadcast"]: + malformed = True + malformed_reason = f"invalid mcu_name '{parts[1]}'" + elif not(parts[2].isnumeric()) or int(parts[2]) < 0: + malformed = True + malformed_reason = f"command_id '{parts[2]}' is not a non-negative integer" + else: + for x in parts[3:]: + try: + float(x) + except ValueError: + malformed = True + malformed_reason = f"data '{x}' is not a float" + break + + if malformed: + self.get_logger().warning(f"Ignoring malformed from_vic message: '{msg.strip()}'; reason: {malformed_reason}") + return + + # Have valid VicCAN message + output = VicCAN() output.mcu_name = parts[1] output.command_id = int(parts[2]) diff --git a/rover_launch.py b/src/anchor_pkg/launch/rover.launch.py similarity index 100% rename from rover_launch.py rename to src/anchor_pkg/launch/rover.launch.py diff --git a/src/anchor_pkg/package.xml b/src/anchor_pkg/package.xml index 19dc42a..4903787 100644 --- a/src/anchor_pkg/package.xml +++ b/src/anchor_pkg/package.xml @@ -8,6 +8,10 @@ AGPL-3.0-only rclpy + common_interfaces + python3-serial + + black ament_copyright ament_flake8 diff --git a/src/anchor_pkg/setup.py b/src/anchor_pkg/setup.py index e2844e7..f29392e 100644 --- a/src/anchor_pkg/setup.py +++ b/src/anchor_pkg/setup.py @@ -1,4 +1,6 @@ from setuptools import find_packages, setup +from os import path +from glob import glob package_name = 'anchor_pkg' @@ -9,7 +11,8 @@ setup( data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), + (path.join("share", package_name), ['package.xml']), + (path.join("share", package_name, "launch"), glob("launch/*")) ], install_requires=['setuptools'], zip_safe=True, diff --git a/src/arm_pkg/package.xml b/src/arm_pkg/package.xml index 8982d81..efcb547 100644 --- a/src/arm_pkg/package.xml +++ b/src/arm_pkg/package.xml @@ -8,7 +8,11 @@ AGPL-3.0-only rclpy + common_interfaces + python3-numpy ros2_interfaces_pkg + + python3-ikpy-pip ament_copyright ament_flake8 diff --git a/src/astra_descriptions b/src/astra_descriptions new file mode 160000 index 0000000..4ab41e9 --- /dev/null +++ b/src/astra_descriptions @@ -0,0 +1 @@ +Subproject commit 4ab41e9c826b0495aa90d0df7972482a831b255b diff --git a/src/bio_pkg/package.xml b/src/bio_pkg/package.xml index d4a8515..d87859f 100644 --- a/src/bio_pkg/package.xml +++ b/src/bio_pkg/package.xml @@ -8,6 +8,7 @@ AGPL-3.0-only rclpy + common_interfaces ros2_interfaces_pkg ament_copyright diff --git a/src/core_gazebo/CMakeLists.txt b/src/core_gazebo/CMakeLists.txt deleted file mode 100644 index 1aa734c..0000000 --- a/src/core_gazebo/CMakeLists.txt +++ /dev/null @@ -1,36 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(core_gazebo) - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(controller_manager REQUIRED) -find_package(gripper_controllers REQUIRED) -find_package(rclcpp REQUIRED) -find_package(ros2_control REQUIRED) -find_package(ros2_controllers REQUIRED) -find_package(trajectory_msgs REQUIRED) -find_package(xacro REQUIRED) - -# Copy necessary files to designated locations in the project -install ( - DIRECTORY config launch models worlds - DESTINATION share/${PROJECT_NAME} -) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # comment the line when a copyright and license is added to all source files - set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # comment the line when this package is in a git repo and when - # a copyright and license is added to all source files - set(ament_cmake_cpplint_FOUND TRUE) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/src/core_gazebo/config/ros_gz_bridge.yaml b/src/core_gazebo/config/ros_gz_bridge.yaml deleted file mode 100644 index 7b9c4eb..0000000 --- a/src/core_gazebo/config/ros_gz_bridge.yaml +++ /dev/null @@ -1,25 +0,0 @@ -# gz topic published by Sensors plugin -- ros_topic_name: "camera_head/depth/camera_info" - gz_topic_name: "camera_head/camera_info" - ros_type_name: "sensor_msgs/msg/CameraInfo" - gz_type_name: "gz.msgs.CameraInfo" - direction: GZ_TO_ROS - lazy: true # Determines whether connections are created immediately at startup (when false) or only when data is actually requested by a subscriber (when true), helping to conserve system resources at the cost of potential initial delays in data flow. - -# gz topic published by Sensors plugin -- ros_topic_name: "camera_head/depth/color/points" - gz_topic_name: "camera_head/points" - ros_type_name: "sensor_msgs/msg/PointCloud2" - gz_type_name: "gz.msgs.PointCloudPacked" - direction: GZ_TO_ROS - lazy: true - -# Clock configuration -- ros_topic_name: "clock" - gz_topic_name: "clock" - ros_type_name: "rosgraph_msgs/msg/Clock" - gz_type_name: "gz.msgs.Clock" - direction: GZ_TO_ROS - lazy: false - - diff --git a/src/core_gazebo/launch/core.gazebo.launch.py b/src/core_gazebo/launch/core.gazebo.launch.py deleted file mode 100644 index ebbf4ff..0000000 --- a/src/core_gazebo/launch/core.gazebo.launch.py +++ /dev/null @@ -1,286 +0,0 @@ -#!/usr/bin/env python3 - -import os -from launch import LaunchDescription -from launch.actions import ( - AppendEnvironmentVariable, - DeclareLaunchArgument, - IncludeLaunchDescription -) -from launch.conditions import IfCondition -from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration, PathJoinSubstitution -from launch_ros.actions import Node -from launch_ros.substitutions import FindPackageShare - - -def generate_launch_description(): - """ - Generate a launch description for the Gazebo simulation. - - This function sets up all necessary parameters, paths, and nodes required to launch - the Gazebo simulation with a robot. It handles: - 1. Setting up package paths and constants - 2. Declaring launch arguments for robot configuration - 3. Setting up the Gazebo environment - 4. Spawning the robot in simulation - - Returns: - LaunchDescription: A complete launch description for the simulation - """ - # Constants for paths to different files and folders - package_name_gazebo = 'core_gazebo' - package_name_description = 'core_rover_description' - # package_name_moveit = 'mycobot_moveit_config' - - default_robot_name = 'core_rover' - gazebo_models_path = 'models' - default_world_file = 'pick_and_place_demo.world' - gazebo_worlds_path = 'worlds' - - ros_gz_bridge_config_file_path = 'config/ros_gz_bridge.yaml' - - # Set the path to different files and folders - pkg_ros_gz_sim = FindPackageShare(package='ros_gz_sim').find('ros_gz_sim') - pkg_share_gazebo = FindPackageShare(package=package_name_gazebo).find(package_name_gazebo) - pkg_share_description = FindPackageShare( - package=package_name_description).find(package_name_description) - # pkg_share_moveit = FindPackageShare(package=package_name_moveit).find(package_name_moveit) - - gazebo_models_path = os.path.join(pkg_share_gazebo, gazebo_models_path) - default_ros_gz_bridge_config_file_path = os.path.join( - pkg_share_gazebo, ros_gz_bridge_config_file_path) - - # Get the parent directory of the package share to access all ROS packages - ros_packages_path = os.path.dirname(pkg_share_description) - - # Launch configuration variables - jsp_gui = LaunchConfiguration('jsp_gui') - load_controllers = LaunchConfiguration('load_controllers') - robot_name = LaunchConfiguration('robot_name') - use_rviz = LaunchConfiguration('use_rviz') - use_camera = LaunchConfiguration('use_camera') - use_gazebo = LaunchConfiguration('use_gazebo') - use_robot_state_pub = LaunchConfiguration('use_robot_state_pub') - use_sim_time = LaunchConfiguration('use_sim_time') - world_file = LaunchConfiguration('world_file') - - world_path = PathJoinSubstitution([ - pkg_share_gazebo, - gazebo_worlds_path, - world_file - ]) - - # Set the pose configuration variables - x = LaunchConfiguration('x') - y = LaunchConfiguration('y') - z = LaunchConfiguration('z') - roll = LaunchConfiguration('roll') - pitch = LaunchConfiguration('pitch') - yaw = LaunchConfiguration('yaw') - - - ################################################################################################ - # Declare the launch arguments - - declare_robot_name_cmd = DeclareLaunchArgument( - name='robot_name', - default_value=default_robot_name, - description='The name for the robot') - - declare_load_controllers_cmd = DeclareLaunchArgument( - name='load_controllers', - default_value='true', - description='Flag to enable loading of ROS 2 controllers') - - declare_use_robot_state_pub_cmd = DeclareLaunchArgument( - name='use_robot_state_pub', - default_value='true', - description='Flag to enable robot state publisher') - - # GUI and visualization arguments - declare_jsp_gui_cmd = DeclareLaunchArgument( - name='jsp_gui', - default_value='false', - description='Flag to enable joint_state_publisher_gui') - - declare_use_camera_cmd = DeclareLaunchArgument( - name='use_camera', - default_value='false', - description='Flag to enable the RGBD camera for Gazebo point cloud simulation') - - declare_use_gazebo_cmd = DeclareLaunchArgument( - name='use_gazebo', - default_value='true', - description='Flag to enable Gazebo') - - declare_use_rviz_cmd = DeclareLaunchArgument( - name='use_rviz', - default_value='true', - description='Flag to enable RViz') - - declare_use_sim_time_cmd = DeclareLaunchArgument( - name='use_sim_time', - default_value='true', - description='Use simulation (Gazebo) clock if true') - - declare_world_cmd = DeclareLaunchArgument( - name='world_file', - default_value=default_world_file, - description='World file name (e.g., simple_demo.world, pick_and_place_demo.world)') - - # Pose arguments - declare_x_cmd = DeclareLaunchArgument( - name='x', - default_value='0.0', - description='x component of initial position, meters') - - declare_y_cmd = DeclareLaunchArgument( - name='y', - default_value='0.0', - description='y component of initial position, meters') - - declare_z_cmd = DeclareLaunchArgument( - name='z', - default_value='0.75', - description='z component of initial position, meters') - - declare_roll_cmd = DeclareLaunchArgument( - name='roll', - default_value='0.0', - description='roll angle of initial orientation, radians') - - declare_pitch_cmd = DeclareLaunchArgument( - name='pitch', - default_value='0.0', - description='pitch angle of initial orientation, radians') - - declare_yaw_cmd = DeclareLaunchArgument( - name='yaw', - default_value='0.0', - description='yaw angle of initial orientation, radians') - - - ################################################################################################ - # Launch stuff - - # Include Robot State Publisher launch file if enabled - robot_state_publisher_cmd = IncludeLaunchDescription( - PythonLaunchDescriptionSource([ - os.path.join(pkg_share_description, 'launch', 'robot_state_publisher.launch.py') - ]), - launch_arguments={ - 'jsp_gui': jsp_gui, - 'use_camera': use_camera, - 'use_gazebo': use_gazebo, - 'use_rviz': use_rviz, - 'use_sim_time': use_sim_time - }.items(), - condition=IfCondition(use_robot_state_pub) - ) - - # # Include ROS 2 Controllers launch file if enabled - # load_controllers_cmd = IncludeLaunchDescription( - # PythonLaunchDescriptionSource([ - # os.path.join(pkg_share_moveit, 'launch', 'load_ros2_controllers.launch.py') - # ]), - # launch_arguments={ - # 'use_sim_time': use_sim_time - # }.items(), - # condition=IfCondition(load_controllers) - # ) - - # Set Gazebo model path - include both models directory and ROS packages - set_env_vars_resources = AppendEnvironmentVariable( - 'GZ_SIM_RESOURCE_PATH', - gazebo_models_path) - - # Add ROS packages path so Gazebo can resolve package:// URIs - set_env_vars_packages = AppendEnvironmentVariable( - 'GZ_SIM_RESOURCE_PATH', - os.path.dirname(pkg_share_description)) - - # Start Gazebo with optimized arguments - start_gazebo_cmd = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')), - launch_arguments=[('gz_args', [' -r -v 3 --render-engine ogre2 ', world_path])]) - - # Bridge ROS topics and Gazebo messages for establishing communication - start_gazebo_ros_bridge_cmd = Node( - package='ros_gz_bridge', - executable='parameter_bridge', - parameters=[{ - 'config_file': default_ros_gz_bridge_config_file_path, - }], - output='screen' - ) - - # Includes optimizations to minimize latency and bandwidth when streaming image data - start_gazebo_ros_image_bridge_cmd = Node( - package='ros_gz_image', - executable='image_bridge', - arguments=[ - '/camera_head/depth_image', - '/camera_head/image', - ], - remappings=[ - ('/camera_head/depth_image', '/camera_head/depth/image_rect_raw'), - ('/camera_head/image', '/camera_head/color/image_raw'), - ], - condition=IfCondition(use_camera) - ) - - # Spawn the robot - start_gazebo_ros_spawner_cmd = Node( - package='ros_gz_sim', - executable='create', - output='screen', - arguments=[ - '-topic', '/robot_description', - '-name', robot_name, - '-allow_renaming', 'true', - '-x', x, - '-y', y, - '-z', z, - '-R', roll, - '-P', pitch, - '-Y', yaw - ]) - - - ################################################################################################ - # Launch description - - ld = LaunchDescription() - - # Declare the launch options - ld.add_action(declare_robot_name_cmd) - ld.add_action(declare_jsp_gui_cmd) - ld.add_action(declare_load_controllers_cmd) - ld.add_action(declare_use_camera_cmd) - ld.add_action(declare_use_gazebo_cmd) - ld.add_action(declare_use_rviz_cmd) - ld.add_action(declare_use_robot_state_pub_cmd) - ld.add_action(declare_use_sim_time_cmd) - ld.add_action(declare_world_cmd) - - # Add pose arguments - ld.add_action(declare_x_cmd) - ld.add_action(declare_y_cmd) - ld.add_action(declare_z_cmd) - ld.add_action(declare_roll_cmd) - ld.add_action(declare_pitch_cmd) - ld.add_action(declare_yaw_cmd) - - # Add the actions to the launch description - ld.add_action(set_env_vars_resources) - ld.add_action(set_env_vars_packages) - ld.add_action(robot_state_publisher_cmd) - # ld.add_action(load_controllers_cmd) - ld.add_action(start_gazebo_cmd) - ld.add_action(start_gazebo_ros_bridge_cmd) - ld.add_action(start_gazebo_ros_image_bridge_cmd) - ld.add_action(start_gazebo_ros_spawner_cmd) - - return ld diff --git a/src/core_gazebo/package.xml b/src/core_gazebo/package.xml deleted file mode 100644 index a1ed1d4..0000000 --- a/src/core_gazebo/package.xml +++ /dev/null @@ -1,18 +0,0 @@ - - - - core_gazebo - 0.0.0 - TODO: Package description - David - AGPL-3.0-only - - ament_cmake - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/src/core_gazebo/worlds/empty.world b/src/core_gazebo/worlds/empty.world deleted file mode 100644 index d7d8bcc..0000000 --- a/src/core_gazebo/worlds/empty.world +++ /dev/null @@ -1,89 +0,0 @@ - - - - - - - - - libgz-physics-bullet-featherstone-plugin.so - - - - - - - - - - - - - - ogre2 - - - - - - - - 0.0 0.0 -9.8 - - - - - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun - - - - - - true - - - - - 0 0 1 - - - - - - 0.0 - - - - - - - - 0 0 1 - 100 100 - - - - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - 0.8 0.8 0.8 1 - - - - - - - - false - - - - diff --git a/src/core_gazebo/worlds/pick_and_place_demo.world b/src/core_gazebo/worlds/pick_and_place_demo.world deleted file mode 100644 index e8f33c1..0000000 --- a/src/core_gazebo/worlds/pick_and_place_demo.world +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - - - - - - - - - - - - - - ogre2 - - - - 0.0 0.0 -9.8 - - - - - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Sun - - - - - - - https://fuel.gazebosim.org/1.0/OpenRobotics/models/Ground Plane - - - - - - - - - - - - - false - - - - diff --git a/src/core_pkg/core_pkg/core_node.py b/src/core_pkg/core_pkg/core_node.py index 870bf1c..42c692d 100644 --- a/src/core_pkg/core_pkg/core_node.py +++ b/src/core_pkg/core_pkg/core_node.py @@ -14,12 +14,12 @@ import sys import threading import glob from scipy.spatial.transform import Rotation -from math import copysign +from math import copysign, pi from std_msgs.msg import String, Header -from sensor_msgs.msg import Imu, NavSatFix, NavSatStatus +from sensor_msgs.msg import Imu, NavSatFix, NavSatStatus, JointState from geometry_msgs.msg import TwistStamped, Twist -from ros2_interfaces_pkg.msg import CoreControl, CoreFeedback +from ros2_interfaces_pkg.msg import CoreControl, CoreFeedback, RevMotorState from ros2_interfaces_pkg.msg import VicCAN, NewCoreFeedback, Barometer, CoreCtrlState @@ -28,7 +28,7 @@ thread = None CORE_WHEELBASE = 0.836 # meters CORE_WHEEL_RADIUS = 0.171 # meters -CORE_GEAR_RATIO = 100 # Clucky: 100:1, Testbed: 64:1 +CORE_GEAR_RATIO = 100.0 # Clucky: 100:1, Testbed: 64:1 control_qos = qos.QoSProfile( history=qos.QoSHistoryPolicy.KEEP_LAST, @@ -41,6 +41,20 @@ control_qos = qos.QoSProfile( liveliness_lease_duration=Duration(seconds=5) ) +# Used to verify the length of an incoming VicCAN feedback message +# Key is VicCAN command_id, value is expected length of data list +viccan_msg_len_dict = { + 48: 1, + 49: 1, + 50: 2, + 51: 4, + 52: 4, + 53: 4, + 54: 4, + 56: 4, # really 3, but viccan + 58: 4 # ditto +} + class SerialRelay(Node): def __init__(self): @@ -67,7 +81,7 @@ class SerialRelay(Node): # Control # autonomy twist -- m/s and rad/s -- for autonomy, in particular Nav2 - self.cmd_vel_sub_ = self.create_subscription(TwistStamped, '/cmd_vel', self.cmd_vel_callback, qos_profile=control_qos) + self.cmd_vel_sub_ = self.create_subscription(TwistStamped, '/cmd_vel', self.cmd_vel_callback, 1) # manual twist -- [-1, 1] rather than real units self.twist_man_sub_ = self.create_subscription(Twist, '/core/twist', self.twist_man_callback, qos_profile=control_qos) # manual flags -- brake mode and max duty cycle @@ -77,26 +91,28 @@ class SerialRelay(Node): # Feedback # Consolidated and organized core feedback - self.feedback_new_pub_ = self.create_publisher(NewCoreFeedback, '/core/feedback_new', 10) + self.feedback_new_pub_ = self.create_publisher(NewCoreFeedback, '/core/feedback_new', qos_profile=qos.qos_profile_sensor_data) self.feedback_new_state = NewCoreFeedback() self.feedback_new_state.fl_motor.id = 1 self.feedback_new_state.bl_motor.id = 2 self.feedback_new_state.fr_motor.id = 3 self.feedback_new_state.br_motor.id = 4 self.telemetry_pub_timer = self.create_timer(1.0, self.publish_feedback) # TODO: not sure about this + # Joint states for topic-based controller + self.joint_state_pub_ = self.create_publisher(JointState, '/core/joint_states', qos_profile=qos.qos_profile_sensor_data) # IMU (embedded BNO-055) - self.imu_pub_ = self.create_publisher(Imu, '/core/imu', 10) + self.imu_pub_ = self.create_publisher(Imu, '/core/imu', qos_profile=qos.qos_profile_sensor_data) self.imu_state = Imu() self.imu_state.header.frame_id = "core_bno055" # GPS (embedded u-blox M9N) - self.gps_pub_ = self.create_publisher(NavSatFix, '/gps/fix', 10) + self.gps_pub_ = self.create_publisher(NavSatFix, '/gps/fix', qos_profile=qos.qos_profile_sensor_data) self.gps_state = NavSatFix() self.gps_state.header.frame_id = "core_gps_antenna" self.gps_state.status.service = NavSatStatus.SERVICE_GPS self.gps_state.status.status = NavSatStatus.STATUS_NO_FIX self.gps_state.position_covariance_type = NavSatFix.COVARIANCE_TYPE_UNKNOWN # Barometer (embedded BMP-388) - self.baro_pub_ = self.create_publisher(Barometer, '/core/baro', 10) + self.baro_pub_ = self.create_publisher(Barometer, '/core/baro', qos_profile=qos.qos_profile_sensor_data) self.baro_state = Barometer() self.baro_state.header.frame_id = "core_bmp388" @@ -355,102 +371,117 @@ class SerialRelay(Node): def relay_fromvic(self, msg: VicCAN): # Assume that the message is coming from Core # skill diff if not - - # TODO: add len(msg.data) checks to each feedback message - # GNSS - if msg.command_id == 48: # GNSS Latitude - self.gps_state.latitude = float(msg.data[0]) - elif msg.command_id == 49: # GNSS Longitude - self.gps_state.longitude = float(msg.data[0]) - elif msg.command_id == 50: # GNSS Satellite count and altitude - self.gps_state.status.status = NavSatStatus.STATUS_FIX if int(msg.data[0]) >= 3 else NavSatStatus.STATUS_NO_FIX - self.gps_state.altitude = float(msg.data[1]) - self.gps_state.header.stamp = msg.header.stamp - self.gps_pub_.publish(self.gps_state) - # IMU - elif msg.command_id == 51: # Gyro x, y, z, and imu calibration - self.feedback_new_state.imu_calib = round(float(msg.data[3])) - self.imu_state.angular_velocity.x = float(msg.data[0]) - self.imu_state.angular_velocity.y = float(msg.data[1]) - self.imu_state.angular_velocity.z = float(msg.data[2]) - self.imu_state.header.stamp = msg.header.stamp - elif msg.command_id == 52: # Accel x, y, z, heading - self.imu_state.linear_acceleration.x = float(msg.data[0]) - self.imu_state.linear_acceleration.y = float(msg.data[1]) - self.imu_state.linear_acceleration.z = float(msg.data[2]) - # Deal with quaternion - r = Rotation.from_euler('z', float(msg.data[3]), degrees=True) - q = r.as_quat() - self.imu_state.orientation.x = q[0] - self.imu_state.orientation.y = q[1] - self.imu_state.orientation.z = q[2] - self.imu_state.orientation.w = q[3] - self.imu_state.header.stamp = msg.header.stamp - self.imu_pub_.publish(self.imu_state) - # REV Motors - elif msg.command_id == 53: # REV SPARK MAX feedback - motorId = round(float(msg.data[0])) - temp = float(msg.data[1]) / 10.0 - voltage = float(msg.data[2]) / 10.0 - current = float(msg.data[3]) / 10.0 - if motorId == 1: - self.feedback_new_state.fl_motor.temperature = temp - self.feedback_new_state.fl_motor.voltage = voltage - self.feedback_new_state.fl_motor.current = current - self.feedback_new_state.fl_motor.header.stamp = msg.header.stamp - elif motorId == 2: - self.feedback_new_state.bl_motor.temperature = temp - self.feedback_new_state.bl_motor.voltage = voltage - self.feedback_new_state.bl_motor.current = current - self.feedback_new_state.bl_motor.header.stamp = msg.header.stamp - elif motorId == 3: - self.feedback_new_state.fr_motor.temperature = temp - self.feedback_new_state.fr_motor.voltage = voltage - self.feedback_new_state.fr_motor.current = current - self.feedback_new_state.fr_motor.header.stamp = msg.header.stamp - elif motorId == 4: - self.feedback_new_state.br_motor.temperature = temp - self.feedback_new_state.br_motor.voltage = voltage - self.feedback_new_state.br_motor.current = current - self.feedback_new_state.br_motor.header.stamp = msg.header.stamp - self.feedback_new_pub_.publish(self.feedback_new_state) - # Board voltage - elif msg.command_id == 54: # Voltages batt, 12, 5, 3, all * 100 - self.feedback_new_state.board_voltage.vbatt = float(msg.data[0]) / 100.0 - self.feedback_new_state.board_voltage.v12 = float(msg.data[1]) / 100.0 - self.feedback_new_state.board_voltage.v5 = float(msg.data[2]) / 100.0 - self.feedback_new_state.board_voltage.v3 = float(msg.data[3]) / 100.0 - # Baro - elif msg.command_id == 56: # BMP temperature, altitude, pressure - self.baro_state.temperature = float(msg.data[0]) - self.baro_state.altitude = float(msg.data[1]) - self.baro_state.pressure = float(msg.data[2]) - self.baro_state.header.stamp = msg.header.stamp - self.baro_pub_.publish(self.baro_state) - # REV Motors (pos and vel) - elif msg.command_id == 58: # REV position and velocity - motorId = round(float(msg.data[0])) - position = float(msg.data[1]) - velocity = float(msg.data[2]) - if motorId == 1: - self.feedback_new_state.fl_motor.position = position - self.feedback_new_state.fl_motor.velocity = velocity - self.feedback_new_state.fl_motor.header.stamp = msg.header.stamp - elif motorId == 2: - self.feedback_new_state.bl_motor.position = position - self.feedback_new_state.bl_motor.velocity = velocity - self.feedback_new_state.bl_motor.header.stamp = msg.header.stamp - elif motorId == 3: - self.feedback_new_state.fr_motor.position = position - self.feedback_new_state.fr_motor.velocity = velocity - self.feedback_new_state.fr_motor.header.stamp = msg.header.stamp - elif motorId == 4: - self.feedback_new_state.br_motor.position = position - self.feedback_new_state.br_motor.velocity = velocity - self.feedback_new_state.br_motor.header.stamp = msg.header.stamp - else: - return + # Check message len to prevent crashing on bad data + if msg.command_id in viccan_msg_len_dict: + expected_len = viccan_msg_len_dict[msg.command_id] + if len(msg.data) != expected_len: + self.get_logger().warning(f"Ignoring VicCAN message with id {msg.command_id} due to unexpected data length (expected {expected_len}, got {len(msg.data)})") + return + + match msg.command_id: + # GNSS + case 48: # GNSS Latitude + self.gps_state.latitude = float(msg.data[0]) + case 49: # GNSS Longitude + self.gps_state.longitude = float(msg.data[0]) + case 50: # GNSS Satellite count and altitude + self.gps_state.status.status = NavSatStatus.STATUS_FIX if int(msg.data[0]) >= 3 else NavSatStatus.STATUS_NO_FIX + self.gps_state.altitude = float(msg.data[1]) + self.gps_state.header.stamp = msg.header.stamp + self.gps_pub_.publish(self.gps_state) + # IMU + case 51: # Gyro x, y, z, and imu calibration + self.feedback_new_state.imu_calib = round(float(msg.data[3])) + self.imu_state.angular_velocity.x = float(msg.data[0]) + self.imu_state.angular_velocity.y = float(msg.data[1]) + self.imu_state.angular_velocity.z = float(msg.data[2]) + self.imu_state.header.stamp = msg.header.stamp + case 52: # Accel x, y, z, heading + self.imu_state.linear_acceleration.x = float(msg.data[0]) + self.imu_state.linear_acceleration.y = float(msg.data[1]) + self.imu_state.linear_acceleration.z = float(msg.data[2]) + # Deal with quaternion + r = Rotation.from_euler('z', float(msg.data[3]), degrees=True) + q = r.as_quat() + self.imu_state.orientation.x = q[0] + self.imu_state.orientation.y = q[1] + self.imu_state.orientation.z = q[2] + self.imu_state.orientation.w = q[3] + self.imu_state.header.stamp = msg.header.stamp + self.imu_pub_.publish(self.imu_state) + # REV Motors + case 53: # REV SPARK MAX feedback + motorId = round(float(msg.data[0])) + temp = float(msg.data[1]) / 10.0 + voltage = float(msg.data[2]) / 10.0 + current = float(msg.data[3]) / 10.0 + motor: RevMotorState | None = None + match motorId: + case 1: + motor = self.feedback_new_state.fl_motor + case 2: + motor = self.feedback_new_state.bl_motor + case 3: + motor = self.feedback_new_state.fr_motor + case 4: + motor = self.feedback_new_state.br_motor + case _: + self.get_logger().warning(f"Ignoring REV motor feedback 53 with invalid motorId {motorId}") + return + + if motor: + motor.temperature = temp + motor.voltage = voltage + motor.current = current + motor.header.stamp = msg.header.stamp + + self.feedback_new_pub_.publish(self.feedback_new_state) + # Board voltage + case 54: # Voltages batt, 12, 5, 3, all * 100 + self.feedback_new_state.board_voltage.vbatt = float(msg.data[0]) / 100.0 + self.feedback_new_state.board_voltage.v12 = float(msg.data[1]) / 100.0 + self.feedback_new_state.board_voltage.v5 = float(msg.data[2]) / 100.0 + self.feedback_new_state.board_voltage.v3 = float(msg.data[3]) / 100.0 + # Baro + case 56: # BMP temperature, altitude, pressure + self.baro_state.temperature = float(msg.data[0]) + self.baro_state.altitude = float(msg.data[1]) + self.baro_state.pressure = float(msg.data[2]) + self.baro_state.header.stamp = msg.header.stamp + self.baro_pub_.publish(self.baro_state) + # REV Motors (pos and vel) + case 58: # REV position and velocity + motorId = round(float(msg.data[0])) + position = float(msg.data[1]) + velocity = float(msg.data[2]) + joint_state_msg = JointState() # TODO: not sure if all motors should be in each message or not + joint_state_msg.position = [position * (2 * pi) / CORE_GEAR_RATIO] # revolutions to radians + joint_state_msg.velocity = [velocity * (2 * pi / 60.0) / CORE_GEAR_RATIO] # RPM to rad/s + + motor: RevMotorState | None = None + + match motorId: + case 1: + motor = self.feedback_new_state.fl_motor + joint_state_msg.name = ["fl_motor_joint"] + case 2: + motor = self.feedback_new_state.bl_motor + joint_state_msg.name = ["bl_motor_joint"] + case 3: + motor = self.feedback_new_state.fr_motor + joint_state_msg.name = ["fr_motor_joint"] + case 4: + motor = self.feedback_new_state.br_motor + joint_state_msg.name = ["br_motor_joint"] + case _: + self.get_logger().warning(f"Ignoring REV motor feedback 58 with invalid motorId {motorId}") + return + + joint_state_msg.header.stamp = msg.header.stamp + self.joint_state_pub_.publish(joint_state_msg) + case _: + return def publish_feedback(self): diff --git a/src/core_pkg/package.xml b/src/core_pkg/package.xml index f97b13e..667ee58 100644 --- a/src/core_pkg/package.xml +++ b/src/core_pkg/package.xml @@ -8,6 +8,9 @@ AGPL-3.0-only rclpy + common_interfaces + python3-scipy + python-crccheck-pip ros2_interfaces_pkg ament_copyright diff --git a/src/core_rover_description/config/joint_names_core_rover_description.yaml b/src/core_rover_description/config/joint_names_core_rover_description.yaml deleted file mode 100644 index a23613a..0000000 --- a/src/core_rover_description/config/joint_names_core_rover_description.yaml +++ /dev/null @@ -1 +0,0 @@ -controller_joint_names: ['', 'right_suspension_joint', 'br_wheel_axis', 'fr_wheel_joint', 'averaging_bar_axis', 'left_suspension_joint', 'bl_wheel_joint', 'fl_wheel_joint', ] diff --git a/src/core_rover_description/config/rviz_basic_settings.rviz b/src/core_rover_description/config/rviz_basic_settings.rviz deleted file mode 100644 index 0ca5048..0000000 --- a/src/core_rover_description/config/rviz_basic_settings.rviz +++ /dev/null @@ -1,229 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 - - /RobotModel1 - - /TF1 - - /TF1/Frames1 - Splitter Ratio: 0.5 - Tree Height: 617 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 1 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base_footprint: - Alpha: 1 - Show Axes: false - Show Trail: false - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - drivewhl_l_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - drivewhl_r_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - front_caster: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - gps_link: - Alpha: 1 - Show Axes: false - Show Trail: false - imu_link: - Alpha: 1 - Show Axes: false - Show Trail: false - lidar_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Name: RobotModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz_default_plugins/TF - Enabled: true - Frame Timeout: 15 - Frames: - All Enabled: false - base_footprint: - Value: false - base_link: - Value: false - drivewhl_l_link: - Value: true - drivewhl_r_link: - Value: true - front_caster: - Value: false - gps_link: - Value: false - imu_link: - Value: false - lidar_link: - Value: false - Marker Scale: 1 - Name: TF - Show Arrows: false - Show Axes: true - Show Names: true - Tree: - base_footprint: - base_link: - drivewhl_l_link: - {} - drivewhl_r_link: - {} - front_caster: - {} - gps_link: - {} - imu_link: - {} - lidar_link: - {} - Update Interval: 0 - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: base_link - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /goal_pose - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 4.434264183044434 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.31193429231643677 - Y: 0.11948385089635849 - Z: -0.4807402193546295 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.490397572517395 - Target Frame: - Value: Orbit (rviz) - Yaw: 1.0503965616226196 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 846 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd000000040000000000000156000002f4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002f4000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002f4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002f4000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d006501000000000000045000000000000000000000023f000002f400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1200 - X: 246 - Y: 77 diff --git a/src/core_rover_description/export.log b/src/core_rover_description/export.log deleted file mode 100644 index 8dd27a9..0000000 --- a/src/core_rover_description/export.log +++ /dev/null @@ -1,4674 +0,0 @@ -2025-09-29 22:31:35,300 INFO Logger.cs: 70 - --------------------------------------------------------------------------------- -2025-09-29 22:31:35,321 INFO Logger.cs: 71 - Logging commencing for SW2URDF exporter -2025-09-29 22:31:35,321 INFO Logger.cs: 73 - Commit version -2025-09-29 22:31:35,321 INFO Logger.cs: 74 - Build version 1.6.9403.28032 -2025-09-29 22:31:35,321 INFO SwAddin.cs: 192 - Attempting to connect to SW -2025-09-29 22:31:35,321 INFO SwAddin.cs: 197 - Setting up callbacks -2025-09-29 22:31:35,321 INFO SwAddin.cs: 201 - Setting up command manager -2025-09-29 22:31:35,321 INFO SwAddin.cs: 204 - Adding command manager -2025-09-29 22:31:35,321 INFO SwAddin.cs: 263 - Adding Assembly export to file menu -2025-09-29 22:31:35,321 INFO SwAddin.cs: 272 - Adding Part export to file menu -2025-09-29 22:31:35,321 INFO SwAddin.cs: 210 - Adding event handlers -2025-09-29 22:31:35,431 INFO SwAddin.cs: 217 - Connecting plugin to SolidWorks -2025-09-29 22:32:16,313 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:18,856 INFO SwAddin.cs: 313 - Saving assembly -2025-09-29 22:32:23,662 INFO SwAddin.cs: 316 - Opening property manager -2025-09-29 22:32:23,678 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:23,694 INFO ExportHelperExtension.cs: 1136 - Found 115 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:23,694 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:23,694 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 22:32:23,710 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 22:32:23,710 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:32:23,710 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:32:23,710 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:32:23,710 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:23,712 INFO ExportHelperExtension.cs: 1136 - Found 115 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:23,712 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:23,712 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 22:32:23,712 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 22:32:23,712 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:32:23,712 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:32:23,712 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:32:24,103 INFO SwAddin.cs: 339 - Loading config tree -2025-09-29 22:32:24,119 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically Generatelinktruenametrueleft_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisAutomatically Generatelinktruenametruebl_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseright_suspension_axisAutomatically Generatelinktruenametruebr_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseaveraging_bar_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node base_link -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-29 22:32:24,229 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-29 22:32:24,229 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-29 22:32:24,244 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-29 22:32:24,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 22:32:24,308 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 22:32:24,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 230 - Loaded 46 components for link base_link -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 22:32:24,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 230 - Loaded 21 components for link left_suspension_member -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 22:32:24,340 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 22:32:24,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 230 - Loaded 21 components for link right_suspension_member -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 22:32:24,387 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,387 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 22:32:24,387 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 22:32:24,387 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 22:32:24,387 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-29 22:32:25,459 INFO SwAddin.cs: 344 - Showing property manager -2025-09-29 22:32:36,517 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-29 22:32:36,532 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically Generatelinktruenametrueleft_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisAutomatically Generatelinktruenametruebl_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseright_suspension_axisAutomatically Generatelinktruenametruebr_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseaveraging_bar_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 22:32:36,957 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-29 22:33:06,680 INFO ExportHelperExtension.cs: 347 - Creating joint left_suspension_member -2025-09-29 22:33:06,695 INFO ExportHelperExtension.cs: 1405 - Fixing components for base_link -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-29 22:33:06,700 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:06,710 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-29 22:33:06,710 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-29 22:33:06,710 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-29 22:33:06,711 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:06,711 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-29 22:33:06,711 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-29 22:33:06,711 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:06,714 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-29 22:33:06,714 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-29 22:33:06,714 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-29 22:33:06,715 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-29 22:33:06,715 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-29 22:33:06,716 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-29 22:33:06,716 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-29 22:33:06,716 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-29 22:33:06,716 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:06,719 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-29 22:33:06,719 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-29 22:33:06,719 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-29 22:33:06,719 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-29 22:33:06,719 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-29 22:33:06,719 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-29 22:33:06,723 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-29 22:33:06,723 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-29 22:33:06,723 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-29 22:33:06,723 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-29 22:33:06,726 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-29 22:33:06,726 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-29 22:33:06,726 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-29 22:33:06,727 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-29 22:33:10,098 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-29 22:33:10,098 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-29 22:33:10,098 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-29 22:33:10,098 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-29 22:33:10,270 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:10,270 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-29 22:33:10,270 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-29 22:33:10,270 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-29 22:33:10,270 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-29 22:33:10,270 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-29 22:33:10,286 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-29 22:33:10,301 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-29 22:33:10,317 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-29 22:33:16,495 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child left_suspension_member failed -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 347 - Creating joint bl_wheel -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1405 - Fixing components for left_suspension_member -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 46 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 29 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 41 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 106 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 51 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 464 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 463 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 465 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-29 22:33:18,475 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-29 22:33:18,491 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-29 22:33:21,731 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-29 22:33:21,731 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-29 22:33:21,731 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-29 22:33:21,731 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 46 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 29 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 41 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 106 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 51 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 464 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 463 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 465 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:21,734 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:21,747 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-29 22:33:21,763 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-29 22:33:28,895 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child bl_wheel failed -2025-09-29 22:33:30,651 INFO ExportHelperExtension.cs: 347 - Creating joint fl_wheel -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1405 - Fixing components for left_suspension_member -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 46 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 29 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 41 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 106 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 51 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 464 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 463 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 465 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-29 22:33:30,654 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-29 22:33:30,670 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-29 22:33:30,670 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-29 22:33:30,670 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-29 22:33:30,670 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-29 22:33:30,670 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-29 22:33:30,670 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-29 22:33:30,670 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 1360 - Unfixing component 46 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 1360 - Unfixing component 29 -2025-09-29 22:33:33,944 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:33,956 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:33,959 INFO ExportHelperExtension.cs: 1360 - Unfixing component 41 -2025-09-29 22:33:33,959 INFO ExportHelperExtension.cs: 1360 - Unfixing component 106 -2025-09-29 22:33:33,959 INFO ExportHelperExtension.cs: 1360 - Unfixing component 51 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 464 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 463 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 465 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-29 22:33:33,961 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-29 22:33:33,975 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-29 22:33:40,866 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child fl_wheel failed -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 347 - Creating joint right_suspension_member -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1405 - Fixing components for base_link -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:42,867 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-29 22:33:42,875 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-29 22:33:45,678 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-29 22:33:45,693 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-29 22:33:45,693 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-29 22:33:45,693 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-29 22:33:45,693 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-29 22:33:45,694 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-29 22:33:52,619 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child right_suspension_member failed -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 347 - Creating joint br_wheel -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1405 - Fixing components for right_suspension_member -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 46 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 41 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 51 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 29 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 202 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 433 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 437 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 429 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-29 22:33:54,448 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-29 22:33:54,464 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-29 22:33:54,464 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-29 22:33:54,464 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-29 22:33:54,464 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-29 22:33:54,464 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 46 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 41 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 51 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 29 -2025-09-29 22:33:58,066 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 202 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 433 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 437 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 429 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-29 22:33:58,081 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-29 22:33:58,095 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-29 22:33:58,095 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-29 22:33:58,095 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-29 22:34:05,451 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child br_wheel failed -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 347 - Creating joint fr_wheel -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1405 - Fixing components for right_suspension_member -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 46 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 41 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 51 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 29 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 50 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 30 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 28 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 202 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 433 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 437 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 429 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,467 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-29 22:34:07,483 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-29 22:34:11,095 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-29 22:34:11,095 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-29 22:34:11,095 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-29 22:34:11,095 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-29 22:34:11,095 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,095 INFO ExportHelperExtension.cs: 1360 - Unfixing component 46 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 41 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 51 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 29 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 50 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 30 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 28 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 202 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 433 -2025-09-29 22:34:11,111 INFO ExportHelperExtension.cs: 1360 - Unfixing component 437 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 429 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-29 22:34:11,119 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-29 22:34:11,127 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-29 22:34:18,898 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child fr_wheel failed -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 347 - Creating joint averaging_bar -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1405 - Fixing components for base_link -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:20,662 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-29 22:34:20,678 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-29 22:34:23,459 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-29 22:34:23,459 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-29 22:34:23,475 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-29 22:34:23,490 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-29 22:34:30,354 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child averaging_bar failed -2025-09-29 22:34:30,920 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 22:34:30,936 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 22:34:30,952 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 22:34:30,952 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 22:34:30,952 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 22:34:30,953 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 22:34:30,953 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 22:34:30,953 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 22:34:30,953 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 22:34:31,079 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 22:34:31,082 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 22:34:31,083 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 22:34:31,085 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 22:34:31,086 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 22:34:31,087 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 22:34:31,088 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 22:34:31,089 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 22:34:31,090 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 22:34:31,091 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 22:34:31,094 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 22:34:31,095 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 22:34:31,096 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 22:34:31,098 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 22:34:31,098 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 22:34:31,099 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 22:34:31,100 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 22:34:31,101 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 22:34:31,101 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 22:34:31,102 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 22:34:31,102 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:34:31,103 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:34:31,104 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:34:31,105 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 22:34:31,105 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 22:34:31,107 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 22:34:31,107 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 22:34:31,108 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 22:34:31,108 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 22:34:31,109 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 22:34:31,109 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 22:34:31,110 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 22:34:31,111 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:34:31,112 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:34:31,113 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 22:34:31,113 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 22:34:31,114 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 22:34:31,114 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 22:34:31,114 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 22:34:31,115 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 22:34:31,115 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 22:34:31,116 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 22:34:31,118 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 22:34:31,118 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 22:34:31,119 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 22:34:31,119 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 22:34:31,121 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 22:34:31,121 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 22:34:31,123 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 22:34:31,123 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 22:34:31,123 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 22:34:31,124 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 22:34:31,124 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 22:34:31,125 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 22:34:31,125 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 22:34:31,126 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 22:34:31,126 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 22:34:31,127 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 22:34:31,127 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 22:34:31,128 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 22:34:31,128 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 22:34:31,128 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 22:34:31,129 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 22:34:31,129 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 22:34:31,129 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 22:34:31,130 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 22:34:31,130 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 22:34:31,131 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 22:34:31,131 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 22:34:31,132 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 22:34:31,132 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 22:34:31,132 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 22:34:31,133 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 22:34:31,133 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 22:34:31,134 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 22:34:31,134 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 22:34:31,135 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:34:31,135 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:34:31,136 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 22:34:31,136 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 22:34:31,136 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 22:34:31,137 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 22:34:31,137 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 22:34:31,138 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 22:34:31,138 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 22:34:31,138 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 22:34:31,139 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 22:34:31,139 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 22:39:07,065 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2025-09-29 22:39:07,080 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseAutomatically Generatelinktruenametrueleft_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowertrueuppertrueefforttruevelocitytruelimittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisAutomatically Generatelinktruenametruebl_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseright_suspension_axisAutomatically Generatelinktruenametruebr_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseaveraging_bar_axisAutomatically GeneratelinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==UEYAAAUAAAD//v//1gFFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE4AVQBDADEAMwBBAE4ASABfAE4AVQBDADEAMwBMAEMASAAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ALwBOAFUAQwAxADMAQQBOAEgAXwBOAFUAQwAxADMATABDAEgALgBTAFQAUAAtADEAQABOAFUAQwAxADMAQQBOAEgAXwBOAFUAQwAxADMATABDAEgALwAwADAAXwBXAFMAXwBBAEwATABfAEEAUwBNAF8AQwBIAEUAQwBLAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAxAC4AUwBUAFAALQAxAEAATgBVAEMAMQAzAEEATgBIAF8ATgBVAEMAMQAzAEwAQwBIAC4AUwBUAFAALwBXAFMAXwBNAEUAXwBQAEwAQQBDAEUATQBFAE4AVABfAEEAUwBNAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAyAC4AUwBUAFAALQAxAEAAMAAwAF8AVwBTAF8AQQBMAEwAXwBBAFMATQBfAEMASABFAEMASwBfAEEAUwBNAF8AMQBfAEEAUwBNAF8AMQAuAFMAVABQAC8AVwBTAF8ATQBFAF8AVABBAEwATABfAEEAUwBTAFkAXwBBAFMATQBfADEAXwBBAFMATQBfADEALgBTAFQAUAAtADEAQABXAFMAXwBNAEUAXwBQAEwAQQBDAEUATQBFAE4AVABfAEEAUwBNAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAyAC4AUwBUAFAALwBXAFMAXwBUAE8AUABfAEMATwBWAEUAUgBfAEEAUwBNAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAxAC4AUwBUAFAALQAxAEAAVwBTAF8ATQBFAF8AVABBAEwATABfAEEAUwBTAFkAXwBBAFMATQBfADEAXwBBAFMATQBfADEALgBTAFQAUAAvAEEATgBfAFQATwBQAF8AQwBPAFYARQBSAF8AMQBfADIALgBTAFQAUAAtADEAQABXAFMAXwBUAE8AUABfAEMATwBWAEUAUgBfAEEAUwBNAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAxAC4AUwBUAFAABAAAABAAAAABAAAACAAAAFAAAABYBAAAGAAAABgAAAAYAAAAGAAAABgAAAAYAAAAUEYAAAUAAAD//v//6QFFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE4AVQBDADEAMwBBAE4ASABfAE4AVQBDADEAMwBMAEMASAAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ALwBOAFUAQwAxADMAQQBOAEgAXwBOAFUAQwAxADMATABDAEgALgBTAFQAUAAtADEAQABOAFUAQwAxADMAQQBOAEgAXwBOAFUAQwAxADMATABDAEgALwAwADAAXwBXAFMAXwBBAEwATABfAEEAUwBNAF8AQwBIAEUAQwBLAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAxAC4AUwBUAFAALQAxAEAATgBVAEMAMQAzAEEATgBIAF8ATgBVAEMAMQAzAEwAQwBIAC4AUwBUAFAALwBXAFMAXwBNAEUAXwBQAEwAQQBDAEUATQBFAE4AVABfAEEAUwBNAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAyAC4AUwBUAFAALQAxAEAAMAAwAF8AVwBTAF8AQQBMAEwAXwBBAFMATQBfAEMASABFAEMASwBfAEEAUwBNAF8AMQBfAEEAUwBNAF8AMQAuAFMAVABQAC8AVwBTAF8ATQBFAF8AVABBAEwATABfAEEAUwBTAFkAXwBBAFMATQBfADEAXwBBAFMATQBfADEALgBTAFQAUAAtADEAQABXAFMAXwBNAEUAXwBQAEwAQQBDAEUATQBFAE4AVABfAEEAUwBNAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAyAC4AUwBUAFAALwBXAFMAXwBUAEEATABMAF8ATQBJAEQAXwBGAFIAQQBNAEUAXwBBAFMATQBfAEEAUwBNAF8AMQBfAEEAUwBNAF8AMQAuAFMAVABQAC0AMQBAAFcAUwBfAE0ARQBfAFQAQQBMAEwAXwBBAFMAUwBZAF8AQQBTAE0AXwAxAF8AQQBTAE0AXwAxAC4AUwBUAFAALwBXAFMAXwBUAEEATABMAF8ATQBJAEQAXwBGAFIAQQBNAEUAXwBOAEUAVwBfADEAXwAxAC4AUwBUAFAALQAxAEAAVwBTAF8AVABBAEwATABfAE0ASQBEAF8ARgBSAEEATQBFAF8AQQBTAE0AXwBBAFMATQBfADEAXwBBAFMATQBfADEALgBTAFQAUAAEAAAAEAAAAAEAAAAIAAAAUAAAAFgEAAAYAAAAGAAAABgAAAAYAAAAGgAAABoAAAA=UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 22:39:31,509 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\David\Desktop\URDF\core_rover_description -2025-09-29 22:39:31,525 INFO ExportHelper.cs: 148 - Beginning the export process -2025-09-29 22:39:31,525 INFO ExportHelper.cs: 154 - Creating package directories with name core_rover_description and save path C:\Users\David\Desktop\URDF -2025-09-29 22:39:33,245 INFO ExportHelper.cs: 163 - Creating CMakeLists.txt at C:\Users\David\Desktop\URDF\core_rover_description\CMakeLists.txt -2025-09-29 22:39:33,261 INFO ExportHelper.cs: 167 - Creating joint names config at C:\Users\David\Desktop\URDF\core_rover_description\config\joint_names_core_rover_description.yaml -2025-09-29 22:39:33,261 INFO ExportHelper.cs: 171 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 22:39:33,261 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 22:39:33,272 INFO ExportHelper.cs: 178 - Creating RVIZ launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 22:39:33,277 INFO ExportHelper.cs: 183 - Creating Gazebo launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 22:39:33,277 INFO ExportHelper.cs: 188 - Saving existing STL preferences -2025-09-29 22:39:33,277 INFO ExportHelper.cs: 568 - Saving users preferences -2025-09-29 22:39:33,293 INFO ExportHelper.cs: 191 - Modifying STL preferences -2025-09-29 22:39:33,293 INFO ExportHelper.cs: 582 - Setting STL preferences -2025-09-29 22:39:33,324 INFO ExportHelper.cs: 197 - Found 5 hidden components Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-2, Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-1, Shell & Averaging System-1/Arm Bracket Bonding Jig-1, Shell & Averaging System-1/Bordered Lid V1 Multibody-1, Shell & Averaging System-1/Front Camera Cluster V2-1 -2025-09-29 22:39:33,324 INFO ExportHelper.cs: 198 - Hiding all components -2025-09-29 22:39:34,111 INFO ExportHelper.cs: 205 - Beginning individual files export -2025-09-29 22:39:34,117 INFO ExportHelper.cs: 271 - Exporting link: base_link -2025-09-29 22:39:34,117 INFO ExportHelper.cs: 273 - Link base_link has 3 children -2025-09-29 22:39:34,117 INFO ExportHelper.cs: 271 - Exporting link: left_suspension_member -2025-09-29 22:39:34,117 INFO ExportHelper.cs: 273 - Link left_suspension_member has 2 children -2025-09-29 22:39:34,117 INFO ExportHelper.cs: 271 - Exporting link: bl_wheel -2025-09-29 22:39:34,117 INFO ExportHelper.cs: 273 - Link bl_wheel has 0 children -2025-09-29 22:39:34,117 INFO ExportHelper.cs: 271 - Exporting link: fl_wheel -2025-09-29 22:39:34,125 INFO ExportHelper.cs: 273 - Link fl_wheel has 0 children -2025-09-29 22:39:34,127 INFO ExportHelper.cs: 271 - Exporting link: right_suspension_member -2025-09-29 22:39:34,127 INFO ExportHelper.cs: 273 - Link right_suspension_member has 2 children -2025-09-29 22:39:34,127 INFO ExportHelper.cs: 271 - Exporting link: br_wheel -2025-09-29 22:39:34,130 INFO ExportHelper.cs: 273 - Link br_wheel has 0 children -2025-09-29 22:39:34,130 INFO ExportHelper.cs: 271 - Exporting link: fr_wheel -2025-09-29 22:39:34,130 INFO ExportHelper.cs: 273 - Link fr_wheel has 0 children -2025-09-29 22:39:34,130 INFO ExportHelper.cs: 271 - Exporting link: averaging_bar -2025-09-29 22:39:34,130 INFO ExportHelper.cs: 273 - Link averaging_bar has 0 children -2025-09-29 22:39:34,130 INFO ExportHelper.cs: 146 - Showing all components except previously hidden components -2025-09-29 22:39:46,018 INFO ExportHelper.cs: 146 - Resetting STL preferences -2025-09-29 22:39:46,018 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-29 22:39:46,018 INFO ExportHelper.cs: 229 - Writing URDF file to C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.urdf -2025-09-29 22:39:46,490 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.csv -2025-09-29 22:39:46,521 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 22:39:46,521 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 22:39:46,521 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 22:39:46,537 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 22:39:46,537 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 22:39:46,537 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 22:39:46,537 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 22:39:46,537 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 22:39:46,537 INFO ExportHelper.cs: 235 - Copying log file -2025-09-29 22:39:46,552 INFO ExportHelper.cs: 557 - Copying C:\Users\David\sw2urdf_logs\sw2urdf.log to C:\Users\David\Desktop\URDF\core_rover_description\export.log -2025-09-29 22:39:46,552 INFO ExportHelper.cs: 238 - Resetting STL preferences -2025-09-29 22:39:46,552 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-29 23:06:05,485 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:05,485 INFO SwAddin.cs: 299 - Save is required -2025-09-29 23:06:05,485 INFO SwAddin.cs: 313 - Saving assembly -2025-09-29 23:06:10,780 INFO SwAddin.cs: 316 - Opening property manager -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:10,780 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 23:06:10,812 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:06:10,817 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 23:06:10,818 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:10,827 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:10,827 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:10,827 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:10,831 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 23:06:10,844 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:10,859 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:10,875 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:10,891 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:10,891 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:10,892 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:10,892 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:10,893 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 23:06:10,893 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:06:10,893 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 23:06:10,894 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 23:06:10,894 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:06:10,895 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 23:06:10,895 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:10,896 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:10,896 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:10,896 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:10,897 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:10,897 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:10,897 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:10,899 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:10,899 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:10,899 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:10,900 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:10,900 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:11,206 INFO SwAddin.cs: 339 - Loading config tree -2025-09-29 23:06:11,210 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242E-06-0.085911-0.11037rpytrue000originfalsefalsevaluetrue74.656massfalseixxtrue2.4002ixytrue-0.0015612ixztrue-0.00011619iyytrue4.2593iyztrue-0.0055914izztrue2.0454inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueleft_suspension_memberxyztrue0.29543019562219275-0.0753112643908363520.0067381927724715074rpytrue000originfalsefalsevaluetrue2.0928776612713675massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819065E-06ixztrue1.7290024726443145E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175067izztrue0.0058480861833012116inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098343-1.0982782239210565E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274105961massfalseixxtrue0.11546820921307198ixytrue7.2058577319844332E-10ixztrue-2.9085928392065569E-10iyytrue0.064706824633587581iyztrue7.1666914106655565E-07izztrue0.0632464587148044inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.7148-0.141390.13569rpytrue1.5769-1.57080originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792120195484E-086.1293307096477179E-09rpytrue000originfalsefalsevaluetrue5.7417579277055086massfalseixxtrue0.1154682092168773ixytrue7.205419893601865E-10ixztrue-2.908748320927302E-10iyytrue0.064706824634663429iyztrue7.1667036967253128E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12196-0.141390.13569rpytrue0.52965-1.57080originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue0.0067381927288255872-0.0752614805139321660.29547074729615252rpytrue000originfalsefalsevaluetrue2.0928776569814489massfalseixxtrue0.0058480861827915256ixytrue0.00021186508756189029ixztrue1.5821055457990269E-08iyytrue0.0098606806671202082iyztrue1.5821618143704969E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956922-1.098010873890054E-086.1284548547035911E-09rpytrue000originfalsefalsevaluetrue5.7417579275605517massfalseixxtrue0.11546820921502621ixytrue7.1976728192132246E-10ixztrue-2.9060332486909116E-10iyytrue0.064706824634147481iyztrue7.1666974422492091E-07izztrue0.063246458716925746inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13569-0.141390.7148rpytrue0.5296500originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076182-1.0982230680411931E-086.1291302033694706E-09rpytrue000originfalsefalsevaluetrue5.7417579276729249massfalseixxtrue0.11546820921644371ixytrue7.20424954886949E-10ixztrue-2.9080038289524082E-10iyytrue0.0647068246345492iyztrue7.1667020113848063E-07izztrue0.0632464587184831inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13569-0.14139-0.12196rpytrue1.576900originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.1712221738877892E-100.010334551290519556.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.8722305168418637massfalseixxtrue0.00010223447866828818ixytrue1.2617305962613194E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546767787E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 23:06:11,217 INFO LinkNode.cs: 35 - Building node base_link -2025-09-29 23:06:11,218 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-29 23:06:11,219 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-29 23:06:11,219 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-29 23:06:11,220 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-29 23:06:11,221 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-29 23:06:11,222 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-29 23:06:11,222 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-29 23:06:11,222 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,223 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-29 23:06:11,224 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-29 23:06:11,224 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:06:11,225 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:06:11,225 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:06:11,226 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:06:11,226 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:06:11,227 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-29 23:06:11,227 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-29 23:06:11,227 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-29 23:06:11,228 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-29 23:06:11,229 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-29 23:06:11,229 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-29 23:06:11,230 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-29 23:06:11,231 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-29 23:06:11,231 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-29 23:06:11,232 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-29 23:06:11,232 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-29 23:06:11,232 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-29 23:06:11,233 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-29 23:06:11,233 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-29 23:06:11,234 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-29 23:06:11,234 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-29 23:06:11,235 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-29 23:06:11,235 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-29 23:06:11,236 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-29 23:06:11,236 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:06:11,236 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:06:11,237 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:06:11,237 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:06:11,245 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:06:11,247 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-29 23:06:11,248 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:06:11,250 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-29 23:06:11,250 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-29 23:06:11,250 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-29 23:06:11,251 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-29 23:06:11,251 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-29 23:06:11,251 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-29 23:06:11,252 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-29 23:06:11,252 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:06:11,252 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:06:11,253 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-29 23:06:11,253 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:06:11,253 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-29 23:06:11,254 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-29 23:06:11,254 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-29 23:06:11,254 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-29 23:06:11,255 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,255 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:06:11,255 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,256 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:06:11,256 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,256 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:06:11,257 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-29 23:06:11,257 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:06:11,257 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-29 23:06:11,258 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:06:11,258 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-29 23:06:11,258 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:06:11,259 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-29 23:06:11,259 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:06:11,259 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-29 23:06:11,260 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-29 23:06:11,260 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-29 23:06:11,260 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:06:11,260 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-29 23:06:11,261 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:06:11,261 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-29 23:06:11,261 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:06:11,262 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,262 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:06:11,262 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,263 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:06:11,263 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,264 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:06:11,264 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,264 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:06:11,265 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-29 23:06:11,265 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:06:11,265 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-29 23:06:11,266 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:06:11,266 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-29 23:06:11,266 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:06:11,267 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-29 23:06:11,267 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:06:11,267 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-29 23:06:11,267 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-29 23:06:11,268 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-29 23:06:11,268 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:06:11,268 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-29 23:06:11,269 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:06:11,269 INFO CommonSwOperations.cs: 230 - Loaded 46 components for link base_link -2025-09-29 23:06:11,269 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,269 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:06:11,270 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,270 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:06:11,270 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,271 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:06:11,271 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,271 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:06:11,271 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,272 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:06:11,272 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,272 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:06:11,273 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:06:11,273 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:06:11,273 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:06:11,274 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:06:11,274 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:06:11,274 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:06:11,274 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:06:11,275 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:06:11,275 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:06:11,275 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:06:11,276 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:06:11,276 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-29 23:06:11,276 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:06:11,277 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:06:11,277 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:06:11,277 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-29 23:06:11,278 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:06:11,278 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:06:11,278 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:06:11,278 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:06:11,279 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,279 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-29 23:06:11,280 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:06:11,280 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:06:11,280 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,280 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,281 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:06:11,281 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,281 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:06:11,282 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,282 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:06:11,282 INFO CommonSwOperations.cs: 230 - Loaded 21 components for link left_suspension_member -2025-09-29 23:06:11,283 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,283 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-29 23:06:11,283 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:06:11,283 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-29 23:06:11,284 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,284 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-29 23:06:11,284 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:06:11,285 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-29 23:06:11,285 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,285 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:06:11,286 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,286 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:06:11,286 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,286 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:06:11,287 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,287 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:06:11,287 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,288 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:06:11,288 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,288 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:06:11,289 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,289 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:06:11,289 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:06:11,289 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:06:11,290 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:06:11,290 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:06:11,290 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:06:11,291 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:06:11,291 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:06:11,291 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:06:11,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:06:11,292 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:06:11,292 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:06:11,293 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:06:11,293 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:06:11,293 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:06:11,293 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:06:11,294 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:06:11,294 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:06:11,294 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:06:11,295 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:06:11,295 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:06:11,296 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:06:11,296 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-29 23:06:11,297 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:06:11,297 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,297 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:06:11,298 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,298 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:06:11,300 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,300 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:06:11,301 INFO CommonSwOperations.cs: 230 - Loaded 21 components for link right_suspension_member -2025-09-29 23:06:11,301 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,301 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:06:11,302 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:06:11,302 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-29 23:06:11,302 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,303 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:06:11,303 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:06:11,303 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-29 23:06:11,304 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:11,304 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-29 23:06:11,304 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-29 23:06:11,304 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,305 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:06:11,305 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,320 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:06:11,321 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,321 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:06:11,322 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:06:11,322 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:06:11,323 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-29 23:06:12,678 INFO SwAddin.cs: 344 - Showing property manager -2025-09-29 23:06:20,648 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-29 23:06:20,656 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242E-06-0.085911-0.11037rpytrue000originfalsefalsevaluetrue74.656massfalseixxtrue2.4002ixytrue-0.0015612ixztrue-0.00011619iyytrue4.2593iyztrue-0.0055914izztrue2.0454inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueleft_suspension_memberxyztrue0.29543019562219275-0.0753112643908363520.0067381927724715074rpytrue000originfalsefalsevaluetrue2.0928776612713675massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819065E-06ixztrue1.7290024726443145E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175067izztrue0.0058480861833012116inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098343-1.0982782239210565E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274105961massfalseixxtrue0.11546820921307198ixytrue7.2058577319844332E-10ixztrue-2.9085928392065569E-10iyytrue0.064706824633587581iyztrue7.1666914106655565E-07izztrue0.0632464587148044inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.7148-0.141390.13569rpytrue1.5769-1.57080originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792120195484E-086.1293307096477179E-09rpytrue000originfalsefalsevaluetrue5.7417579277055086massfalseixxtrue0.1154682092168773ixytrue7.205419893601865E-10ixztrue-2.908748320927302E-10iyytrue0.064706824634663429iyztrue7.1667036967253128E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12196-0.141390.13569rpytrue0.52965-1.57080originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue0.0067381927288255872-0.0752614805139321660.29547074729615252rpytrue000originfalsefalsevaluetrue2.0928776569814489massfalseixxtrue0.0058480861827915256ixytrue0.00021186508756189029ixztrue1.5821055457990269E-08iyytrue0.0098606806671202082iyztrue1.5821618143704969E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956922-1.098010873890054E-086.1284548547035911E-09rpytrue000originfalsefalsevaluetrue5.7417579275605517massfalseixxtrue0.11546820921502621ixytrue7.1976728192132246E-10ixztrue-2.9060332486909116E-10iyytrue0.064706824634147481iyztrue7.1666974422492091E-07izztrue0.063246458716925746inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13569-0.141390.7148rpytrue0.5296500originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076182-1.0982230680411931E-086.1291302033694706E-09rpytrue000originfalsefalsevaluetrue5.7417579276729249massfalseixxtrue0.11546820921644371ixytrue7.20424954886949E-10ixztrue-2.9080038289524082E-10iyytrue0.0647068246345492iyztrue7.1667020113848063E-07izztrue0.0632464587184831inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13569-0.14139-0.12196rpytrue1.576900originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.1712221738877892E-100.010334551290519556.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.8722305168418637massfalseixxtrue0.00010223447866828818ixytrue1.2617305962613194E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546767787E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 23:06:25,179 INFO ExportHelperExtension.cs: 347 - Creating joint left_suspension_member -2025-09-29 23:06:25,463 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child left_suspension_member failed -2025-09-29 23:06:27,397 INFO ExportHelperExtension.cs: 347 - Creating joint bl_wheel -2025-09-29 23:06:27,618 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child bl_wheel failed -2025-09-29 23:06:29,454 INFO ExportHelperExtension.cs: 347 - Creating joint fl_wheel -2025-09-29 23:06:29,611 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child fl_wheel failed -2025-09-29 23:06:31,479 INFO ExportHelperExtension.cs: 347 - Creating joint right_suspension_member -2025-09-29 23:06:31,683 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child right_suspension_member failed -2025-09-29 23:06:33,675 INFO ExportHelperExtension.cs: 347 - Creating joint br_wheel -2025-09-29 23:06:33,834 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child br_wheel failed -2025-09-29 23:06:35,532 INFO ExportHelperExtension.cs: 347 - Creating joint fr_wheel -2025-09-29 23:06:35,678 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child fr_wheel failed -2025-09-29 23:06:37,086 INFO ExportHelperExtension.cs: 347 - Creating joint averaging_bar -2025-09-29 23:06:37,243 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child averaging_bar failed -2025-09-29 23:06:37,651 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:37,651 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:37,651 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:37,667 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 23:06:37,681 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:06:37,681 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 23:06:37,681 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 23:06:37,681 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:06:37,682 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:37,698 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:37,714 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:06:37,763 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-29 23:06:47,238 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2025-09-29 23:06:47,254 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242E-06-0.085911-0.11037rpytrue000originfalsefalsevaluetrue74.656massfalseixxtrue2.4002ixytrue-0.0015612ixztrue-0.00011619iyytrue4.2593iyztrue-0.0055914izztrue2.0454inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueleft_suspension_memberxyztrue0.29543019562219275-0.0753112643908363520.0067381927724715074rpytrue000originfalsefalsevaluetrue2.0928776612713675massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819065E-06ixztrue1.7290024726443145E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175067izztrue0.0058480861833012116inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098343-1.0982782239210565E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274105961massfalseixxtrue0.11546820921307198ixytrue7.2058577319844332E-10ixztrue-2.9085928392065569E-10iyytrue0.064706824633587581iyztrue7.1666914106655565E-07izztrue0.0632464587148044inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.7148-0.141390.13569rpytrue1.5769-1.57080originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792120195484E-086.1293307096477179E-09rpytrue000originfalsefalsevaluetrue5.7417579277055086massfalseixxtrue0.1154682092168773ixytrue7.205419893601865E-10ixztrue-2.908748320927302E-10iyytrue0.064706824634663429iyztrue7.1667036967253128E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12196-0.141390.13569rpytrue0.52965-1.57080originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue0.0067381927288255872-0.0752614805139321660.29547074729615252rpytrue000originfalsefalsevaluetrue2.0928776569814489massfalseixxtrue0.0058480861827915256ixytrue0.00021186508756189029ixztrue1.5821055457990269E-08iyytrue0.0098606806671202082iyztrue1.5821618143704969E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956922-1.098010873890054E-086.1284548547035911E-09rpytrue000originfalsefalsevaluetrue5.7417579275605517massfalseixxtrue0.11546820921502621ixytrue7.1976728192132246E-10ixztrue-2.9060332486909116E-10iyytrue0.064706824634147481iyztrue7.1666974422492091E-07izztrue0.063246458716925746inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13569-0.141390.7148rpytrue0.5296500originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076182-1.0982230680411931E-086.1291302033694706E-09rpytrue000originfalsefalsevaluetrue5.7417579276729249massfalseixxtrue0.11546820921644371ixytrue7.20424954886949E-10ixztrue-2.9080038289524082E-10iyytrue0.0647068246345492iyztrue7.1667020113848063E-07izztrue0.0632464587184831inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13569-0.14139-0.12196rpytrue1.576900originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.1712221738877892E-100.010334551290519556.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.8722305168418637massfalseixxtrue0.00010223447866828818ixytrue1.2617305962613194E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546767787E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue000axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 23:07:04,623 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2025-09-29 23:07:04,623 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242259423287625E-060.11037389216180901-0.0859105519232749rpytrue000originfalsefalsevaluetrue74.655780473161542massfalseixxtrue2.4001787633692504ixytrue0.00011618556838517536ixztrue-0.0015611886307071486iyytrue2.0453538462072869iyztrue0.0055914075297434883izztrue4.2593413623318055inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueleft_suspension_memberxyztrue0.29543019562220779-0.0753112643908512290.00673819277248161rpytrue000originfalsefalsevaluetrue2.092877661271368massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819353E-06ixztrue1.7290024726393557E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175073izztrue0.00584808618330121inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482195640000161-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896601.5707963267948966originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098232-1.0982782128188262E-086.1294024300551087E-09rpytrue000originfalsefalsevaluetrue5.7417579274105979massfalseixxtrue0.11546820921307206ixytrue7.2058576629712916E-10ixztrue-2.9085928016673176E-10iyytrue0.064706824633587623iyztrue7.166691410727627E-07izztrue0.063246458714804443inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811228-1.0982792120195484E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.741757927705506massfalseixxtrue0.11546820921687725ixytrue7.2054198879857512E-10ixztrue-2.9087482991579359E-10iyytrue0.064706824634663374iyztrue7.1667036967600073E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue0.0067381927281905951-0.075261480514894730.2954707472971152rpytrue000originfalsefalsevaluetrue2.0928776569814485massfalseixxtrue0.0058480861827915282ixytrue0.00021186508756189037ixztrue1.5821055457941621E-08iyytrue0.0098606806671202116iyztrue1.5821618143704884E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482195640000006-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896803.1415926535897931originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956811-1.0980108655633813E-086.1284549657258935E-09rpytrue000originfalsefalsevaluetrue5.7417579275605526massfalseixxtrue0.11546820921502553ixytrue7.1976727943417927E-10ixztrue-2.9060339735168936E-10iyytrue0.064706824634146828iyztrue7.166697443567599E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291298703025632E-09rpytrue000originfalsefalsevaluetrue5.7417579276729231massfalseixxtrue0.11546820921644431ixytrue7.2042497877163817E-10ixztrue-2.9080041212128088E-10iyytrue0.064706824634549714iyztrue7.1667020121548609E-07izztrue0.063246458718483181inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.171222203703349E-100.0103345512905195786.3263057986651106E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305962602827E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546733627E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 23:07:27,520 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\David\Desktop\URDF\core_rover_description -2025-09-29 23:07:27,534 INFO ExportHelper.cs: 148 - Beginning the export process -2025-09-29 23:07:27,534 INFO ExportHelper.cs: 154 - Creating package directories with name core_rover_description and save path C:\Users\David\Desktop\URDF -2025-09-29 23:07:29,761 INFO ExportHelper.cs: 163 - Creating CMakeLists.txt at C:\Users\David\Desktop\URDF\core_rover_description\CMakeLists.txt -2025-09-29 23:07:29,761 INFO ExportHelper.cs: 167 - Creating joint names config at C:\Users\David\Desktop\URDF\core_rover_description\config\joint_names_core_rover_description.yaml -2025-09-29 23:07:29,761 INFO ExportHelper.cs: 171 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 23:07:29,761 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 23:07:29,761 INFO ExportHelper.cs: 178 - Creating RVIZ launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 23:07:29,761 INFO ExportHelper.cs: 183 - Creating Gazebo launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 23:07:29,777 INFO ExportHelper.cs: 188 - Saving existing STL preferences -2025-09-29 23:07:29,777 INFO ExportHelper.cs: 568 - Saving users preferences -2025-09-29 23:07:29,777 INFO ExportHelper.cs: 191 - Modifying STL preferences -2025-09-29 23:07:29,777 INFO ExportHelper.cs: 582 - Setting STL preferences -2025-09-29 23:07:29,793 INFO ExportHelper.cs: 197 - Found 5 hidden components Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-2, Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-1, Shell & Averaging System-1/Arm Bracket Bonding Jig-1, Shell & Averaging System-1/Bordered Lid V1 Multibody-1, Shell & Averaging System-1/Front Camera Cluster V2-1 -2025-09-29 23:07:29,793 INFO ExportHelper.cs: 198 - Hiding all components -2025-09-29 23:07:30,519 INFO ExportHelper.cs: 205 - Beginning individual files export -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 271 - Exporting link: base_link -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 273 - Link base_link has 3 children -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 271 - Exporting link: left_suspension_member -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 273 - Link left_suspension_member has 2 children -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 271 - Exporting link: bl_wheel -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 273 - Link bl_wheel has 0 children -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 435 - bl_wheel: Exporting STL with coordinate frame Origin_bl_wheel_joint -2025-09-29 23:07:30,534 INFO ExportHelper.cs: 440 - bl_wheel: Reference geometry name -2025-09-29 23:07:30,656 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\bl_wheel.STL -2025-09-29 23:07:32,110 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:32,110 INFO ExportHelper.cs: 271 - Exporting link: fl_wheel -2025-09-29 23:07:32,110 INFO ExportHelper.cs: 273 - Link fl_wheel has 0 children -2025-09-29 23:07:32,110 INFO ExportHelper.cs: 435 - fl_wheel: Exporting STL with coordinate frame Origin_fl_wheel_joint -2025-09-29 23:07:32,110 INFO ExportHelper.cs: 440 - fl_wheel: Reference geometry name -2025-09-29 23:07:32,232 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fl_wheel.STL -2025-09-29 23:07:33,332 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:33,332 INFO ExportHelper.cs: 435 - left_suspension_member: Exporting STL with coordinate frame Origin_left_suspension_joint -2025-09-29 23:07:33,332 INFO ExportHelper.cs: 440 - left_suspension_member: Reference geometry name -2025-09-29 23:07:35,054 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\left_suspension_member.STL -2025-09-29 23:07:37,462 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:37,477 INFO ExportHelper.cs: 271 - Exporting link: right_suspension_member -2025-09-29 23:07:37,477 INFO ExportHelper.cs: 273 - Link right_suspension_member has 2 children -2025-09-29 23:07:37,477 INFO ExportHelper.cs: 271 - Exporting link: br_wheel -2025-09-29 23:07:37,477 INFO ExportHelper.cs: 273 - Link br_wheel has 0 children -2025-09-29 23:07:37,477 INFO ExportHelper.cs: 435 - br_wheel: Exporting STL with coordinate frame Origin_br_wheel_axis -2025-09-29 23:07:37,477 INFO ExportHelper.cs: 440 - br_wheel: Reference geometry name -2025-09-29 23:07:37,698 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\br_wheel.STL -2025-09-29 23:07:38,975 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:38,976 INFO ExportHelper.cs: 271 - Exporting link: fr_wheel -2025-09-29 23:07:38,976 INFO ExportHelper.cs: 273 - Link fr_wheel has 0 children -2025-09-29 23:07:38,976 INFO ExportHelper.cs: 435 - fr_wheel: Exporting STL with coordinate frame Origin_fr_wheel_joint -2025-09-29 23:07:38,976 INFO ExportHelper.cs: 440 - fr_wheel: Reference geometry name -2025-09-29 23:07:39,102 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fr_wheel.STL -2025-09-29 23:07:40,358 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:40,358 INFO ExportHelper.cs: 435 - right_suspension_member: Exporting STL with coordinate frame Origin_right_suspension_joint -2025-09-29 23:07:40,358 INFO ExportHelper.cs: 440 - right_suspension_member: Reference geometry name -2025-09-29 23:07:41,431 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\right_suspension_member.STL -2025-09-29 23:07:43,888 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:43,888 INFO ExportHelper.cs: 271 - Exporting link: averaging_bar -2025-09-29 23:07:43,888 INFO ExportHelper.cs: 273 - Link averaging_bar has 0 children -2025-09-29 23:07:43,888 INFO ExportHelper.cs: 435 - averaging_bar: Exporting STL with coordinate frame Origin_averaging_bar_axis -2025-09-29 23:07:43,888 INFO ExportHelper.cs: 440 - averaging_bar: Reference geometry name -2025-09-29 23:07:44,007 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\averaging_bar.STL -2025-09-29 23:07:44,408 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:44,408 INFO ExportHelper.cs: 435 - base_link: Exporting STL with coordinate frame Origin_global -2025-09-29 23:07:44,408 INFO ExportHelper.cs: 440 - base_link: Reference geometry name -2025-09-29 23:07:46,680 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\base_link.STL -2025-09-29 23:07:52,941 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:07:52,941 INFO ExportHelper.cs: 146 - Showing all components except previously hidden components -2025-09-29 23:08:07,034 INFO ExportHelper.cs: 146 - Resetting STL preferences -2025-09-29 23:08:07,034 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-29 23:08:07,034 INFO ExportHelper.cs: 229 - Writing URDF file to C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.urdf -2025-09-29 23:08:07,034 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.csv -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:08:07,034 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 23:08:07,034 INFO ExportHelper.cs: 235 - Copying log file -2025-09-29 23:08:07,034 INFO ExportHelper.cs: 557 - Copying C:\Users\David\sw2urdf_logs\sw2urdf.log to C:\Users\David\Desktop\URDF\core_rover_description\export.log -2025-09-29 23:08:07,050 INFO ExportHelper.cs: 238 - Resetting STL preferences -2025-09-29 23:08:07,050 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-29 23:09:56,543 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:09:56,543 INFO SwAddin.cs: 299 - Save is required -2025-09-29 23:09:56,543 INFO SwAddin.cs: 313 - Saving assembly -2025-09-29 23:10:00,348 INFO SwAddin.cs: 316 - Opening property manager -2025-09-29 23:10:00,348 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 23:10:00,355 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 23:10:00,364 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:10:00,380 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 23:10:00,380 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 23:10:00,380 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:10:00,380 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:10:00,382 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 23:10:00,395 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:10:00,397 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 23:10:00,397 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:10:00,397 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:10:00,398 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:10:00,398 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:10:00,399 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:10:00,411 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:10:00,662 INFO SwAddin.cs: 339 - Loading config tree -2025-09-29 23:10:00,662 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242259423287625E-060.11037389216180901-0.0859105519232749rpytrue000originfalsefalsevaluetrue74.655780473161542massfalseixxtrue2.4001787633692504ixytrue0.00011618556838517536ixztrue-0.0015611886307071486iyytrue2.0453538462072869iyztrue0.0055914075297434883izztrue4.2593413623318055inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueleft_suspension_memberxyztrue0.29543019562220779-0.0753112643908512290.00673819277248161rpytrue000originfalsefalsevaluetrue2.092877661271368massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819353E-06ixztrue1.7290024726393557E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175073izztrue0.00584808618330121inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482195640000161-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896601.5707963267948966originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098232-1.0982782128188262E-086.1294024300551087E-09rpytrue000originfalsefalsevaluetrue5.7417579274105979massfalseixxtrue0.11546820921307206ixytrue7.2058576629712916E-10ixztrue-2.9085928016673176E-10iyytrue0.064706824633587623iyztrue7.166691410727627E-07izztrue0.063246458714804443inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811228-1.0982792120195484E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.741757927705506massfalseixxtrue0.11546820921687725ixytrue7.2054198879857512E-10ixztrue-2.9087482991579359E-10iyytrue0.064706824634663374iyztrue7.1667036967600073E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue0.0067381927281905951-0.075261480514894730.2954707472971152rpytrue000originfalsefalsevaluetrue2.0928776569814485massfalseixxtrue0.0058480861827915282ixytrue0.00021186508756189037ixztrue1.5821055457941621E-08iyytrue0.0098606806671202116iyztrue1.5821618143704884E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482195640000006-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896803.1415926535897931originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956811-1.0980108655633813E-086.1284549657258935E-09rpytrue000originfalsefalsevaluetrue5.7417579275605526massfalseixxtrue0.11546820921502553ixytrue7.1976727943417927E-10ixztrue-2.9060339735168936E-10iyytrue0.064706824634146828iyztrue7.166697443567599E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291298703025632E-09rpytrue000originfalsefalsevaluetrue5.7417579276729231massfalseixxtrue0.11546820921644431ixytrue7.2042497877163817E-10ixztrue-2.9080041212128088E-10iyytrue0.064706824634549714iyztrue7.1667020121548609E-07izztrue0.063246458718483181inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.171222203703349E-100.0103345512905195786.3263057986651106E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305962602827E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546733627E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node base_link -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-29 23:10:00,662 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-29 23:10:00,662 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-29 23:10:00,678 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-29 23:10:00,694 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,694 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:10:00,694 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,694 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-29 23:10:00,696 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 230 - Loaded 46 components for link base_link -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:10:00,710 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 230 - Loaded 21 components for link left_suspension_member -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-29 23:10:00,772 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:10:00,788 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:10:00,796 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,804 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:10:00,804 INFO CommonSwOperations.cs: 230 - Loaded 21 components for link right_suspension_member -2025-09-29 23:10:00,804 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,804 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:10:00,805 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:10:00,805 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-29 23:10:00,805 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,805 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:10:00,806 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:10:00,806 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-29 23:10:00,806 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:10:00,807 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-29 23:10:00,807 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-29 23:10:00,807 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:10:00,808 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-29 23:10:01,998 INFO SwAddin.cs: 344 - Showing property manager -2025-09-29 23:12:25,776 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-29 23:12:37,082 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-29 23:12:37,082 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242259423287625E-060.11037389216180901-0.0859105519232749rpytrue000originfalsefalsevaluetrue74.655780473161542massfalseixxtrue2.4001787633692504ixytrue0.00011618556838517536ixztrue-0.0015611886307071486iyytrue2.0453538462072869iyztrue0.0055914075297434883izztrue4.2593413623318055inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueleft_suspension_memberxyztrue0.29543019562220779-0.0753112643908512290.00673819277248161rpytrue000originfalsefalsevaluetrue2.092877661271368massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819353E-06ixztrue1.7290024726393557E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175073izztrue0.00584808618330121inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482195640000161-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896601.5707963267948966originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098232-1.0982782128188262E-086.1294024300551087E-09rpytrue000originfalsefalsevaluetrue5.7417579274105979massfalseixxtrue0.11546820921307206ixytrue7.2058576629712916E-10ixztrue-2.9085928016673176E-10iyytrue0.064706824633587623iyztrue7.166691410727627E-07izztrue0.063246458714804443inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811228-1.0982792120195484E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.741757927705506massfalseixxtrue0.11546820921687725ixytrue7.2054198879857512E-10ixztrue-2.9087482991579359E-10iyytrue0.064706824634663374iyztrue7.1667036967600073E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsenametrueright_suspension_memberxyztrue0.0067381927281905951-0.075261480514894730.2954707472971152rpytrue000originfalsefalsevaluetrue2.0928776569814485massfalseixxtrue0.0058480861827915282ixytrue0.00021186508756189037ixztrue1.5821055457941621E-08iyytrue0.0098606806671202116iyztrue1.5821618143704884E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482195640000006-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896803.1415926535897931originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956811-1.0980108655633813E-086.1284549657258935E-09rpytrue000originfalsefalsevaluetrue5.7417579275605526massfalseixxtrue0.11546820921502553ixytrue7.1976727943417927E-10ixztrue-2.9060339735168936E-10iyytrue0.064706824634146828iyztrue7.166697443567599E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291298703025632E-09rpytrue000originfalsefalsevaluetrue5.7417579276729231massfalseixxtrue0.11546820921644431ixytrue7.2042497877163817E-10ixztrue-2.9080041212128088E-10iyytrue0.064706824634549714iyztrue7.1667020121548609E-07izztrue0.063246458718483181inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.171222203703349E-100.0103345512905195786.3263057986651106E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305962602827E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546733627E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=UEYAAAUAAAD//v+HUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABWADMALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABNAAAAUEYAAAUAAAD//v+RUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwBEAGkAZgBmACAAQgBvAHgAIABWADUALQAxAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAYAAAAUEYAAAUAAAD//v+HUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABWADMALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABQAAAAUEYAAAUAAAD//v91UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAHAAaQBjAGEAdABpAG4AbgB5ADkANQBtAG0ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAAA3BAAAUEYAAAUAAAD//v91UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAHAAaQBjAGEAdABpAG4AbgB5ADkANQBtAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABFBAAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMYAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAfalsefalse -2025-09-29 23:12:37,319 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-29 23:13:04,652 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:08,234 INFO SwAddin.cs: 313 - Saving assembly -2025-09-29 23:13:11,936 INFO SwAddin.cs: 316 - Opening property manager -2025-09-29 23:13:11,938 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:11,938 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:13:11,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:13:11,956 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:13:12,044 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:13:12,045 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:13:12,046 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:13:12,047 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:13:12,048 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:13:12,049 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 23:13:12,051 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:13:12,052 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 23:13:12,052 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 23:13:12,053 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:13:12,053 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 23:13:12,054 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:13:12,055 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:13:12,055 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:13:12,056 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:13:12,056 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:13:12,057 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:13:12,057 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:13:12,057 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:13:12,058 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:13:12,058 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:13:12,058 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:13:12,059 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:13:12,059 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,060 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,061 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,061 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:13:12,061 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:13:12,062 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:13:12,062 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:13:12,062 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:13:12,063 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 23:13:12,064 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:13:12,065 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 23:13:12,066 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:13:12,066 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:13:12,067 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:13:12,067 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 23:13:12,068 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:13:12,069 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 23:13:12,069 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:13:12,069 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:13:12,070 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:13:12,070 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:13:12,070 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:13:12,071 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:13:12,071 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:13:12,071 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:13:12,072 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:13:12,072 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:13:12,072 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:13:12,073 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:13:12,073 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:13:12,073 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:13:12,074 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:13:12,074 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:13:12,074 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:13:12,075 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:13:12,075 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:13:12,075 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:13:12,076 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:13:12,076 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 23:13:12,076 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:13:12,077 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 23:13:12,077 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 23:13:12,077 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:13:12,078 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 23:13:12,078 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:13:12,078 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:13:12,079 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:13:12,079 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:13:12,080 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:13:12,080 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:13:12,080 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:13:12,081 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:13:12,081 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:13:12,081 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:13:12,082 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:13:12,082 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:13:12,098 INFO SwAddin.cs: 339 - Loading config tree -2025-09-29 23:13:12,099 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242259423287625E-060.11037389216180901-0.0859105519232749rpytrue000originfalsefalsevaluetrue74.655780473161542massfalseixxtrue2.4001787633692504ixytrue0.00011618556838517536ixztrue-0.0015611886307071486iyytrue2.0453538462072869iyztrue0.0055914075297434883izztrue4.2593413623318055inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.0067381927281905951-0.075261480514894730.2954707472971152rpytrue000originfalsefalsevaluetrue2.0928776569814485massfalseixxtrue0.0058480861827915282ixytrue0.00021186508756189037ixztrue1.5821055457941621E-08iyytrue0.0098606806671202116iyztrue1.5821618143704884E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482195640000006-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896803.1415926535897931originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956811-1.0980108655633813E-086.1284549657258935E-09rpytrue000originfalsefalsevaluetrue5.7417579275605526massfalseixxtrue0.11546820921502553ixytrue7.1976727943417927E-10ixztrue-2.9060339735168936E-10iyytrue0.064706824634146828iyztrue7.166697443567599E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291298703025632E-09rpytrue000originfalsefalsevaluetrue5.7417579276729231massfalseixxtrue0.11546820921644431ixytrue7.2042497877163817E-10ixztrue-2.9080041212128088E-10iyytrue0.064706824634549714iyztrue7.1667020121548609E-07izztrue0.063246458718483181inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.171222203703349E-100.0103345512905195786.3263057986651106E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305962602827E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546733627E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29543019562220779-0.0753112643908512290.00673819277248161rpytrue000originfalsefalsevaluetrue2.092877661271368massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819353E-06ixztrue1.7290024726393557E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175073izztrue0.00584808618330121inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482195640000161-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896601.5707963267948966originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098232-1.0982782128188262E-086.1294024300551087E-09rpytrue000originfalsefalsevaluetrue5.7417579274105979massfalseixxtrue0.11546820921307206ixytrue7.2058576629712916E-10ixztrue-2.9085928016673176E-10iyytrue0.064706824633587623iyztrue7.166691410727627E-07izztrue0.063246458714804443inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811228-1.0982792120195484E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.741757927705506massfalseixxtrue0.11546820921687725ixytrue7.2054198879857512E-10ixztrue-2.9087482991579359E-10iyytrue0.064706824634663374iyztrue7.1667036967600073E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-29 23:13:12,102 INFO LinkNode.cs: 35 - Building node base_link -2025-09-29 23:13:12,102 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-29 23:13:12,103 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-29 23:13:12,103 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-29 23:13:12,103 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-29 23:13:12,104 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-29 23:13:12,104 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-29 23:13:12,104 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-29 23:13:12,104 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,105 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-29 23:13:12,105 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-29 23:13:12,105 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:13:12,106 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:13:12,106 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:13:12,106 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:13:12,107 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:13:12,107 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-29 23:13:12,107 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-29 23:13:12,108 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-29 23:13:12,108 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-29 23:13:12,108 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-29 23:13:12,109 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-29 23:13:12,109 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-29 23:13:12,109 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-29 23:13:12,110 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-29 23:13:12,110 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-29 23:13:12,111 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-29 23:13:12,111 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-29 23:13:12,111 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-29 23:13:12,112 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-29 23:13:12,112 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-29 23:13:12,112 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-29 23:13:12,113 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-29 23:13:12,113 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-29 23:13:12,114 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-29 23:13:12,114 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:13:12,114 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:13:12,114 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:13:12,115 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:13:12,115 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:13:12,115 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-29 23:13:12,116 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:13:12,116 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-29 23:13:12,116 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-29 23:13:12,117 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-29 23:13:12,117 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-29 23:13:12,117 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-29 23:13:12,118 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-29 23:13:12,118 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-29 23:13:12,118 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:13:12,119 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:13:12,119 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-29 23:13:12,119 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:13:12,120 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-29 23:13:12,120 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-29 23:13:12,120 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-29 23:13:12,121 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-29 23:13:12,121 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,121 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:13:12,122 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,122 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:13:12,122 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,123 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:13:12,123 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-29 23:13:12,123 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:13:12,124 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-29 23:13:12,128 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:13:12,128 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-29 23:13:12,128 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:13:12,130 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-29 23:13:12,130 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:13:12,130 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/2342K186_Bearing .5 shaft sealed-3@Diff V5 Assem? -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-1@Shell & Averaging SystemZ -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-29 23:13:12,131 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-2@Shell & Averaging System] -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 230 - Loaded 51 components for link base_link -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link right_suspension_member -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:13:12,143 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:13:12,158 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link left_suspension_member -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:13:12,174 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-29 23:13:14,160 INFO SwAddin.cs: 344 - Showing property manager -2025-09-29 23:14:14,538 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-29 23:14:14,538 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242259423287625E-060.11037389216180901-0.0859105519232749rpytrue000originfalsefalsevaluetrue74.655780473161542massfalseixxtrue2.4001787633692504ixytrue0.00011618556838517536ixztrue-0.0015611886307071486iyytrue2.0453538462072869iyztrue0.0055914075297434883izztrue4.2593413623318055inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.0067381927281905951-0.075261480514894730.2954707472971152rpytrue000originfalsefalsevaluetrue2.0928776569814485massfalseixxtrue0.0058480861827915282ixytrue0.00021186508756189037ixztrue1.5821055457941621E-08iyytrue0.0098606806671202116iyztrue1.5821618143704884E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482195640000006-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896803.1415926535897931originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956811-1.0980108655633813E-086.1284549657258935E-09rpytrue000originfalsefalsevaluetrue5.7417579275605526massfalseixxtrue0.11546820921502553ixytrue7.1976727943417927E-10ixztrue-2.9060339735168936E-10iyytrue0.064706824634146828iyztrue7.166697443567599E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291298703025632E-09rpytrue000originfalsefalsevaluetrue5.7417579276729231massfalseixxtrue0.11546820921644431ixytrue7.2042497877163817E-10ixztrue-2.9080041212128088E-10iyytrue0.064706824634549714iyztrue7.1667020121548609E-07izztrue0.063246458718483181inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.171222203703349E-100.0103345512905195786.3263057986651106E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305962602827E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546733627E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29543019562220779-0.0753112643908512290.00673819277248161rpytrue000originfalsefalsevaluetrue2.092877661271368massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819353E-06ixztrue1.7290024726393557E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175073izztrue0.00584808618330121inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482195640000161-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896601.5707963267948966originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098232-1.0982782128188262E-086.1294024300551087E-09rpytrue000originfalsefalsevaluetrue5.7417579274105979massfalseixxtrue0.11546820921307206ixytrue7.2058576629712916E-10ixztrue-2.9085928016673176E-10iyytrue0.064706824633587623iyztrue7.166691410727627E-07izztrue0.063246458714804443inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811228-1.0982792120195484E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.741757927705506massfalseixxtrue0.11546820921687725ixytrue7.2054198879857512E-10ixztrue-2.9087482991579359E-10iyytrue0.064706824634663374iyztrue7.1667036967600073E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=UEYAAAUAAAD//v+HUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABWADMALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABNAAAAUEYAAAUAAAD//v+RUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwBEAGkAZgBmACAAQgBvAHgAIABWADUALQAxAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAYAAAAUEYAAAUAAAD//v+HUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABWADMALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABQAAAAUEYAAAUAAAD//v91UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAHAAaQBjAGEAdABpAG4AbgB5ADkANQBtAG0ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAAA3BAAAUEYAAAUAAAD//v91UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAHAAaQBjAGEAdABpAG4AbgB5ADkANQBtAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABFBAAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMYAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-29 23:14:19,371 INFO ExportHelperExtension.cs: 347 - Creating joint right_suspension_member -2025-09-29 23:14:19,623 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child right_suspension_member failed -2025-09-29 23:14:21,522 INFO ExportHelperExtension.cs: 347 - Creating joint br_wheel -2025-09-29 23:14:21,701 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child br_wheel failed -2025-09-29 23:14:23,488 INFO ExportHelperExtension.cs: 347 - Creating joint fr_wheel -2025-09-29 23:14:23,661 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child fr_wheel failed -2025-09-29 23:14:25,451 INFO ExportHelperExtension.cs: 347 - Creating joint averaging_bar -2025-09-29 23:14:25,640 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child averaging_bar failed -2025-09-29 23:14:26,095 INFO ExportHelperExtension.cs: 347 - Creating joint left_suspension_member -2025-09-29 23:14:26,268 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child left_suspension_member failed -2025-09-29 23:14:27,964 INFO ExportHelperExtension.cs: 347 - Creating joint bl_wheel -2025-09-29 23:14:28,121 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child bl_wheel failed -2025-09-29 23:14:29,440 INFO ExportHelperExtension.cs: 347 - Creating joint fl_wheel -2025-09-29 23:14:29,597 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child fl_wheel failed -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:14:30,980 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:14:30,996 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 23:14:30,996 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:14:30,997 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 23:14:30,998 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:14:30,998 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:14:30,998 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:14:30,999 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 23:14:31,012 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:14:31,017 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:14:31,028 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:14:31,028 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:14:31,048 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:14:31,048 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:14:31,050 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:14:31,050 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:14:31,051 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:14:31,051 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 23:14:31,051 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:14:31,052 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 23:14:31,052 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 23:14:31,052 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:14:31,053 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 23:14:31,053 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:14:31,053 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:14:31,054 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:14:31,054 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:14:31,054 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:14:31,055 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:14:31,055 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:14:31,055 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:14:31,056 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:14:31,056 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:14:31,056 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:14:31,057 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:14:31,092 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-29 23:15:41,822 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2025-09-29 23:15:41,838 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.7242259423287625E-060.11037389216180901-0.0859105519232749rpytrue000originfalsefalsevaluetrue74.655780473161542massfalseixxtrue2.4001787633692504ixytrue0.00011618556838517536ixztrue-0.0015611886307071486iyytrue2.0453538462072869iyztrue0.0055914075297434883izztrue4.2593413623318055inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.0067381927281905951-0.075261480514894730.2954707472971152rpytrue000originfalsefalsevaluetrue2.0928776569814485massfalseixxtrue0.0058480861827915282ixytrue0.00021186508756189037ixztrue1.5821055457941621E-08iyytrue0.0098606806671202116iyztrue1.5821618143704884E-06izztrue0.00515783964909268inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482195640000006-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896803.1415926535897931originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956811-1.0980108655633813E-086.1284549657258935E-09rpytrue000originfalsefalsevaluetrue5.7417579275605526massfalseixxtrue0.11546820921502553ixytrue7.1976727943417927E-10ixztrue-2.9060339735168936E-10iyytrue0.064706824634146828iyztrue7.166697443567599E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291298703025632E-09rpytrue000originfalsefalsevaluetrue5.7417579276729231massfalseixxtrue0.11546820921644431ixytrue7.2042497877163817E-10ixztrue-2.9080041212128088E-10iyytrue0.064706824634549714iyztrue7.1667020121548609E-07izztrue0.063246458718483181inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.171222203703349E-100.0103345512905195786.3263057986651106E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305962602827E-11ixztrue-1.0050971789446396E-11iyytrue0.023692179851896412iyztrue1.5403213546733627E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29543019562220779-0.0753112643908512290.00673819277248161rpytrue000originfalsefalsevaluetrue2.092877661271368massfalseixxtrue0.0051582154324871059ixytrue-1.4343899977819353E-06ixztrue1.7290024726393557E-08iyytrue0.0098603048843634682iyztrue0.00021191376548175073izztrue0.00584808618330121inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482195640000161-0.26788728163563535-0.18459449999999997rpytrue1.570796326794896601.5707963267948966originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098232-1.0982782128188262E-086.1294024300551087E-09rpytrue000originfalsefalsevaluetrue5.7417579274105979massfalseixxtrue0.11546820921307206ixytrue7.2058576629712916E-10ixztrue-2.9085928016673176E-10iyytrue0.064706824633587623iyztrue7.166691410727627E-07izztrue0.063246458714804443inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811228-1.0982792120195484E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.741757927705506massfalseixxtrue0.11546820921687725ixytrue7.2054198879857512E-10ixztrue-2.9087482991579359E-10iyytrue0.064706824634663374iyztrue7.1667036967600073E-07izztrue0.063246458718970056inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-29 23:16:08,850 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\David\Desktop\URDF\core_rover_description -2025-09-29 23:16:08,850 INFO ExportHelper.cs: 148 - Beginning the export process -2025-09-29 23:16:08,850 INFO ExportHelper.cs: 154 - Creating package directories with name core_rover_description and save path C:\Users\David\Desktop\URDF -2025-09-29 23:16:10,351 INFO ExportHelper.cs: 163 - Creating CMakeLists.txt at C:\Users\David\Desktop\URDF\core_rover_description\CMakeLists.txt -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 167 - Creating joint names config at C:\Users\David\Desktop\URDF\core_rover_description\config\joint_names_core_rover_description.yaml -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 171 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 23:16:10,383 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 178 - Creating RVIZ launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 183 - Creating Gazebo launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 188 - Saving existing STL preferences -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 568 - Saving users preferences -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 191 - Modifying STL preferences -2025-09-29 23:16:10,383 INFO ExportHelper.cs: 582 - Setting STL preferences -2025-09-29 23:16:10,398 INFO ExportHelper.cs: 197 - Found 5 hidden components Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-2, Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-1, Shell & Averaging System-1/Arm Bracket Bonding Jig-1, Shell & Averaging System-1/Bordered Lid V1 Multibody-1, Shell & Averaging System-1/Front Camera Cluster V2-1 -2025-09-29 23:16:10,398 INFO ExportHelper.cs: 198 - Hiding all components -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 205 - Beginning individual files export -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 271 - Exporting link: base_link -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 273 - Link base_link has 3 children -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 271 - Exporting link: right_suspension_member -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 273 - Link right_suspension_member has 2 children -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 271 - Exporting link: br_wheel -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 273 - Link br_wheel has 0 children -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 435 - br_wheel: Exporting STL with coordinate frame Origin_br_wheel_axis -2025-09-29 23:16:11,077 INFO ExportHelper.cs: 440 - br_wheel: Reference geometry name -2025-09-29 23:16:11,171 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\br_wheel.STL -2025-09-29 23:16:12,352 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:12,352 INFO ExportHelper.cs: 271 - Exporting link: fr_wheel -2025-09-29 23:16:12,352 INFO ExportHelper.cs: 273 - Link fr_wheel has 0 children -2025-09-29 23:16:12,352 INFO ExportHelper.cs: 435 - fr_wheel: Exporting STL with coordinate frame Origin_fr_wheel_joint -2025-09-29 23:16:12,352 INFO ExportHelper.cs: 440 - fr_wheel: Reference geometry name -2025-09-29 23:16:12,462 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fr_wheel.STL -2025-09-29 23:16:13,630 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:13,630 INFO ExportHelper.cs: 435 - right_suspension_member: Exporting STL with coordinate frame Origin_right_suspension_joint -2025-09-29 23:16:13,630 INFO ExportHelper.cs: 440 - right_suspension_member: Reference geometry name -2025-09-29 23:16:14,098 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\right_suspension_member.STL -2025-09-29 23:16:15,703 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:15,703 INFO ExportHelper.cs: 271 - Exporting link: averaging_bar -2025-09-29 23:16:15,703 INFO ExportHelper.cs: 273 - Link averaging_bar has 0 children -2025-09-29 23:16:15,703 INFO ExportHelper.cs: 435 - averaging_bar: Exporting STL with coordinate frame Origin_averaging_bar_axis -2025-09-29 23:16:15,703 INFO ExportHelper.cs: 440 - averaging_bar: Reference geometry name -2025-09-29 23:16:15,876 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\averaging_bar.STL -2025-09-29 23:16:16,285 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:16,285 INFO ExportHelper.cs: 271 - Exporting link: left_suspension_member -2025-09-29 23:16:16,285 INFO ExportHelper.cs: 273 - Link left_suspension_member has 2 children -2025-09-29 23:16:16,285 INFO ExportHelper.cs: 271 - Exporting link: bl_wheel -2025-09-29 23:16:16,285 INFO ExportHelper.cs: 273 - Link bl_wheel has 0 children -2025-09-29 23:16:16,285 INFO ExportHelper.cs: 435 - bl_wheel: Exporting STL with coordinate frame Origin_bl_wheel_joint -2025-09-29 23:16:16,285 INFO ExportHelper.cs: 440 - bl_wheel: Reference geometry name -2025-09-29 23:16:16,440 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\bl_wheel.STL -2025-09-29 23:16:17,667 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:17,685 INFO ExportHelper.cs: 271 - Exporting link: fl_wheel -2025-09-29 23:16:17,686 INFO ExportHelper.cs: 273 - Link fl_wheel has 0 children -2025-09-29 23:16:17,686 INFO ExportHelper.cs: 435 - fl_wheel: Exporting STL with coordinate frame Origin_fl_wheel_joint -2025-09-29 23:16:17,686 INFO ExportHelper.cs: 440 - fl_wheel: Reference geometry name -2025-09-29 23:16:17,824 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fl_wheel.STL -2025-09-29 23:16:19,162 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:19,162 INFO ExportHelper.cs: 435 - left_suspension_member: Exporting STL with coordinate frame Origin_left_suspension_joint -2025-09-29 23:16:19,162 INFO ExportHelper.cs: 440 - left_suspension_member: Reference geometry name -2025-09-29 23:16:19,618 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\left_suspension_member.STL -2025-09-29 23:16:21,394 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:21,394 INFO ExportHelper.cs: 435 - base_link: Exporting STL with coordinate frame Origin_global -2025-09-29 23:16:21,394 INFO ExportHelper.cs: 440 - base_link: Reference geometry name -2025-09-29 23:16:23,677 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\base_link.STL -2025-09-29 23:16:30,076 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:16:30,076 INFO ExportHelper.cs: 146 - Showing all components except previously hidden components -2025-09-29 23:16:43,463 INFO ExportHelper.cs: 146 - Resetting STL preferences -2025-09-29 23:16:43,463 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-29 23:16:43,463 INFO ExportHelper.cs: 229 - Writing URDF file to C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.urdf -2025-09-29 23:16:43,463 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.csv -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:16:43,463 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:16:43,463 INFO ExportHelper.cs: 235 - Copying log file -2025-09-29 23:16:43,463 INFO ExportHelper.cs: 557 - Copying C:\Users\David\sw2urdf_logs\sw2urdf.log to C:\Users\David\Desktop\URDF\core_rover_description\export.log -2025-09-29 23:16:43,463 INFO ExportHelper.cs: 238 - Resetting STL preferences -2025-09-29 23:16:43,463 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-29 23:18:51,843 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:51,843 INFO SwAddin.cs: 299 - Save is required -2025-09-29 23:18:51,843 INFO SwAddin.cs: 313 - Saving assembly -2025-09-29 23:18:55,830 INFO SwAddin.cs: 316 - Opening property manager -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 23:18:55,831 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:18:55,841 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:18:55,856 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:18:55,872 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:18:55,888 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:18:55,889 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:18:55,889 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:18:55,890 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:18:55,891 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:18:55,891 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:18:55,892 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:18:55,904 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:18:55,904 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:18:55,935 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:18:55,935 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:18:55,951 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:18:55,951 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:18:55,951 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:18:56,301 INFO SwAddin.cs: 339 - Loading config tree -2025-09-29 23:18:56,302 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.65913305993836E-060.1095719694213222-0.086573079086824836rpytrue000originfalsefalsevaluetrue75.385539110244707massfalseixxtrue2.4001992795671647ixytrue0.00011623742466701307ixztrue-0.001561140137627726iyytrue2.0513865858339115iyztrue0.0055915551871194543izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203-0.094670.29529rpytrue000originfalsefalsevaluetrue1.7681massfalseixxtrue0.0058417ixytrue0.00021191ixztrue2.5225E-08iyytrue0.0068473iyztrue1.4957E-06izztrue0.0021448inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956922-1.0980108822167267E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605606massfalseixxtrue0.1154682092150255ixytrue7.1976726571971569E-10ixztrue-2.9060340684471563E-10iyytrue0.0647068246341468iyztrue7.1666974435155573E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076182-1.098223062490078E-086.1291299813248656E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644387ixytrue7.20424939451769E-10ixztrue-2.9080038111389341E-10iyytrue0.0647068246345494iyztrue7.166702010841079E-07izztrue0.063246458718483028inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.1712E-100.0103356.3263E-10rpytrue000originfalsefalsevaluetrue0.87223massfalseixxtrue0.00010223ixytrue1.2617E-11ixztrue-1.0051E-11iyytrue0.023692iyztrue1.5403E-11izztrue0.023658inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601-1.0983E-086.1294E-09rpytrue000originfalsefalsevaluetrue5.7418massfalseixxtrue0.11547ixytrue7.2059E-10ixztrue-2.9086E-10iyytrue0.064707iyztrue7.1667E-07izztrue0.063246inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.04760134974481145-1.0982792231217786E-086.129330265558508E-09rpytrue000originfalsefalsevaluetrue5.7417579277055131massfalseixxtrue0.11546820921687731ixytrue7.2054199058401324E-10ixztrue-2.9087483110759981E-10iyytrue0.064706824634663429iyztrue7.1667036964651043E-07izztrue0.063246458718970069inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-29 23:18:56,306 INFO LinkNode.cs: 35 - Building node base_link -2025-09-29 23:18:56,306 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-29 23:18:56,307 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-29 23:18:56,307 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-29 23:18:56,308 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-29 23:18:56,308 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-29 23:18:56,308 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-29 23:18:56,309 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-29 23:18:56,309 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,310 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-29 23:18:56,310 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-29 23:18:56,311 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:18:56,311 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:18:56,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:18:56,313 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-29 23:18:56,313 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-29 23:18:56,314 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,324 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/2342K186_Bearing .5 shaft sealed-3@Diff V5 Assem? -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-1@Shell & Averaging SystemZ -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-2@Shell & Averaging System] -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 230 - Loaded 51 components for link base_link -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:18:56,339 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,355 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:18:56,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,386 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:18:56,386 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,386 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:18:56,386 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link right_suspension_member -2025-09-29 23:18:56,386 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:18:56,389 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link left_suspension_member -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-29 23:18:56,402 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-29 23:18:57,787 INFO SwAddin.cs: 344 - Showing property manager -2025-09-29 23:19:04,526 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-29 23:19:04,526 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.65913305993836E-060.1095719694213222-0.086573079086824836rpytrue000originfalsefalsevaluetrue75.385539110244707massfalseixxtrue2.4001992795671647ixytrue0.00011623742466701307ixztrue-0.001561140137627726iyytrue2.0513865858339115iyztrue0.0055915551871194543izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203-0.094670.29529rpytrue000originfalsefalsevaluetrue1.7681massfalseixxtrue0.0058417ixytrue0.00021191ixztrue2.5225E-08iyytrue0.0068473iyztrue1.4957E-06izztrue0.0021448inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956922-1.0980108822167267E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605606massfalseixxtrue0.1154682092150255ixytrue7.1976726571971569E-10ixztrue-2.9060340684471563E-10iyytrue0.0647068246341468iyztrue7.1666974435155573E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076182-1.098223062490078E-086.1291299813248656E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644387ixytrue7.20424939451769E-10ixztrue-2.9080038111389341E-10iyytrue0.0647068246345494iyztrue7.166702010841079E-07izztrue0.063246458718483028inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.1712E-100.0103356.3263E-10rpytrue000originfalsefalsevaluetrue0.87223massfalseixxtrue0.00010223ixytrue1.2617E-11ixztrue-1.0051E-11iyytrue0.023692iyztrue1.5403E-11izztrue0.023658inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601-1.0983E-086.1294E-09rpytrue000originfalsefalsevaluetrue5.7418massfalseixxtrue0.11547ixytrue7.2059E-10ixztrue-2.9086E-10iyytrue0.064707iyztrue7.1667E-07izztrue0.063246inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.04760134974481145-1.0982792231217786E-086.129330265558508E-09rpytrue000originfalsefalsevaluetrue5.7417579277055131massfalseixxtrue0.11546820921687731ixytrue7.2054199058401324E-10ixztrue-2.9087483110759981E-10iyytrue0.064706824634663429iyztrue7.1667036964651043E-07izztrue0.063246458718970069inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-29 23:19:08,989 INFO ExportHelperExtension.cs: 347 - Creating joint right_suspension_member -2025-09-29 23:19:09,196 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child right_suspension_member failed -2025-09-29 23:19:11,110 INFO ExportHelperExtension.cs: 347 - Creating joint br_wheel -2025-09-29 23:19:11,252 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child br_wheel failed -2025-09-29 23:19:13,090 INFO ExportHelperExtension.cs: 347 - Creating joint fr_wheel -2025-09-29 23:19:13,247 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child fr_wheel failed -2025-09-29 23:19:15,069 INFO ExportHelperExtension.cs: 347 - Creating joint averaging_bar -2025-09-29 23:19:15,242 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child averaging_bar failed -2025-09-29 23:19:15,744 INFO ExportHelperExtension.cs: 347 - Creating joint left_suspension_member -2025-09-29 23:19:15,902 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child left_suspension_member failed -2025-09-29 23:19:17,724 INFO ExportHelperExtension.cs: 347 - Creating joint bl_wheel -2025-09-29 23:19:17,850 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child bl_wheel failed -2025-09-29 23:19:19,233 INFO ExportHelperExtension.cs: 347 - Creating joint fl_wheel -2025-09-29 23:19:19,359 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child fl_wheel failed -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-29 23:19:20,773 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:19:20,788 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:19:20,804 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:19:20,820 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-29 23:19:20,835 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-29 23:19:20,835 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-29 23:19:20,835 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-29 23:19:20,835 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:19:20,836 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-29 23:19:20,883 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-29 23:20:56,102 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2025-09-29 23:20:56,102 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.65913305993836E-060.1095719694213222-0.086573079086824836rpytrue000originfalsefalsevaluetrue75.385539110244707massfalseixxtrue2.4001992795671647ixytrue0.00011623742466701307ixztrue-0.001561140137627726iyytrue2.0513865858339115iyztrue0.0055915551871194543izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203-0.094670.29529rpytrue000originfalsefalsevaluetrue1.7681massfalseixxtrue0.0058417ixytrue0.00021191ixztrue2.5225E-08iyytrue0.0068473iyztrue1.4957E-06izztrue0.0021448inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956922-1.0980108822167267E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605606massfalseixxtrue0.1154682092150255ixytrue7.1976726571971569E-10ixztrue-2.9060340684471563E-10iyytrue0.0647068246341468iyztrue7.1666974435155573E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076182-1.098223062490078E-086.1291299813248656E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644387ixytrue7.20424939451769E-10ixztrue-2.9080038111389341E-10iyytrue0.0647068246345494iyztrue7.166702010841079E-07izztrue0.063246458718483028inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.1712E-100.0103356.3263E-10rpytrue000originfalsefalsevaluetrue0.87223massfalseixxtrue0.00010223ixytrue1.2617E-11ixztrue-1.0051E-11iyytrue0.023692iyztrue1.5403E-11izztrue0.023658inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue000rpytrue000originfalsefalsevaluetrue0massfalseixxtrue0ixytrue0ixztrue0iyytrue0iyztrue0izztrue0inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue0uppertrue0efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601-1.0983E-086.1294E-09rpytrue000originfalsefalsevaluetrue5.7418massfalseixxtrue0.11547ixytrue7.2059E-10ixztrue-2.9086E-10iyytrue0.064707iyztrue7.1667E-07izztrue0.063246inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.792160.819610.933331colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.04760134974481145-1.0982792231217786E-086.129330265558508E-09rpytrue000originfalsefalsevaluetrue5.7417579277055131massfalseixxtrue0.11546820921687731ixytrue7.2054199058401324E-10ixztrue-2.9087483110759981E-10iyytrue0.064706824634663429iyztrue7.1667036964651043E-07izztrue0.063246458718970069inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-29 23:21:11,720 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\David\Desktop\URDF\core_rover_description -2025-09-29 23:21:11,720 INFO ExportHelper.cs: 148 - Beginning the export process -2025-09-29 23:21:11,720 INFO ExportHelper.cs: 154 - Creating package directories with name core_rover_description and save path C:\Users\David\Desktop\URDF -2025-09-29 23:21:12,921 INFO ExportHelper.cs: 163 - Creating CMakeLists.txt at C:\Users\David\Desktop\URDF\core_rover_description\CMakeLists.txt -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 167 - Creating joint names config at C:\Users\David\Desktop\URDF\core_rover_description\config\joint_names_core_rover_description.yaml -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 171 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 23:21:12,946 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 178 - Creating RVIZ launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 183 - Creating Gazebo launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 188 - Saving existing STL preferences -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 568 - Saving users preferences -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 191 - Modifying STL preferences -2025-09-29 23:21:12,946 INFO ExportHelper.cs: 582 - Setting STL preferences -2025-09-29 23:21:12,953 INFO ExportHelper.cs: 197 - Found 5 hidden components Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-2, Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-1, Shell & Averaging System-1/Arm Bracket Bonding Jig-1, Shell & Averaging System-1/Bordered Lid V1 Multibody-1, Shell & Averaging System-1/Front Camera Cluster V2-1 -2025-09-29 23:21:12,953 INFO ExportHelper.cs: 198 - Hiding all components -2025-09-29 23:21:13,758 INFO ExportHelper.cs: 205 - Beginning individual files export -2025-09-29 23:21:13,758 INFO ExportHelper.cs: 271 - Exporting link: base_link -2025-09-29 23:21:13,758 INFO ExportHelper.cs: 273 - Link base_link has 3 children -2025-09-29 23:21:13,758 INFO ExportHelper.cs: 271 - Exporting link: right_suspension_member -2025-09-29 23:21:13,773 INFO ExportHelper.cs: 273 - Link right_suspension_member has 2 children -2025-09-29 23:21:13,773 INFO ExportHelper.cs: 271 - Exporting link: br_wheel -2025-09-29 23:21:13,773 INFO ExportHelper.cs: 273 - Link br_wheel has 0 children -2025-09-29 23:21:13,773 INFO ExportHelper.cs: 435 - br_wheel: Exporting STL with coordinate frame Origin_br_wheel_axis -2025-09-29 23:21:13,773 INFO ExportHelper.cs: 440 - br_wheel: Reference geometry name -2025-09-29 23:21:13,868 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\br_wheel.STL -2025-09-29 23:21:15,048 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:15,048 INFO ExportHelper.cs: 271 - Exporting link: fr_wheel -2025-09-29 23:21:15,048 INFO ExportHelper.cs: 273 - Link fr_wheel has 0 children -2025-09-29 23:21:15,048 INFO ExportHelper.cs: 435 - fr_wheel: Exporting STL with coordinate frame Origin_fr_wheel_joint -2025-09-29 23:21:15,048 INFO ExportHelper.cs: 440 - fr_wheel: Reference geometry name -2025-09-29 23:21:15,190 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fr_wheel.STL -2025-09-29 23:21:16,473 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:16,480 INFO ExportHelper.cs: 435 - right_suspension_member: Exporting STL with coordinate frame Origin_right_suspension_joint -2025-09-29 23:21:16,480 INFO ExportHelper.cs: 440 - right_suspension_member: Reference geometry name -2025-09-29 23:21:17,078 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\right_suspension_member.STL -2025-09-29 23:21:18,748 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:18,748 INFO ExportHelper.cs: 271 - Exporting link: averaging_bar -2025-09-29 23:21:18,748 INFO ExportHelper.cs: 273 - Link averaging_bar has 0 children -2025-09-29 23:21:18,748 INFO ExportHelper.cs: 435 - averaging_bar: Exporting STL with coordinate frame Origin_averaging_bar_axis -2025-09-29 23:21:18,764 INFO ExportHelper.cs: 440 - averaging_bar: Reference geometry name -2025-09-29 23:21:18,905 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\averaging_bar.STL -2025-09-29 23:21:19,336 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:19,343 INFO ExportHelper.cs: 271 - Exporting link: left_suspension_member -2025-09-29 23:21:19,343 INFO ExportHelper.cs: 273 - Link left_suspension_member has 2 children -2025-09-29 23:21:19,343 INFO ExportHelper.cs: 271 - Exporting link: bl_wheel -2025-09-29 23:21:19,343 INFO ExportHelper.cs: 273 - Link bl_wheel has 0 children -2025-09-29 23:21:19,347 INFO ExportHelper.cs: 435 - bl_wheel: Exporting STL with coordinate frame Origin_bl_wheel_joint -2025-09-29 23:21:19,347 INFO ExportHelper.cs: 440 - bl_wheel: Reference geometry name -2025-09-29 23:21:19,489 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\bl_wheel.STL -2025-09-29 23:21:20,752 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:20,765 INFO ExportHelper.cs: 271 - Exporting link: fl_wheel -2025-09-29 23:21:20,765 INFO ExportHelper.cs: 273 - Link fl_wheel has 0 children -2025-09-29 23:21:20,765 INFO ExportHelper.cs: 435 - fl_wheel: Exporting STL with coordinate frame Origin_fl_wheel_joint -2025-09-29 23:21:20,765 INFO ExportHelper.cs: 440 - fl_wheel: Reference geometry name -2025-09-29 23:21:20,922 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fl_wheel.STL -2025-09-29 23:21:22,196 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:22,196 INFO ExportHelper.cs: 435 - left_suspension_member: Exporting STL with coordinate frame Origin_left_suspension_joint -2025-09-29 23:21:22,212 INFO ExportHelper.cs: 440 - left_suspension_member: Reference geometry name -2025-09-29 23:21:22,720 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\left_suspension_member.STL -2025-09-29 23:21:24,650 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:24,650 INFO ExportHelper.cs: 435 - base_link: Exporting STL with coordinate frame Origin_global -2025-09-29 23:21:24,666 INFO ExportHelper.cs: 440 - base_link: Reference geometry name -2025-09-29 23:21:27,125 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\base_link.STL -2025-09-29 23:21:33,187 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-29 23:21:33,187 INFO ExportHelper.cs: 146 - Showing all components except previously hidden components -2025-09-29 23:21:47,288 INFO ExportHelper.cs: 146 - Resetting STL preferences -2025-09-29 23:21:47,288 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-29 23:21:47,288 INFO ExportHelper.cs: 229 - Writing URDF file to C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.urdf -2025-09-29 23:21:47,303 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.csv -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:21:47,303 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-29 23:21:47,303 INFO ExportHelper.cs: 235 - Copying log file -2025-09-29 23:21:47,303 INFO ExportHelper.cs: 557 - Copying C:\Users\David\sw2urdf_logs\sw2urdf.log to C:\Users\David\Desktop\URDF\core_rover_description\export.log -2025-09-29 23:21:47,336 INFO ExportHelper.cs: 238 - Resetting STL preferences -2025-09-29 23:21:47,338 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-30 00:48:47,779 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:47,779 INFO SwAddin.cs: 299 - Save is required -2025-09-30 00:48:47,779 INFO SwAddin.cs: 313 - Saving assembly -2025-09-30 00:48:51,901 INFO SwAddin.cs: 316 - Opening property manager -2025-09-30 00:48:51,902 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:51,903 INFO ExportHelperExtension.cs: 1136 - Found 122 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:51,903 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:51,908 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 00:48:51,970 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 00:48:51,970 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:48:51,971 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:48:51,987 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 122 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:48:52,003 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:48:52,018 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:48:52,301 INFO SwAddin.cs: 339 - Loading config tree -2025-09-30 00:48:52,317 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.6591330599454964E-060.10957196942132218-0.0865730790868248rpytrue000originfalsefalsevaluetrue75.38553911024465massfalseixxtrue2.4001992795671661ixytrue0.00011623742466712062ixztrue-0.0015611401376277457iyytrue2.0513865858339093iyztrue0.0055915551871194976izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203448629581968-0.094669634292892990.29528781555519346rpytrue000originfalsefalsevaluetrue1.7680515785319755massfalseixxtrue0.0058416782325832819ixytrue0.00021190700411912095ixztrue2.5225188524254267E-08iyytrue0.0068472827239013613iyztrue1.4957244240372892E-06izztrue0.0021448075862501538inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956978-1.0980108849922843E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605615massfalseixxtrue0.11546820921502547ixytrue7.1976727110259342E-10ixztrue-2.9060340642419872E-10iyytrue0.064706824634146787iyztrue7.1666974435849462E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291300923471681E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644385ixytrue7.2042494408480529E-10ixztrue-2.908003802532643E-10iyytrue0.0647068246345494iyztrue7.1667020108847181E-07izztrue0.063246458718483042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.17122205462555E-100.0103345512905195226.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305885000188E-11ixztrue-1.0050971599711016E-11iyytrue0.023692179851896412iyztrue1.5403213545380754E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29528890483070291-0.09468265717200270.035203448612943222rpytrue000originfalsefalsevaluetrue1.7680515828218952massfalseixxtrue0.0021448075806859038ixytrue-1.495609983178101E-06ixztrue-2.516212300397192E-08iyytrue0.006847282730103251iyztrue0.00021190718895972162izztrue0.0058416782330929637inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098287-1.0982782072677111E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274106014massfalseixxtrue0.11546820921307203ixytrue7.205857542983549E-10ixztrue-2.9085930408666472E-10iyytrue0.064706824633587651iyztrue7.1666914106959141E-07izztrue0.063246458714804388inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792203462211E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.7417579277055113massfalseixxtrue0.11546820921687724ixytrue7.20541992781926E-10ixztrue-2.9087483733328303E-10iyytrue0.0647068246346634iyztrue7.1667036964477571E-07izztrue0.063246458718970042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node base_link -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-30 00:48:52,317 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-30 00:48:52,317 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-30 00:48:52,332 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-30 00:48:52,332 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-30 00:48:52,332 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-30 00:48:52,332 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-30 00:48:52,332 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-30 00:48:52,332 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-30 00:48:52,332 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-30 00:48:52,371 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-30 00:48:52,380 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:48:52,395 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-30 00:48:52,397 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:48:52,397 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-30 00:48:52,398 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:48:52,398 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-30 00:48:52,399 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-30 00:48:52,399 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-30 00:48:52,399 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-30 00:48:52,399 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/2342K186_Bearing .5 shaft sealed-3@Diff V5 Assem? -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-1@Shell & Averaging SystemZ -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-2@Shell & Averaging System] -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 230 - Loaded 51 components for link base_link -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:48:52,400 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:48:52,412 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:48:52,412 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:48:52,413 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,413 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-30 00:48:52,413 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:48:52,413 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:48:52,414 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:48:52,414 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:48:52,414 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:48:52,415 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:48:52,415 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:48:52,416 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,416 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-30 00:48:52,416 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,417 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-30 00:48:52,417 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,417 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:48:52,418 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link right_suspension_member -2025-09-30 00:48:52,418 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,418 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-30 00:48:52,419 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:48:52,419 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-30 00:48:52,419 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,420 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-30 00:48:52,420 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:48:52,420 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-30 00:48:52,421 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,421 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-30 00:48:52,421 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-30 00:48:52,421 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,422 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-30 00:48:52,422 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,422 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-30 00:48:52,423 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,423 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-30 00:48:52,423 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,424 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-30 00:48:52,424 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-30 00:48:52,424 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,425 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-30 00:48:52,425 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,425 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:48:52,426 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,426 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-30 00:48:52,426 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,426 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:48:52,427 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,427 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-30 00:48:52,427 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,428 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-30 00:48:52,428 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:48:52,429 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-30 00:48:52,430 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:48:52,431 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-30 00:48:52,431 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:48:52,432 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-30 00:48:52,432 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:48:52,432 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-30 00:48:52,433 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:48:52,433 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-30 00:48:52,433 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:48:52,434 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-30 00:48:52,434 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:48:52,434 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-30 00:48:52,435 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:48:52,435 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-30 00:48:52,435 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:48:52,436 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-30 00:48:52,436 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:48:52,439 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-30 00:48:52,458 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,458 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-30 00:48:52,459 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:48:52,459 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,460 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-30 00:48:52,460 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,461 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:48:52,461 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link left_suspension_member -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:48:52,462 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-30 00:48:53,921 INFO SwAddin.cs: 344 - Showing property manager -2025-09-30 00:49:16,257 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-30 00:49:16,273 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.6591330599454964E-060.10957196942132218-0.0865730790868248rpytrue000originfalsefalsevaluetrue75.38553911024465massfalseixxtrue2.4001992795671661ixytrue0.00011623742466712062ixztrue-0.0015611401376277457iyytrue2.0513865858339093iyztrue0.0055915551871194976izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203448629581968-0.094669634292892990.29528781555519346rpytrue000originfalsefalsevaluetrue1.7680515785319755massfalseixxtrue0.0058416782325832819ixytrue0.00021190700411912095ixztrue2.5225188524254267E-08iyytrue0.0068472827239013613iyztrue1.4957244240372892E-06izztrue0.0021448075862501538inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_jointlinktruenametruebr_wheelxyztrue-0.047601349745956978-1.0980108849922843E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605615massfalseixxtrue0.11546820921502547ixytrue7.1976727110259342E-10ixztrue-2.9060340642419872E-10iyytrue0.064706824634146787iyztrue7.1666974435849462E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291300923471681E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644385ixytrue7.2042494408480529E-10ixztrue-2.908003802532643E-10iyytrue0.0647068246345494iyztrue7.1667020108847181E-07izztrue0.063246458718483042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.17122205462555E-100.0103345512905195226.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305885000188E-11ixztrue-1.0050971599711016E-11iyytrue0.023692179851896412iyztrue1.5403213545380754E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29528890483070291-0.09468265717200270.035203448612943222rpytrue000originfalsefalsevaluetrue1.7680515828218952massfalseixxtrue0.0021448075806859038ixytrue-1.495609983178101E-06ixztrue-2.516212300397192E-08iyytrue0.006847282730103251iyztrue0.00021190718895972162izztrue0.0058416782330929637inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_jointlinktruenametruebl_wheelxyztrue-0.047601349747098287-1.0982782072677111E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274106014massfalseixxtrue0.11546820921307203ixytrue7.205857542983549E-10ixztrue-2.9085930408666472E-10iyytrue0.064706824633587651iyztrue7.1666914106959141E-07izztrue0.063246458714804388inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792203462211E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.7417579277055113massfalseixxtrue0.11546820921687724ixytrue7.20541992781926E-10ixztrue-2.9087483733328303E-10iyytrue0.0647068246346634iyztrue7.1667036964477571E-07izztrue0.063246458718970042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 347 - Creating joint right_suspension_member -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1405 - Fixing components for base_link -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 168 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 159 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 163 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 855 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 285 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 55 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-30 00:49:20,914 INFO ExportHelperExtension.cs: 1410 - Fixing 40 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 31 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 35 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 1046 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 1055 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 26 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 1171 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 1175 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 25 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 144 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 120 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 1000 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 150 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 171 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 155 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 310 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 311 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 309 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 77 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 24 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 80 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 1079 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 1093 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 198 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 207 -2025-09-30 00:49:20,930 INFO ExportHelperExtension.cs: 1410 - Fixing 208 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 206 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 819 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 823 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 822 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 816 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 119 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 578 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 579 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 106 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 202 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 27 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 90 -2025-09-30 00:49:20,938 INFO ExportHelperExtension.cs: 1410 - Fixing 93 -2025-09-30 00:49:24,504 INFO ExportHelperExtension.cs: 832 - R1: 0, 0 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 841 - R2: 0, 0 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 849 - L1: 0 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 857 - L2: 0 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 168 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 159 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 163 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 855 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 285 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 55 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 40 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 31 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 35 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1046 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1055 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 26 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1171 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1175 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 25 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 144 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 120 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1000 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 150 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 171 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 155 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 310 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 311 -2025-09-30 00:49:24,520 INFO ExportHelperExtension.cs: 1360 - Unfixing component 309 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 77 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 24 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 80 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1079 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 1093 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 198 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 207 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 208 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 206 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 819 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 823 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 822 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 816 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 119 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 578 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 579 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 106 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 202 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 27 -2025-09-30 00:49:24,536 INFO ExportHelperExtension.cs: 1360 - Unfixing component 90 -2025-09-30 00:49:24,543 INFO ExportHelperExtension.cs: 1360 - Unfixing component 93 -2025-09-30 00:49:27,379 ERROR ExportPropertyManager.cs: 399 - Exception caught handling button press 17 -System.Exception: Reference sketch does not exist - at SW2URDF.URDFExport.ExportHelper.AddSketchGeometry(Origin Origin) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 696 - at SW2URDF.URDFExport.ExportHelper.CreateRefOrigin(Origin Origin, String CoordinateSystemName) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 494 - at SW2URDF.URDFExport.ExportHelper.CreateRefOrigin(Joint Joint) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 486 - at SW2URDF.URDFExport.ExportHelper.CreateJoint(Link parent, Link child) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 454 - at SW2URDF.URDFExport.ExportHelper.CreateLinkFromComponents(Link parent, LinkNode node) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 348 - at SW2URDF.URDFExport.ExportHelper.CreateLink(LinkNode node, Int32 count) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 215 - at SW2URDF.URDFExport.ExportHelper.CreateLink(LinkNode node, Int32 count) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 227 - at SW2URDF.URDFExport.ExportHelper.CreateRobotFromTreeView(LinkNode baseNode) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportHelperExtension.cs:line 169 - at SW2URDF.URDFExport.ExportPropertyManager.ExportButtonPress() in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportPropertyManager.cs:line 239 - at SW2URDF.URDFExport.ExportPropertyManager.OnButtonPress(Int32 Id) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportPropertyManager.cs:line 381 - at SW2URDF.URDFExport.ExportPropertyManager.SolidWorks.Interop.swpublished.IPropertyManagerPage2Handler9.OnButtonPress(Int32 Id) in C:\Users\David\Source\Repos\solidworks_urdf_exporter\SW2URDF\URDFExport\ExportPropertyManager.cs:line 399 -2025-09-30 00:49:27,426 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 00:50:59,208 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:50:59,208 INFO SwAddin.cs: 299 - Save is required -2025-09-30 00:50:59,208 INFO SwAddin.cs: 313 - Saving assembly -2025-09-30 00:51:03,119 INFO SwAddin.cs: 316 - Opening property manager -2025-09-30 00:51:03,119 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,119 INFO ExportHelperExtension.cs: 1136 - Found 122 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1145 - Found 6 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 00:51:03,134 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-30 00:51:03,143 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:51:03,143 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:51:03,143 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:51:03,143 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-30 00:51:03,143 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:51:03,150 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:51:03,261 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:51:03,276 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:51:03,276 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 122 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:51:03,277 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:51:03,292 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 00:51:03,292 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-30 00:51:03,293 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 00:51:03,295 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-30 00:51:03,295 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-30 00:51:03,297 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:51:03,308 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 00:51:03,576 INFO SwAddin.cs: 339 - Loading config tree -2025-09-30 00:51:03,576 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.6591330599454964E-060.10957196942132218-0.0865730790868248rpytrue000originfalsefalsevaluetrue75.38553911024465massfalseixxtrue2.4001992795671661ixytrue0.00011623742466712062ixztrue-0.0015611401376277457iyytrue2.0513865858339093iyztrue0.0055915551871194976izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203448629581968-0.094669634292892990.29528781555519346rpytrue000originfalsefalsevaluetrue1.7680515785319755massfalseixxtrue0.0058416782325832819ixytrue0.00021190700411912095ixztrue2.5225188524254267E-08iyytrue0.0068472827239013613iyztrue1.4957244240372892E-06izztrue0.0021448075862501538inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisAutomatically Generatelinktruenametruebr_wheelxyztrue-0.047601349745956978-1.0980108849922843E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605615massfalseixxtrue0.11546820921502547ixytrue7.1976727110259342E-10ixztrue-2.9060340642419872E-10iyytrue0.064706824634146787iyztrue7.1666974435849462E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291300923471681E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644385ixytrue7.2042494408480529E-10ixztrue-2.908003802532643E-10iyytrue0.0647068246345494iyztrue7.1667020108847181E-07izztrue0.063246458718483042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.17122205462555E-100.0103345512905195226.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305885000188E-11ixztrue-1.0050971599711016E-11iyytrue0.023692179851896412iyztrue1.5403213545380754E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29528890483070291-0.09468265717200270.035203448612943222rpytrue000originfalsefalsevaluetrue1.7680515828218952massfalseixxtrue0.0021448075806859038ixytrue-1.495609983178101E-06ixztrue-2.516212300397192E-08iyytrue0.006847282730103251iyztrue0.00021190718895972162izztrue0.0058416782330929637inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisAutomatically Generatelinktruenametruebl_wheelxyztrue-0.047601349747098287-1.0982782072677111E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274106014massfalseixxtrue0.11546820921307203ixytrue7.205857542983549E-10ixztrue-2.9085930408666472E-10iyytrue0.064706824633587651iyztrue7.1666914106959141E-07izztrue0.063246458714804388inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792203462211E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.7417579277055113massfalseixxtrue0.11546820921687724ixytrue7.20541992781926E-10ixztrue-2.9087483733328303E-10iyytrue0.0647068246346634iyztrue7.1667036964477571E-07izztrue0.063246458718970042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node base_link -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-30 00:51:03,576 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-30 00:51:03,576 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,576 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-30 00:51:03,576 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-30 00:51:03,576 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:51:03,576 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-30 00:51:03,591 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-30 00:51:03,607 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,622 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:51:03,638 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-30 00:51:03,638 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:51:03,638 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/2342K186_Bearing .5 shaft sealed-3@Diff V5 Assem? -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-1@Shell & Averaging SystemZ -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-2@Shell & Averaging System] -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 230 - Loaded 51 components for link base_link -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-30 00:51:03,640 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link right_suspension_member -2025-09-30 00:51:03,654 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-30 00:51:03,669 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:51:03,676 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-30 00:51:03,685 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 00:51:03,695 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link left_suspension_member -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 00:51:03,701 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-30 00:51:05,103 INFO SwAddin.cs: 344 - Showing property manager -2025-09-30 00:51:11,903 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 00:51:13,548 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 00:51:17,734 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 00:51:19,062 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 00:51:28,445 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-30 00:51:28,476 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.6591330599454964E-060.10957196942132218-0.0865730790868248rpytrue000originfalsefalsevaluetrue75.38553911024465massfalseixxtrue2.4001992795671661ixytrue0.00011623742466712062ixztrue-0.0015611401376277457iyytrue2.0513865858339093iyztrue0.0055915551871194976izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203448629581968-0.094669634292892990.29528781555519346rpytrue000originfalsefalsevaluetrue1.7680515785319755massfalseixxtrue0.0058416782325832819ixytrue0.00021190700411912095ixztrue2.5225188524254267E-08iyytrue0.0068472827239013613iyztrue1.4957244240372892E-06izztrue0.0021448075862501538inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisAutomatically Generatelinktruenametruebr_wheelxyztrue-0.047601349745956978-1.0980108849922843E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605615massfalseixxtrue0.11546820921502547ixytrue7.1976727110259342E-10ixztrue-2.9060340642419872E-10iyytrue0.064706824634146787iyztrue7.1666974435849462E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291300923471681E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644385ixytrue7.2042494408480529E-10ixztrue-2.908003802532643E-10iyytrue0.0647068246345494iyztrue7.1667020108847181E-07izztrue0.063246458718483042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.17122205462555E-100.0103345512905195226.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305885000188E-11ixztrue-1.0050971599711016E-11iyytrue0.023692179851896412iyztrue1.5403213545380754E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29528890483070291-0.09468265717200270.035203448612943222rpytrue000originfalsefalsevaluetrue1.7680515828218952massfalseixxtrue0.0021448075806859038ixytrue-1.495609983178101E-06ixztrue-2.516212300397192E-08iyytrue0.006847282730103251iyztrue0.00021190718895972162izztrue0.0058416782330929637inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisAutomatically Generatelinktruenametruebl_wheelxyztrue-0.047601349747098287-1.0982782072677111E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274106014massfalseixxtrue0.11546820921307203ixytrue7.205857542983549E-10ixztrue-2.9085930408666472E-10iyytrue0.064706824633587651iyztrue7.1666914106959141E-07izztrue0.063246458714804388inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792203462211E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.7417579277055113massfalseixxtrue0.11546820921687724ixytrue7.20541992781926E-10ixztrue-2.9087483733328303E-10iyytrue0.0647068246346634iyztrue7.1667036964477571E-07izztrue0.063246458718970042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-30 00:51:28,712 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 01:02:30,363 INFO SwAddin.cs: 294 - Assembly export called for file A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:31,881 INFO SwAddin.cs: 313 - Saving assembly -2025-09-30 01:02:35,485 INFO SwAddin.cs: 316 - Opening property manager -2025-09-30 01:02:35,485 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,485 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:02:35,495 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-30 01:02:35,510 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:02:35,526 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:02:35,526 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:02:35,526 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-30 01:02:35,527 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 01:02:35,528 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-30 01:02:35,528 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-30 01:02:35,528 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:02:35,530 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:02:35,530 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-30 01:02:35,530 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:02:35,530 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:02:35,531 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-30 01:02:35,531 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:02:35,531 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:02:35,532 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:02:35,794 INFO SwAddin.cs: 339 - Loading config tree -2025-09-30 01:02:35,794 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.6591330599454964E-060.10957196942132218-0.0865730790868248rpytrue000originfalsefalsevaluetrue75.38553911024465massfalseixxtrue2.4001992795671661ixytrue0.00011623742466712062ixztrue-0.0015611401376277457iyytrue2.0513865858339093iyztrue0.0055915551871194976izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203448629581968-0.094669634292892990.29528781555519346rpytrue000originfalsefalsevaluetrue1.7680515785319755massfalseixxtrue0.0058416782325832819ixytrue0.00021190700411912095ixztrue2.5225188524254267E-08iyytrue0.0068472827239013613iyztrue1.4957244240372892E-06izztrue0.0021448075862501538inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisAutomatically Generatelinktruenametruebr_wheelxyztrue-0.047601349745956978-1.0980108849922843E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605615massfalseixxtrue0.11546820921502547ixytrue7.1976727110259342E-10ixztrue-2.9060340642419872E-10iyytrue0.064706824634146787iyztrue7.1666974435849462E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291300923471681E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644385ixytrue7.2042494408480529E-10ixztrue-2.908003802532643E-10iyytrue0.0647068246345494iyztrue7.1667020108847181E-07izztrue0.063246458718483042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.17122205462555E-100.0103345512905195226.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305885000188E-11ixztrue-1.0050971599711016E-11iyytrue0.023692179851896412iyztrue1.5403213545380754E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29528890483070291-0.09468265717200270.035203448612943222rpytrue000originfalsefalsevaluetrue1.7680515828218952massfalseixxtrue0.0021448075806859038ixytrue-1.495609983178101E-06ixztrue-2.516212300397192E-08iyytrue0.006847282730103251iyztrue0.00021190718895972162izztrue0.0058416782330929637inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisAutomatically Generatelinktruenametruebl_wheelxyztrue-0.047601349747098287-1.0982782072677111E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274106014massfalseixxtrue0.11546820921307203ixytrue7.205857542983549E-10ixztrue-2.9085930408666472E-10iyytrue0.064706824633587651iyztrue7.1666914106959141E-07izztrue0.063246458714804388inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792203462211E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.7417579277055113massfalseixxtrue0.11546820921687724ixytrue7.20541992781926E-10ixztrue-2.9087483733328303E-10iyytrue0.0647068246346634iyztrue7.1667036964477571E-07izztrue0.063246458718970042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node base_link -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node right_suspension_member -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node br_wheel -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node fr_wheel -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node averaging_bar -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node left_suspension_member -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node bl_wheel -2025-09-30 01:02:35,810 INFO LinkNode.cs: 35 - Building node fl_wheel -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for base_link from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/CSC Shell Assembly-1@Shell & Averaging System/CSC V4 Shell-1@CSC Shell Assembly -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Chassis Shells CSC V4\CSC V4 Shell.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???SMotor and 6 pin connector mount-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Motor and 6 pin connector mount.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???`Inside Motor and 6 pin connector mount plate-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Motor & 6 Pin Connctor Mount CSC V4\Inside Motor and 6 pin connector mount plate.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff Box Backing Plate V2-1@Shell & Averaging SystemW -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box Backing Plate V2.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate Backing V1-1@Shell & Averaging System -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate Backing V1.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/L bracket-1@Arm Bracket Assembly Right V3o -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\L bracket.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorArm Bolts-1@MirrorArm Bracket Assemblyt -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorArm Bolts.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Arm Bracket Assembly Right V3-1@Shell & Averaging System/Arm Bolts-1@Arm Bracket Assembly Right V3o7 -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\Arm Bolts.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Base-1@Elec_Box_AssemP -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Base.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Left_Wall-1@Elec_Box_AssemP( -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Left_Wall.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Front_Wall-1@Elec_Box_AssemP -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Front_Wall.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???bElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Right_Wall-1@Elec_Box_AssemP# -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Right_Wall.SLDPRT -2025-09-30 01:02:35,810 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???{Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/POE Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\POE Switch (Measured with hole pattern).SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Ethernet Switch (Measured with hole pattern)-1@Elec_Box_AssemP -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Ethernet Switch (Measured with hole pattern).SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/AN_TOP_COVER_1_2.STP-1@WS_TOP_COVER_ASM_ASM_1_ASM_1.STPPX -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\AN_TOP_COVER_1_2.STP.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/NUC13ANH_NUC13LCH-1@Elec_Box_Assem/NUC13ANH_NUC13LCH.STP-1@NUC13ANH_NUC13LCH/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1@NUC13ANH_NUC13LCH.STP/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1@00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1@WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1@WS_ME_TALL_ASSY_ASM_1_ASM_1.STP/WS_TALL_MID_FRAME_NEW_1_1.STP-1@WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STPPX -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\WS_TALL_MID_FRAME_NEW_1_1.STP.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???cElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/SolidStateRelay-1@Elec_Box_AssemP? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\SolidStateRelay.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???\Elec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/100AFuse-1@Elec_Box_AssemP? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\100AFuse.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???aElec_Box_Assem-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Box_Back_Wall-1@Elec_Box_AssemP -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Box_Back_Wall.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Outer-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)x -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Outer.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/MirrorArm Bracket Assembly-2@Shell & Averaging System/MirrorL bracket-1@MirrorArm Bracket Assemblyt -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Arm Loading CSC V4\V2\MirrorL bracket.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???|Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Chasis C-Channel Lip-1@Shell & Averaging System? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Edge Dams CSC V4\Chasis C-Channel Lip.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Core Mount Front Plate-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Core Mount Front Plate.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-9@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?6 -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-10@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?7 -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Easy To weld Tube Spacer-8@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?5 -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Easy To weld Tube Spacer.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-1@Shell & Averaging SystemM -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/Diff Box V5-1@Diff V5 Assem? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Diff Box V5.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging System Outer Plate V3-2@Shell & Averaging SystemP -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging System Outer Plate V3.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-1@Shell & Averaging System7 -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???uShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/picatinny95mm-2@Shell & Averaging SystemE -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\8. Front of Core Camera Mounts\picatinny95mm.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 01:02:35,825 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\90044A425_Black-Oxide Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-2@Shell & Averaging System3 -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-4@Shell & Averaging System7 -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-3@Shell & Averaging System6 -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6436K14 .5 Shaft Collar-1@Shell & Averaging System0 -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\6436K14 .5 Shaft Collar.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???JRear_Wall_Sheath_Inner-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)w -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Electronics Box CSC V4\Rear_Wall_Sheath_Inner.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-1@Shell & Averaging SystemB -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/8896T69 SS U Bolt 1.375in-2@Shell & Averaging SystemC -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\8896T69 SS U Bolt 1.375in.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-2@Shell & Averaging Systemj -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???zShell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Averaging Shaft V3-3@Shell & Averaging System? -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\2. Composite Sandwitch Chassis\CSC V4\Averaging System CSC V4\Averaging Shaft V3.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Diff V5 Assem-2@Shell & Averaging System/2342K186_Bearing .5 shaft sealed-3@Diff V5 Assem? -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-1@Shell & Averaging SystemZ -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Shell & Averaging System-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/2342K186_Bearing .5 shaft sealed-2@Shell & Averaging System] -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\1. COTS\McMaster\2342K186_Bearing .5 shaft sealed.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 230 - Loaded 51 components for link base_link -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for right_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 01:02:35,841 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-4@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRROR?2 -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEP?- -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRROR? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link right_suspension_member -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for br_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-7@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link br_wheel -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fr_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-6@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROR?X -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fr_wheel -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for averaging_bar from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Old Averaging Bar (Modified)-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\Old Averaging Bar (Modified).SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/92981A220_Alloy Steel Shoulder Screws-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\92981A220_Alloy Steel Shoulder Screws.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube-1@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube.SLDPRT -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 230 - Loaded 5 components for link averaging_bar -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for left_suspension_member from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,856 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?. -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CENTER LEG [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CENTER LEG [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?2 -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)? -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2@A- POST BOND SUSPENSION (1)?( -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- SIDE LEGS [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,872 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-30 01:02:35,887 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 01:02:35,887 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-30 01:02:35,887 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 01:02:35,887 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPE- -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Gearbox Casing-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox Casing.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF???? Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF?????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/3 Stage HD - 57 Sport-1@Gearbox-Wheel Assembly - MIRROR/3 Stage HD - 57 Sport.STEP-1@3 Stage HD - 57 Sport/am-3765 - 57 Sport Motor Block.STEP-1@3 Stage HD - 57 Sport.STEPD- -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\TempUserTemp\swx15124\IC~~\am-3765 - 57 Sport Motor Block.STEP.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORD2 -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORD -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/REV-21-1651.step-1@Gearbox-Wheel Assembly - MIRRORE2 -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Gearbox and Motor\REV-21-1651.step.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Bonding Tube-1@Gearbox-Wheel Assembly - MIRRORE -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Bonding Tube.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?) -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- CORE ATTACHMENT [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A- POST BOND SUSPENSION (1)-3@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1@A- POST BOND SUSPENSION (1)?3 -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\02. SUSPENSION MEMBERS\01. POST BOND DESIGN\P- AXIS PLATE [POST BOND SUSPENSION] (1).SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/6045N122_Low-Carbon Steel Round Tube 2-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\6045N122_Low-Carbon Steel Round Tube 2.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\96144A239_Fine-Thread Alloy Steel Socket Head Screw.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/94645A111_High-Strength Steel Nylon-Insert Locknut-2@A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)?? -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\3. Composite Chassis & Suspension\5. Averaging System Redesigns\1. Front Averaging Bar\94645A111_High-Strength Steel Nylon-Insert Locknut.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 230 - Loaded 20 components for link left_suspension_member -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for bl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-1@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRRORDX -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link bl_wheel -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 221 - Loading SolidWorks components for fl_wheel from C:\Users\David\Documents\ASTRA BILT\01. MECHANICAL 2025-2026\01. CORE ROVER\00. CORE ROVER ASSEMBLY\POST BOND SUSPENSION\A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 245 - Loading component with PID PF????Gearbox-Wheel Assembly - MIRROR-2@A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1)/Updated Wheel Starboard-1@Gearbox-Wheel Assembly - MIRROREX -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 254 - Successfully loaded component C:\Users\David\Documents\ASTRA BILT\03. LEGACY\1. Mechanical 2024-2025\1. CORE ROVER\6. Compressed Drivetrain\Gearbox Assembly\Updated Wheel Starboard.SLDPRT -2025-09-30 01:02:35,888 INFO CommonSwOperations.cs: 230 - Loaded 1 components for link fl_wheel -2025-09-30 01:02:37,284 INFO SwAddin.cs: 344 - Showing property manager -2025-09-30 01:02:43,499 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 01:02:48,384 INFO ExportPropertyManager.cs: 1018 - OnComboboxSelectionChanged called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 01:02:51,897 INFO ExportPropertyManager.cs: 422 - Configuration saved -2025-09-30 01:02:51,914 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.6591330599454964E-060.10957196942132218-0.0865730790868248rpytrue000originfalsefalsevaluetrue75.38553911024465massfalseixxtrue2.4001992795671661ixytrue0.00011623742466712062ixztrue-0.0015611401376277457iyytrue2.0513865858339093iyztrue0.0055915551871194976izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203448629581968-0.094669634292892990.29528781555519346rpytrue000originfalsefalsevaluetrue1.7680515785319755massfalseixxtrue0.0058416782325832819ixytrue0.00021190700411912095ixztrue2.5225188524254267E-08iyytrue0.0068472827239013613iyztrue1.4957244240372892E-06izztrue0.0021448075862501538inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisAutomatically Generatelinktruenametruebr_wheelxyztrue-0.047601349745956978-1.0980108849922843E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605615massfalseixxtrue0.11546820921502547ixytrue7.1976727110259342E-10ixztrue-2.9060340642419872E-10iyytrue0.064706824634146787iyztrue7.1666974435849462E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291300923471681E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644385ixytrue7.2042494408480529E-10ixztrue-2.908003802532643E-10iyytrue0.0647068246345494iyztrue7.1667020108847181E-07izztrue0.063246458718483042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.17122205462555E-100.0103345512905195226.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305885000188E-11ixztrue-1.0050971599711016E-11iyytrue0.023692179851896412iyztrue1.5403213545380754E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29528890483070291-0.09468265717200270.035203448612943222rpytrue000originfalsefalsevaluetrue1.7680515828218952massfalseixxtrue0.0021448075806859038ixytrue-1.495609983178101E-06ixztrue-2.516212300397192E-08iyytrue0.006847282730103251iyztrue0.00021190718895972162izztrue0.0058416782330929637inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisAutomatically Generatelinktruenametruebl_wheelxyztrue-0.047601349747098287-1.0982782072677111E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274106014massfalseixxtrue0.11546820921307203ixytrue7.205857542983549E-10ixztrue-2.9085930408666472E-10iyytrue0.064706824633587651iyztrue7.1666914106959141E-07izztrue0.063246458714804388inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792203462211E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.7417579277055113massfalseixxtrue0.11546820921687724ixytrue7.20541992781926E-10ixztrue-2.9087483733328303E-10iyytrue0.0647068246346634iyztrue7.1667036964477571E-07izztrue0.063246458718970042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-30 01:02:56,122 INFO ExportHelperExtension.cs: 347 - Creating joint right_suspension_member -2025-09-30 01:02:56,309 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child right_suspension_member failed -2025-09-30 01:02:58,163 INFO ExportHelperExtension.cs: 347 - Creating joint br_wheel -2025-09-30 01:02:58,335 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child br_wheel failed -2025-09-30 01:03:00,079 INFO ExportHelperExtension.cs: 347 - Creating joint fr_wheel -2025-09-30 01:03:00,268 WARN ExportHelperExtension.cs: 351 - Creating joint from parent right_suspension_member to child fr_wheel failed -2025-09-30 01:03:01,666 INFO ExportHelperExtension.cs: 347 - Creating joint averaging_bar -2025-09-30 01:03:01,823 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child averaging_bar failed -2025-09-30 01:03:02,184 INFO ExportHelperExtension.cs: 347 - Creating joint left_suspension_member -2025-09-30 01:03:02,341 WARN ExportHelperExtension.cs: 351 - Creating joint from parent base_link to child left_suspension_member failed -2025-09-30 01:03:03,786 INFO ExportHelperExtension.cs: 347 - Creating joint bl_wheel -2025-09-30 01:03:03,935 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child bl_wheel failed -2025-09-30 01:03:05,309 INFO ExportHelperExtension.cs: 347 - Creating joint fl_wheel -2025-09-30 01:03:05,451 WARN ExportHelperExtension.cs: 351 - Creating joint from parent left_suspension_member to child fl_wheel failed -2025-09-30 01:03:06,912 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:03:06,912 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:03:06,912 INFO ExportHelperExtension.cs: 1145 - Found 8 features of type [CoordSys] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:03:06,912 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 01:03:06,912 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 01:03:06,912 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Shell & Averaging System-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Shell & Averaging System-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Elec_Box_Assem-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Elec_Box_Assem-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Inner-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:03:06,928 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-1 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-1 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Motor and 6 pin connector mount-2 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Motor and 6 pin connector mount-2 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:03:06,940 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:03:06,945 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:03:06,945 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Rear_Wall_Sheath_Outer-2 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [CoordSys] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [CoordSys] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1136 - Found 124 in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1145 - Found 7 features of type [RefAxis] in A - CORE ROVER WITH PBS [FULL ROVER ASSEMBLY] (1).SLDASM -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1148 - Proceeding through assembly components -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1160 - 17 components to check -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-2 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Shell & Averaging System-1 -2025-09-30 01:03:06,960 INFO ExportHelperExtension.cs: 1136 - Found 421 in Shell & Averaging System-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Shell & Averaging System-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Elec_Box_Assem-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 268 in Elec_Box_Assem-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Elec_Box_Assem-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Inner-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Inner-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-4 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 57 in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A- POST BOND SUSPENSION (1)-3 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-6 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Motor and 6 pin connector mount-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 47 in Motor and 6 pin connector mount-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Motor and 6 pin connector mount-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 107 in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Rear_Wall_Sheath_Outer-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 32 in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Rear_Wall_Sheath_Outer-2 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1136 - Found 29 in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:03:06,975 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Inside Motor and 6 pin connector mount plate-1 -2025-09-30 01:03:06,991 INFO ExportHelperExtension.cs: 1125 - Retrieving features of type [RefAxis] from Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:03:06,992 INFO ExportHelperExtension.cs: 1136 - Found 68 in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:03:06,992 INFO ExportHelperExtension.cs: 1145 - Found 0 features of type [RefAxis] in Gearbox-Wheel Assembly - MIRROR-7 -2025-09-30 01:03:07,023 INFO ExportPropertyManager.cs: 1142 - AfterClose called. This method no longer throws an Exception. It just silently does nothing. Ok, except for this logging message -2025-09-30 01:04:15,253 INFO AssemblyExportForm.cs: 253 - Completing URDF export -2025-09-30 01:04:15,269 INFO ConfigurationSerialization.cs: 276 - URDF Configuration found -nametruebase_linkxyztrue-6.6591330599454964E-060.10957196942132218-0.0865730790868248rpytrue000originfalsefalsevaluetrue75.38553911024465massfalseixxtrue2.4001992795671661ixytrue0.00011623742466712062ixztrue-0.0015611401376277457iyytrue2.0513865858339093iyztrue0.0055915551871194976izztrue4.2653726815557453inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruetypetruexyztrue000rpytrue000originfalsefalselinktrueparenttruelinktruechildtruexyztrue000axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseOrigin_globallinktruenametrueright_suspension_memberxyztrue0.035203448629581968-0.094669634292892990.29528781555519346rpytrue000originfalsefalsevaluetrue1.7680515785319755massfalseixxtrue0.0058416782325832819ixytrue0.00021190700411912095ixztrue2.5225188524254267E-08iyytrue0.0068472827239013613iyztrue1.4957244240372892E-06izztrue0.0021448075862501538inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueright_suspension_jointtypetruerevolutexyztrue-0.32482-0.26789-0.18459rpytrue1.570803.1416originfalsefalselinktruebase_linkparenttruelinktrueright_suspension_memberchildtruexyztrue-100axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse1offsetfalse0mimicfalsejointfalseright_suspension_axisOrigin_right_suspension_manuallinktruenametruebr_wheelxyztrue-0.047601349745956978-1.0980108849922843E-086.1284547436812886E-09rpytrue000originfalsefalsevaluetrue5.7417579275605615massfalseixxtrue0.11546820921502547ixytrue7.1976727110259342E-10ixztrue-2.9060340642419872E-10iyytrue0.064706824634146787iyztrue7.1666974435849462E-07izztrue0.0632464587169257inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebr_wheel_axistypetruecontinuousxyztrue0.13568550002800012-0.141390699039643080.71479587445434367rpytrue0.52965498126433100originfalsefalselinktrueright_suspension_memberparenttruelinktruebr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebr_wheel_axisOrigin_br_wheel_axislinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAABYAAAAfalsefalsenametruefr_wheelxyztrue-0.047601349745076293-1.098223062490078E-086.1291300923471681E-09rpytrue000originfalsefalsevaluetrue5.7417579276729223massfalseixxtrue0.11546820921644385ixytrue7.2042494408480529E-10ixztrue-2.908003802532643E-10iyytrue0.0647068246345494iyztrue7.1667020108847181E-07izztrue0.063246458718483042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefr_wheel_jointtypetruecontinuousxyztrue0.13568550002799978-0.14139069903964319-0.12195987445434353rpytrue1.5768525324609400originfalsefalselinktrueright_suspension_memberparenttruelinktruefr_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefr_wheel_axisOrigin_fr_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAAC4AAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAN8AAAAzAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAA3wAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAOYAAAAYAAAAUEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADmAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADYAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA5gAAABkAAAA=UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAOYAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA5gAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAO8AAAAYAAAAUEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQA0AEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADfAAAAHQAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAADvAAAAMgAAAA==UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAA7wAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0ANwBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAO8AAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADcAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAA7wAAABkAAAA=UEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAACxAQAAUEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMQBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAAC1AQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAK0BAAA=falsefalsenametrueaveraging_barxyztrue5.17122205462555E-100.0103345512905195226.32630586805405E-10rpytrue000originfalsefalsevaluetrue0.87223051684186359massfalseixxtrue0.00010223447866828818ixytrue1.2617305885000188E-11ixztrue-1.0050971599711016E-11iyytrue0.023692179851896412iyztrue1.5403213545380754E-11izztrue0.023657700070946881inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueaveraging_bar_axistypetruerevolutexyztrue0-0.23362-0.0508rpytrue0-0.0060774-3.1416originfalsefalselinktruebase_linkparenttruelinktrueaveraging_barchildtruexyztrue0-10axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtrueleft_suspension_jointmultiplierfalse-1offsetfalse0mimicfalsejointfalseaveraging_bar_axisOrigin_averaging_bar_axislinktruefalseUEYAAAUAAAD//v+8QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ATwBsAGQAIABBAHYAZQByAGEAZwBpAG4AZwAgAEIAYQByACAAKABNAG8AZABpAGYAaQBlAGQAKQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAGAAAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAyQEAAA==UEYAAAUAAAD//v/FQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAyADkAOAAxAEEAMgAyADAAXwBBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAGgAbwB1AGwAZABlAHIAIABTAGMAcgBlAHcAcwAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAggEAAA==UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAMwBAAA=UEYAAAUAAAD//v/EQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJUBAAA=falsefalsenametrueleft_suspension_memberxyztrue0.29528890483070291-0.09468265717200270.035203448612943222rpytrue000originfalsefalsevaluetrue1.7680515828218952massfalseixxtrue0.0021448075806859038ixytrue-1.495609983178101E-06ixztrue-2.516212300397192E-08iyytrue0.006847282730103251iyztrue0.00021190718895972162izztrue0.0058416782330929637inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue1111colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametrueleft_suspension_jointtypetruerevolutexyztrue0.32482-0.26789-0.18459rpytrue1.570801.5708originfalsefalselinktruebase_linkparenttruelinktrueleft_suspension_memberchildtruexyztrue00-1axisfalselowertrue-0.38uppertrue0.38efforttrue0velocitytrue0limittruerisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalseleft_suspension_axisOrigin_left_suspension_manuallinktruenametruebl_wheelxyztrue-0.047601349747098287-1.0982782072677111E-086.129402263521655E-09rpytrue000originfalsefalsevaluetrue5.7417579274106014massfalseixxtrue0.11546820921307203ixytrue7.205857542983549E-10ixztrue-2.9085930408666472E-10iyytrue0.064706824633587651iyztrue7.1666914106959141E-07izztrue0.063246458714804388inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruebl_wheel_jointtypetruecontinuousxyztrue0.71479587445434378-0.141390699039643130.13568550002799828rpytrue1.57685253246094-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruebl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsebl_wheel_axisOrigin_bl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAABYAAAAfalsefalsenametruefl_wheelxyztrue-0.047601349744811339-1.0982792203462211E-086.1293304876031129E-09rpytrue000originfalsefalsevaluetrue5.7417579277055113massfalseixxtrue0.11546820921687724ixytrue7.20541992781926E-10ixztrue-2.9087483733328303E-10iyytrue0.0647068246346634iyztrue7.1667036964477571E-07izztrue0.063246458718970042inertiafalseinertialfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruenametruergbatrue0.7921568627450980.819607843137254880.933333333333333351colorfalsefilenametruetexturefalsematerialfalsevisualfalsexyztrue000rpytrue000originfalsefalsefilenametruemeshfalsegeometrytruecollisionfalsenametruefl_wheel_jointtypetruecontinuousxyztrue-0.12195987445434364-0.141390699039643190.13568550002799851rpytrue0.529654981264331-1.57079632679489660originfalsefalselinktrueleft_suspension_memberparenttruelinktruefl_wheelchildtruexyztrue100axisfalselowerfalseupperfalseefforttruevelocitytruelimitfalserisingfalsefallingfalsecalibrationfalsedampingfalsefrictionfalsedynamicsfalsesoft_upper_limitfalsesoft_lower_limitfalsek_positionfalsek_velocitytruesafety_controllerfalsejointtruemultiplierfalseoffsetfalsemimicfalsejointfalsefl_wheel_axisOrigin_fl_wheel_jointlinktruefalseUEYAAAUAAAD//v+NRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AVQBwAGQAYQB0AGUAZAAgAFcAaABlAGUAbAAgAFMAdABhAHIAYgBvAGEAcgBkAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAABYAAAAfalsefalsefalseUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADEAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAAC4AAAA=UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMARQBOAFQARQBSACAATABFAEcAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAYAAAAUEYAAAUAAAD//v+jQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEwARQBHACAAQQBUAFQAQQBDAEgATQBFAE4AVAAgAEMARgAgAEMATwBWAEUAUgAgAFsAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOAF0AIAAoADEAKQAtADIAQABBAC0AIABQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAygAAADIAAAA=UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAHQAAAA==UEYAAAUAAAD//v+VQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAFMASQBEAEUAIABMAEUARwBTACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMgBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKAAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEUAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEUAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMgBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARQAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+ERwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARwBlAGEAcgBiAG8AeAAgAEMAYQBzAGkAbgBnAC0AMQBAAEcAZQBhAHIAYgBvAHgALQBXAGgAZQBlAGwAIABBAHMAcwBlAG0AYgBsAHkAIAAtACAATQBJAFIAUgBPAFIABAAAABAAAAABAAAAAgAAAEQAAAAYAAAAUEYAAAUAAAD//v//DQFHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AWABYAFgAWAAgAC0AIAA1ADcAIABTAHAAbwByAHQAIAAzACAAUwB0AGEAZwBlACAAUgBpAG4AZwAgAEcAZQBhAHIAIABIAG8AdQBzAGkAbgBnAC4AUwBUAEUAUAAtADEAQAAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAuAFMAVABFAFAABAAAABAAAAABAAAABAAAAEQAAAAtAAAAGAAAABwAAAA=UEYAAAUAAAD//v///wBHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAzACAAUwB0AGEAZwBlACAASABEACAALQAgADUANwAgAFMAcABvAHIAdAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAC8AMwAgAFMAdABhAGcAZQAgAEgARAAgAC0AIAA1ADcAIABTAHAAbwByAHQALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC8AYQBtAC0AMwA3ADYANQAgAC0AIAA1ADcAIABTAHAAbwByAHQAIABNAG8AdABvAHIAIABCAGwAbwBjAGsALgBTAFQARQBQAC0AMQBAADMAIABTAHQAYQBnAGUAIABIAEQAIAAtACAANQA3ACAAUwBwAG8AcgB0AC4AUwBUAEUAUAAEAAAAEAAAAAEAAAAEAAAARAAAAC0AAAAYAAAAHgAAAA==UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABEAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARAAAABkAAAA=UEYAAAUAAAD//v+GRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AUgBFAFYALQAyADEALQAxADYANQAxAC4AcwB0AGUAcAAtADEAQABHAGUAYQByAGIAbwB4AC0AVwBoAGUAZQBsACAAQQBzAHMAZQBtAGIAbAB5ACAALQAgAE0ASQBSAFIATwBSAAQAAAAQAAAAAQAAAAIAAABFAAAAMgAAAA==UEYAAAUAAAD//v+CRwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQgBvAG4AZABpAG4AZwAgAFQAdQBiAGUALQAxAEAARwBlAGEAcgBiAG8AeAAtAFcAaABlAGUAbAAgAEEAcwBzAGUAbQBiAGwAeQAgAC0AIABNAEkAUgBSAE8AUgAEAAAAEAAAAAEAAAACAAAARQAAABkAAAA=UEYAAAUAAAD//v+bQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEMATwBSAEUAIABBAFQAVABBAEMASABNAEUATgBUACAAWwBQAE8AUwBUACAAQgBPAE4ARAAgAFMAVQBTAFAARQBOAFMASQBPAE4AXQAgACgAMQApAC0AMQBAAEEALQAgAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgAgACgAMQApAAQAAAAQAAAAAQAAAAIAAADKAAAAKQAAAA==UEYAAAUAAAD//v+WQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkALQAzAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAFAALQAgAEEAWABJAFMAIABQAEwAQQBUAEUAIABbAFAATwBTAFQAIABCAE8ATgBEACAAUwBVAFMAUABFAE4AUwBJAE8ATgBdACAAKAAxACkALQAxAEAAQQAtACAAUABPAFMAVAAgAEIATwBOAEQAIABTAFUAUwBQAEUATgBTAEkATwBOACAAKAAxACkABAAAABAAAAABAAAAAgAAAMoAAAAzAAAAUEYAAAUAAAD//v/GQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ANgAwADQANQBOADEAMgAyAF8ATABvAHcALQBDAGEAcgBiAG8AbgAgAFMAdABlAGUAbAAgAFIAbwB1AG4AZAAgAFQAdQBiAGUAIAAyAC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADQAQAAUEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA2ADEANAA0AEEAMgAzADkAXwBGAGkAbgBlAC0AVABoAHIAZQBhAGQAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8BAAA=UEYAAAUAAAD//v/SQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQA0ADYANAA1AEEAMQAxADEAXwBIAGkAZwBoAC0AUwB0AHIAZQBuAGcAdABoACAAUwB0AGUAZQBsACAATgB5AGwAbwBuAC0ASQBuAHMAZQByAHQAIABMAG8AYwBrAG4AdQB0AC0AMgBAAEEAIAAtACAAQQBWAEUAUgBBAEcASQBOAEcAIABCAEEAUgAgAEEAUwBTAEUATQBCAEwAWQAgAFsAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwBdACAAKAAxACkABAAAABAAAAABAAAAAgAAALAAAADRAQAAfalsefalsefalseUEYAAAUAAAD//v+cUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAUwBDACAAUwBoAGUAbABsACAAQQBzAHMAZQBtAGIAbAB5AC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAC8AQwBTAEMAIABWADQAIABTAGgAZQBsAGwALQAxAEAAQwBTAEMAIABTAGgAZQBsAGwAIABBAHMAcwBlAG0AYgBsAHkABAAAABAAAAABAAAAAwAAABgAAAAYAAAAGQAAAA==UEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACoAAAAUEYAAAUAAAD//v9TTQBvAHQAbwByACAAYQBuAGQAIAA2ACAAcABpAG4AIABjAG8AbgBuAGUAYwB0AG8AcgAgAG0AbwB1AG4AdAAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACfAAAAUEYAAAUAAAD//v9gSQBuAHMAaQBkAGUAIABNAG8AdABvAHIAIABhAG4AZAAgADYAIABwAGkAbgAgAGMAbwBuAG4AZQBjAHQAbwByACAAbQBvAHUAbgB0ACAAcABsAGEAdABlAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkABAAAABAAAAABAAAAAQAAAKMAAAA=UEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABCAG8AeAAgAEIAYQBjAGsAaQBuAGcAIABQAGwAYQB0AGUAIABWADIALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABXAwAAUEYAAAUAAAD//v+PUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0AIABPAHUAdABlAHIAIABQAGwAYQB0AGUAIABCAGEAYwBrAGkAbgBnACAAVgAxAC0AMQBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAHQEAAA==UEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAAYAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAbAAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAEEAcgBtACAAQgBvAGwAdABzAC0AMQBAAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAgAFIAaQBnAGgAdAAgAFYAMwAEAAAAEAAAAAEAAAADAAAAGAAAAG8DAAA3AAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAGAAAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEwAZQBmAHQAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAACgAAAA=UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEYAcgBvAG4AdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwAAAA==UEYAAAUAAAD//v9iRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAFIAaQBnAGgAdABfAFcAYQBsAGwALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAIwAAAA==UEYAAAUAAAD//v97RQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBQAE8ARQAgAFMAdwBpAHQAYwBoACAAKABNAGUAYQBzAHUAcgBlAGQAIAB3AGkAdABoACAAaABvAGwAZQAgAHAAYQB0AHQAZQByAG4AKQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAAAWBAAAUEYAAAUAAAD//v+ARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBFAHQAaABlAHIAbgBlAHQAIABTAHcAaQB0AGMAaAAgACgATQBlAGEAcwB1AHIAZQBkACAAdwBpAHQAaAAgAGgAbwBsAGUAIABwAGEAdAB0AGUAcgBuACkALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAHwQAAA==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UEYAAAUAAAD//v9jRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBTAG8AbABpAGQAUwB0AGEAdABlAFIAZQBsAGEAeQAtADEAQABFAGwAZQBjAF8AQgBvAHgAXwBBAHMAcwBlAG0ABAAAABAAAAABAAAAAgAAAFAAAACTBAAAUEYAAAUAAAD//v9cRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwAxADAAMABBAEYAdQBzAGUALQAxAEAARQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAAQAAAAQAAAAAQAAAAIAAABQAAAAlwQAAA==UEYAAAUAAAD//v9hRQBsAGUAYwBfAEIAbwB4AF8AQQBzAHMAZQBtAC0AMQBAAEEAIAAtACAAQwBPAFIARQAgAFIATwBWAEUAUgAgAFcASQBUAEgAIABQAEIAUwAgAFsARgBVAEwATAAgAFIATwBWAEUAUgAgAEEAUwBTAEUATQBCAEwAWQBdACAAKAAxACkALwBCAG8AeABfAEIAYQBjAGsAXwBXAGEAbABsAC0AMQBAAEUAbABlAGMAXwBCAG8AeABfAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAACAAAAUAAAABkAAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADIAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAACQAAAAUEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAE8AdQB0AGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB4AAAAUEYAAAUAAAD//v+vUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAvAE0AaQByAHIAbwByAEwAIABiAHIAYQBjAGsAZQB0AC0AMQBAAE0AaQByAHIAbwByAEEAcgBtACAAQgByAGEAYwBrAGUAdAAgAEEAcwBzAGUAbQBiAGwAeQAEAAAAEAAAAAEAAAADAAAAGAAAAHQDAAAYAAAAUEYAAAUAAAD//v98UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEMAaABhAHMAaQBzACAAQwAtAEMAaABhAG4AbgBlAGwAIABMAGkAcAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAOgDAAA=UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADEAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAlgAAAA==UEYAAAUAAAD//v+2QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AQwBvAHIAZQAgAE0AbwB1AG4AdAAgAEYAcgBvAG4AdAAgAFAAbABhAHQAZQAtADIAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAAqwAAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAJsAAAA=UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA5AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADYBAAA=UEYAAAUAAAD//v+5QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQAxADAAQABBACAALQAgAEEAVgBFAFIAQQBHAEkATgBHACAAQgBBAFIAIABBAFMAUwBFAE0AQgBMAFkAIABbAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAXQAgACgAMQApAAQAAAAQAAAAAQAAAAIAAACwAAAANwEAAA==UEYAAAUAAAD//v+4QQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8ARQBhAHMAeQAgAFQAbwAgAHcAZQBsAGQAIABUAHUAYgBlACAAUwBwAGEAYwBlAHIALQA4AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAADUBAAA=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UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAzAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM8AAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQA0AEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAANAAAAA=UEYAAAUAAAD//v/TQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAC8AOQAwADAANAA0AEEANAAyADUAXwBCAGwAYQBjAGsALQBPAHgAaQBkAGUAIABBAGwAbABvAHkAIABTAHQAZQBlAGwAIABTAG8AYwBrAGUAdAAgAEgAZQBhAGQAIABTAGMAcgBlAHcALQAyAEAAQQAgAC0AIABBAFYARQBSAEEARwBJAE4ARwAgAEIAQQBSACAAQQBTAFMARQBNAEIATABZACAAWwBDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTAF0AIAAoADEAKQAEAAAAEAAAAAEAAAACAAAAsAAAAM4AAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADMDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADQAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADcDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADMAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADYDAAA=UEYAAAUAAAD//v9/UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADYANAAzADYASwAxADQAIAAuADUAIABTAGgAYQBmAHQAIABDAG8AbABsAGEAcgAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAADADAAA=UEYAAAUAAAD//v9KUgBlAGEAcgBfAFcAYQBsAGwAXwBTAGgAZQBhAHQAaABfAEkAbgBuAGUAcgAtADEAQABBACAALQAgAEMATwBSAEUAIABSAE8AVgBFAFIAIABXAEkAVABIACAAUABCAFMAIABbAEYAVQBMAEwAIABSAE8AVgBFAFIAIABBAFMAUwBFAE0AQgBMAFkAXQAgACgAMQApAAQAAAAQAAAAAQAAAAEAAAB3AAAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAxAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABCAgAAUEYAAAUAAAD//v+BUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADgAOAA5ADYAVAA2ADkAIABTAFMAIABVACAAQgBvAGwAdAAgADEALgAzADcANQBpAG4ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ABAAAABAAAAABAAAAAgAAABgAAABDAgAAUEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMgBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAagAAAA==UEYAAAUAAAD//v96UwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEEAdgBlAHIAYQBnAGkAbgBnACAAUwBoAGEAZgB0ACAAVgAzAC0AMwBAAFMAaABlAGwAbAAgACYAIABBAHYAZQByAGEAZwBpAG4AZwAgAFMAeQBzAHQAZQBtAAQAAAAQAAAAAQAAAAIAAAAYAAAAygAAAA==UEYAAAUAAAD//v+mUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvAEQAaQBmAGYAIABWADUAIABBAHMAcwBlAG0ALQAyAEAAUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALwAyADMANAAyAEsAMQA4ADYAXwBCAGUAYQByAGkAbgBnACAALgA1ACAAcwBoAGEAZgB0ACAAcwBlAGEAbABlAGQALQAzAEAARABpAGYAZgAgAFYANQAgAEEAcwBzAGUAbQAEAAAAEAAAAAEAAAADAAAAGAAAAI4CAAAbAAAAUEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADEAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAFoAAAA=UEYAAAUAAAD//v+IUwBoAGUAbABsACAAJgAgAEEAdgBlAHIAYQBnAGkAbgBnACAAUwB5AHMAdABlAG0ALQAxAEAAQQAgAC0AIABDAE8AUgBFACAAUgBPAFYARQBSACAAVwBJAFQASAAgAFAAQgBTACAAWwBGAFUATABMACAAUgBPAFYARQBSACAAQQBTAFMARQBNAEIATABZAF0AIAAoADEAKQAvADIAMwA0ADIASwAxADgANgBfAEIAZQBhAHIAaQBuAGcAIAAuADUAIABzAGgAYQBmAHQAIABzAGUAYQBsAGUAZAAtADIAQABTAGgAZQBsAGwAIAAmACAAQQB2AGUAcgBhAGcAaQBuAGcAIABTAHkAcwB0AGUAbQAEAAAAEAAAAAEAAAACAAAAGAAAAF0AAAA=falsefalse -2025-09-30 01:04:26,581 INFO AssemblyExportForm.cs: 309 - Saving URDF package to C:\Users\David\Desktop\URDF\core_rover_description -2025-09-30 01:04:26,581 INFO ExportHelper.cs: 148 - Beginning the export process -2025-09-30 01:04:26,581 INFO ExportHelper.cs: 154 - Creating package directories with name core_rover_description and save path C:\Users\David\Desktop\URDF -2025-09-30 01:04:27,975 INFO ExportHelper.cs: 163 - Creating CMakeLists.txt at C:\Users\David\Desktop\URDF\core_rover_description\CMakeLists.txt -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 167 - Creating joint names config at C:\Users\David\Desktop\URDF\core_rover_description\config\joint_names_core_rover_description.yaml -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 171 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-30 01:04:28,006 INFO PackageXMLWriter.cs: 21 - Creating package.xml at C:\Users\David\Desktop\URDF\core_rover_description\package.xml -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 178 - Creating RVIZ launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 183 - Creating Gazebo launch file in C:\Users\David\Desktop\URDF\core_rover_description\launch\ -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 188 - Saving existing STL preferences -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 568 - Saving users preferences -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 191 - Modifying STL preferences -2025-09-30 01:04:28,006 INFO ExportHelper.cs: 582 - Setting STL preferences -2025-09-30 01:04:28,022 INFO ExportHelper.cs: 197 - Found 5 hidden components Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-2, Shell & Averaging System-1/CSC Shell Assembly-1/8492A154 .25in Drill Bushing-1, Shell & Averaging System-1/Arm Bracket Bonding Jig-1, Shell & Averaging System-1/Bordered Lid V1 Multibody-1, Shell & Averaging System-1/Front Camera Cluster V2-1 -2025-09-30 01:04:28,022 INFO ExportHelper.cs: 198 - Hiding all components -2025-09-30 01:04:28,798 INFO ExportHelper.cs: 205 - Beginning individual files export -2025-09-30 01:04:28,798 INFO ExportHelper.cs: 271 - Exporting link: base_link -2025-09-30 01:04:28,798 INFO ExportHelper.cs: 273 - Link base_link has 3 children -2025-09-30 01:04:28,812 INFO ExportHelper.cs: 271 - Exporting link: right_suspension_member -2025-09-30 01:04:28,812 INFO ExportHelper.cs: 273 - Link right_suspension_member has 2 children -2025-09-30 01:04:28,812 INFO ExportHelper.cs: 271 - Exporting link: br_wheel -2025-09-30 01:04:28,812 INFO ExportHelper.cs: 273 - Link br_wheel has 0 children -2025-09-30 01:04:28,812 INFO ExportHelper.cs: 435 - br_wheel: Exporting STL with coordinate frame Origin_br_wheel_axis -2025-09-30 01:04:28,812 INFO ExportHelper.cs: 440 - br_wheel: Reference geometry name -2025-09-30 01:04:28,906 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\br_wheel.STL -2025-09-30 01:04:30,062 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:30,062 INFO ExportHelper.cs: 271 - Exporting link: fr_wheel -2025-09-30 01:04:30,062 INFO ExportHelper.cs: 273 - Link fr_wheel has 0 children -2025-09-30 01:04:30,062 INFO ExportHelper.cs: 435 - fr_wheel: Exporting STL with coordinate frame Origin_fr_wheel_joint -2025-09-30 01:04:30,062 INFO ExportHelper.cs: 440 - fr_wheel: Reference geometry name -2025-09-30 01:04:30,167 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fr_wheel.STL -2025-09-30 01:04:31,255 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:31,255 INFO ExportHelper.cs: 435 - right_suspension_member: Exporting STL with coordinate frame Origin_right_suspension_manual -2025-09-30 01:04:31,255 INFO ExportHelper.cs: 440 - right_suspension_member: Reference geometry name -2025-09-30 01:04:31,726 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\right_suspension_member.STL -2025-09-30 01:04:33,412 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:33,412 INFO ExportHelper.cs: 271 - Exporting link: averaging_bar -2025-09-30 01:04:33,416 INFO ExportHelper.cs: 273 - Link averaging_bar has 0 children -2025-09-30 01:04:33,416 INFO ExportHelper.cs: 435 - averaging_bar: Exporting STL with coordinate frame Origin_averaging_bar_axis -2025-09-30 01:04:33,416 INFO ExportHelper.cs: 440 - averaging_bar: Reference geometry name -2025-09-30 01:04:33,491 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\averaging_bar.STL -2025-09-30 01:04:33,946 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:33,946 INFO ExportHelper.cs: 271 - Exporting link: left_suspension_member -2025-09-30 01:04:33,948 INFO ExportHelper.cs: 273 - Link left_suspension_member has 2 children -2025-09-30 01:04:33,948 INFO ExportHelper.cs: 271 - Exporting link: bl_wheel -2025-09-30 01:04:33,948 INFO ExportHelper.cs: 273 - Link bl_wheel has 0 children -2025-09-30 01:04:33,948 INFO ExportHelper.cs: 435 - bl_wheel: Exporting STL with coordinate frame Origin_bl_wheel_joint -2025-09-30 01:04:33,948 INFO ExportHelper.cs: 440 - bl_wheel: Reference geometry name -2025-09-30 01:04:34,077 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\bl_wheel.STL -2025-09-30 01:04:35,281 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:35,281 INFO ExportHelper.cs: 271 - Exporting link: fl_wheel -2025-09-30 01:04:35,281 INFO ExportHelper.cs: 273 - Link fl_wheel has 0 children -2025-09-30 01:04:35,281 INFO ExportHelper.cs: 435 - fl_wheel: Exporting STL with coordinate frame Origin_fl_wheel_joint -2025-09-30 01:04:35,281 INFO ExportHelper.cs: 440 - fl_wheel: Reference geometry name -2025-09-30 01:04:35,407 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\fl_wheel.STL -2025-09-30 01:04:36,680 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:36,680 INFO ExportHelper.cs: 435 - left_suspension_member: Exporting STL with coordinate frame Origin_left_suspension_manual -2025-09-30 01:04:36,680 INFO ExportHelper.cs: 440 - left_suspension_member: Reference geometry name -2025-09-30 01:04:37,121 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\left_suspension_member.STL -2025-09-30 01:04:38,835 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:38,835 INFO ExportHelper.cs: 435 - base_link: Exporting STL with coordinate frame Origin_global -2025-09-30 01:04:38,835 INFO ExportHelper.cs: 440 - base_link: Reference geometry name -2025-09-30 01:04:41,077 INFO ExportHelper.cs: 448 - Saving STL to C:\Users\David\Desktop\URDF\core_rover_description\meshes\base_link.STL -2025-09-30 01:04:47,025 INFO ExportHelper.cs: 523 - Removing SW header in STL file -2025-09-30 01:04:47,025 INFO ExportHelper.cs: 146 - Showing all components except previously hidden components -2025-09-30 01:05:00,828 INFO ExportHelper.cs: 146 - Resetting STL preferences -2025-09-30 01:05:00,828 INFO ExportHelper.cs: 596 - Returning STL preferences to user preferences -2025-09-30 01:05:00,828 INFO ExportHelper.cs: 229 - Writing URDF file to C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.urdf -2025-09-30 01:05:00,828 INFO CSVImportExport.cs: 32 - Writing CSV file C:\Users\David\Desktop\URDF\core_rover_description\urdf\core_rover_description.csv -2025-09-30 01:05:00,828 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-30 01:05:00,828 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-30 01:05:00,843 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-30 01:05:00,843 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-30 01:05:00,843 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link,Link.Joint.Mimic.joint,Link.Joint.Mimic.multiplier,Link.Joint.Mimic.offset, -2025-09-30 01:05:00,843 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-30 01:05:00,843 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-30 01:05:00,843 ERROR CSVImportExport.cs: 130 - The following columns were not written to the CSV: Link.Joint.ChildLink.link, -2025-09-30 01:05:00,843 INFO ExportHelper.cs: 235 - Copying log file -2025-09-30 01:05:00,843 INFO ExportHelper.cs: 557 - Copying C:\Users\David\sw2urdf_logs\sw2urdf.log to C:\Users\David\Desktop\URDF\core_rover_description\export.log diff --git a/src/core_rover_description/launch/display.launch.py b/src/core_rover_description/launch/display.launch.py deleted file mode 100644 index 14a385a..0000000 --- a/src/core_rover_description/launch/display.launch.py +++ /dev/null @@ -1,117 +0,0 @@ -# Author: Addison Sears-Collins -# Date: September 14, 2021 -# Description: Launch a two-wheeled robot URDF file using Rviz. -# https://automaticaddison.com - -import os -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.conditions import IfCondition, UnlessCondition -from launch.substitutions import Command, LaunchConfiguration -from launch_ros.actions import Node -from launch_ros.substitutions import FindPackageShare -from launch_ros.parameter_descriptions import ParameterValue - -def generate_launch_description(): - - # Set the path to this package. - pkg_share = FindPackageShare(package='core_rover_description').find('core_rover_description') - - # Set the path to the RViz configuration settings - default_rviz_config_path = os.path.join(pkg_share, 'config/rviz_basic_settings.rviz') - - # Set the path to the URDF file - default_urdf_model_path = os.path.join(pkg_share, 'urdf/core_rover_description.urdf') - - ########### YOU DO NOT NEED TO CHANGE ANYTHING BELOW THIS LINE ############## - # Launch configuration variables specific to simulation - gui = LaunchConfiguration('gui') - urdf_model = LaunchConfiguration('urdf_model') - rviz_config_file = LaunchConfiguration('rviz_config_file') - use_robot_state_pub = LaunchConfiguration('use_robot_state_pub') - use_rviz = LaunchConfiguration('use_rviz') - use_sim_time = LaunchConfiguration('use_sim_time') - - # Declare the launch arguments - declare_urdf_model_path_cmd = DeclareLaunchArgument( - name='urdf_model', - default_value=default_urdf_model_path, - description='Absolute path to robot urdf file') - - declare_rviz_config_file_cmd = DeclareLaunchArgument( - name='rviz_config_file', - default_value=default_rviz_config_path, - description='Full path to the RVIZ config file to use') - - declare_use_joint_state_publisher_cmd = DeclareLaunchArgument( - name='gui', - default_value='True', - description='Flag to enable joint_state_publisher_gui') - - declare_use_robot_state_pub_cmd = DeclareLaunchArgument( - name='use_robot_state_pub', - default_value='True', - description='Whether to start the robot state publisher') - - declare_use_rviz_cmd = DeclareLaunchArgument( - name='use_rviz', - default_value='True', - description='Whether to start RVIZ') - - declare_use_sim_time_cmd = DeclareLaunchArgument( - name='use_sim_time', - default_value='True', - description='Use simulation (Gazebo) clock if true') - - # Specify the actions - - # Publish the joint state values for the non-fixed joints in the URDF file. - start_joint_state_publisher_cmd = Node( - condition=UnlessCondition(gui), - package='joint_state_publisher', - executable='joint_state_publisher', - name='joint_state_publisher') - - # A GUI to manipulate the joint state values - start_joint_state_publisher_gui_node = Node( - condition=IfCondition(gui), - package='joint_state_publisher_gui', - executable='joint_state_publisher_gui', - name='joint_state_publisher_gui') - - # Subscribe to the joint states of the robot, and publish the 3D pose of each link. - start_robot_state_publisher_cmd = Node( - condition=IfCondition(use_robot_state_pub), - package='robot_state_publisher', - executable='robot_state_publisher', - parameters=[{'use_sim_time': use_sim_time, - 'robot_description': ParameterValue(Command(['xacro ', urdf_model]), value_type=str)}], - arguments=[default_urdf_model_path]) - - # Launch RViz - start_rviz_cmd = Node( - condition=IfCondition(use_rviz), - package='rviz2', - executable='rviz2', - name='rviz2', - output='screen', - arguments=['-d', rviz_config_file]) - - # Create the launch description and populate - ld = LaunchDescription() - - # Declare the launch options - ld.add_action(declare_urdf_model_path_cmd) - ld.add_action(declare_rviz_config_file_cmd) - ld.add_action(declare_use_joint_state_publisher_cmd) - ld.add_action(declare_use_robot_state_pub_cmd) - ld.add_action(declare_use_rviz_cmd) - ld.add_action(declare_use_sim_time_cmd) - - # Add any actions - ld.add_action(start_joint_state_publisher_cmd) - ld.add_action(start_joint_state_publisher_gui_node) - ld.add_action(start_robot_state_publisher_cmd) - ld.add_action(start_rviz_cmd) - - return ld \ No newline at end of file diff --git a/src/core_rover_description/launch/robot_state_publisher.launch.py b/src/core_rover_description/launch/robot_state_publisher.launch.py deleted file mode 100644 index ed3b87b..0000000 --- a/src/core_rover_description/launch/robot_state_publisher.launch.py +++ /dev/null @@ -1,238 +0,0 @@ -#!/usr/bin/env python3 -""" -Launch RViz visualization for the mycobot robot. - -This launch file sets up the complete visualization environment for the mycobot robot, -including robot state publisher, joint state publisher, and RViz2. It handles loading -and processing of URDF/XACRO files and controller configurations. - -:author: Addison Sears-Collins -:date: November 15, 2024 -""" -import os -from pathlib import Path -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, OpaqueFunction -from launch.conditions import IfCondition, UnlessCondition -from launch.substitutions import Command, LaunchConfiguration, PathJoinSubstitution -from launch_ros.actions import Node -from launch_ros.parameter_descriptions import ParameterValue -from launch_ros.substitutions import FindPackageShare - - -def process_ros2_controllers_config(context): - """Process the ROS 2 controller configuration yaml file before loading the URDF. - - This function reads a template configuration file, replaces placeholder values - with actual configuration, and writes the processed file to both source and - install directories. - - Args: - context: Launch context containing configuration values - - Returns: - list: Empty list as required by OpaqueFunction - """ - - # Get the configuration values - prefix = LaunchConfiguration('prefix').perform(context) - flange_link = LaunchConfiguration('flange_link').perform(context) - robot_name = LaunchConfiguration('robot_name').perform(context) - - home = str(Path.home()) - - # Define both source and install paths - src_config_path = os.path.join( - home, - 'ros2_ws/src/mycobot_ros2/mycobot_moveit_config/config', - robot_name - ) - install_config_path = os.path.join( - home, - 'ros2_ws/install/mycobot_moveit_config/share/mycobot_moveit_config/config', - robot_name - ) - - # Read from source template - template_path = os.path.join(src_config_path, 'ros2_controllers_template.yaml') - with open(template_path, 'r', encoding='utf-8') as file: - template_content = file.read() - - # Create processed content (leaving template untouched) - processed_content = template_content.replace('${prefix}', prefix) - processed_content = processed_content.replace('${flange_link}', flange_link) - - # Write processed content to both source and install directories - for config_path in [src_config_path, install_config_path]: - os.makedirs(config_path, exist_ok=True) - output_path = os.path.join(config_path, 'ros2_controllers.yaml') - with open(output_path, 'w', encoding='utf-8') as file: - file.write(processed_content) - - return [] - - -# Define the arguments for the XACRO file -ARGUMENTS = [ - DeclareLaunchArgument('robot_name', default_value='mycobot_280', - description='Name of the robot'), - DeclareLaunchArgument('prefix', default_value='', - description='Prefix for robot joints and links'), - DeclareLaunchArgument('add_world', default_value='true', - choices=['true', 'false'], - description='Whether to add world link'), - DeclareLaunchArgument('base_link', default_value='base_link', - description='Name of the base link'), - DeclareLaunchArgument('base_type', default_value='g_shape', - description='Type of the base'), - DeclareLaunchArgument('flange_link', default_value='link6_flange', - description='Name of the flange link'), - DeclareLaunchArgument('gripper_type', default_value='adaptive_gripper', - description='Type of the gripper'), - DeclareLaunchArgument('use_camera', default_value='false', - choices=['true', 'false'], - description='Whether to use the RGBD Gazebo plugin for point cloud'), - DeclareLaunchArgument('use_gazebo', default_value='false', - choices=['true', 'false'], - description='Whether to use Gazebo simulation'), - DeclareLaunchArgument('use_gripper', default_value='true', - choices=['true', 'false'], - description='Whether to attach a gripper') -] - - -def generate_launch_description(): - """Generate the launch description for the mycobot robot visualization. - - This function sets up all necessary nodes and parameters for visualizing - the mycobot robot in RViz, including: - - Robot state publisher for broadcasting transforms - - Joint state publisher for simulating joint movements - - RViz for visualization - - Returns: - LaunchDescription: Complete launch description for the visualization setup - """ - # Define filenames - urdf_package = 'core_rover_description' - urdf_filename = 'core_rover_description.urdf' - rviz_config_filename = 'rviz_basic_settings.rviz' - - # Set paths to important files - pkg_share_description = FindPackageShare(urdf_package) - default_urdf_model_path = PathJoinSubstitution( - [pkg_share_description, 'urdf', urdf_filename]) - default_rviz_config_path = PathJoinSubstitution( - [pkg_share_description, 'rviz', rviz_config_filename]) - - # Launch configuration variables - jsp_gui = LaunchConfiguration('jsp_gui') - rviz_config_file = LaunchConfiguration('rviz_config_file') - urdf_model = LaunchConfiguration('urdf_model') - use_jsp = LaunchConfiguration('use_jsp') - use_rviz = LaunchConfiguration('use_rviz') - use_sim_time = LaunchConfiguration('use_sim_time') - - # Declare the launch arguments - declare_jsp_gui_cmd = DeclareLaunchArgument( - name='jsp_gui', - default_value='true', - choices=['true', 'false'], - description='Flag to enable joint_state_publisher_gui') - - declare_rviz_config_file_cmd = DeclareLaunchArgument( - name='rviz_config_file', - default_value=default_rviz_config_path, - description='Full path to the RVIZ config file to use') - - declare_urdf_model_path_cmd = DeclareLaunchArgument( - name='urdf_model', - default_value=default_urdf_model_path, - description='Absolute path to robot urdf file') - - declare_use_jsp_cmd = DeclareLaunchArgument( - name='use_jsp', - default_value='false', - choices=['true', 'false'], - description='Enable the joint state publisher') - - declare_use_rviz_cmd = DeclareLaunchArgument( - name='use_rviz', - default_value='true', - description='Whether to start RVIZ') - - declare_use_sim_time_cmd = DeclareLaunchArgument( - name='use_sim_time', - default_value='false', - description='Use simulation (Gazebo) clock if true') - - robot_description_content = ParameterValue(Command([ - 'xacro', ' ', urdf_model, ' ', - 'robot_name:=', LaunchConfiguration('robot_name'), ' ', - 'prefix:=', LaunchConfiguration('prefix'), ' ', - 'add_world:=', LaunchConfiguration('add_world'), ' ', - 'base_link:=', LaunchConfiguration('base_link'), ' ', - 'base_type:=', LaunchConfiguration('base_type'), ' ', - 'flange_link:=', LaunchConfiguration('flange_link'), ' ', - 'gripper_type:=', LaunchConfiguration('gripper_type'), ' ', - 'use_camera:=', LaunchConfiguration('use_camera'), ' ', - 'use_gazebo:=', LaunchConfiguration('use_gazebo'), ' ', - 'use_gripper:=', LaunchConfiguration('use_gripper') - ]), value_type=str) - - # Subscribe to the joint states of the robot, and publish the 3D pose of each link. - start_robot_state_publisher_cmd = Node( - package='robot_state_publisher', - executable='robot_state_publisher', - name='robot_state_publisher', - output='screen', - parameters=[{ - 'use_sim_time': use_sim_time, - 'robot_description': robot_description_content}]) - - # Publish the joint state values for the non-fixed joints in the URDF file. - start_joint_state_publisher_cmd = Node( - package='joint_state_publisher', - executable='joint_state_publisher', - name='joint_state_publisher', - parameters=[{'use_sim_time': use_sim_time}], - condition=IfCondition(use_jsp)) - - # Depending on gui parameter, either launch joint_state_publisher or joint_state_publisher_gui - start_joint_state_publisher_gui_cmd = Node( - package='joint_state_publisher_gui', - executable='joint_state_publisher_gui', - name='joint_state_publisher_gui', - parameters=[{'use_sim_time': use_sim_time}], - condition=IfCondition(jsp_gui)) - - # Launch RViz - start_rviz_cmd = Node( - condition=IfCondition(use_rviz), - package='rviz2', - executable='rviz2', - output='screen', - arguments=['-d', rviz_config_file], - parameters=[{'use_sim_time': use_sim_time}]) - - # Create the launch description and populate - ld = LaunchDescription(ARGUMENTS) - - # Process the controller configuration before starting nodes - # ld.add_action(OpaqueFunction(function=process_ros2_controllers_config)) - - # Declare the launch options - ld.add_action(declare_jsp_gui_cmd) - ld.add_action(declare_rviz_config_file_cmd) - ld.add_action(declare_urdf_model_path_cmd) - ld.add_action(declare_use_jsp_cmd) - ld.add_action(declare_use_rviz_cmd) - ld.add_action(declare_use_sim_time_cmd) - - # Add any actions - ld.add_action(start_joint_state_publisher_cmd) - ld.add_action(start_joint_state_publisher_gui_cmd) - ld.add_action(start_robot_state_publisher_cmd) - ld.add_action(start_rviz_cmd) - - return ld diff --git a/src/core_rover_description/meshes/averaging_bar.STL b/src/core_rover_description/meshes/averaging_bar.STL deleted file mode 100644 index 617912f..0000000 Binary files a/src/core_rover_description/meshes/averaging_bar.STL and /dev/null differ diff --git a/src/core_rover_description/meshes/base_link.STL b/src/core_rover_description/meshes/base_link.STL deleted file mode 100644 index b040cf4..0000000 Binary files a/src/core_rover_description/meshes/base_link.STL and /dev/null differ diff --git a/src/core_rover_description/meshes/bl_wheel.STL b/src/core_rover_description/meshes/bl_wheel.STL deleted file mode 100644 index 311e88c..0000000 Binary files a/src/core_rover_description/meshes/bl_wheel.STL and /dev/null differ diff --git a/src/core_rover_description/meshes/br_wheel.STL b/src/core_rover_description/meshes/br_wheel.STL deleted file mode 100644 index 24b40dd..0000000 Binary files a/src/core_rover_description/meshes/br_wheel.STL and /dev/null differ diff --git a/src/core_rover_description/meshes/fl_wheel.STL b/src/core_rover_description/meshes/fl_wheel.STL deleted file mode 100644 index e1a8a49..0000000 Binary files a/src/core_rover_description/meshes/fl_wheel.STL and /dev/null differ diff --git a/src/core_rover_description/meshes/fr_wheel.STL b/src/core_rover_description/meshes/fr_wheel.STL deleted file mode 100644 index 905e955..0000000 Binary files a/src/core_rover_description/meshes/fr_wheel.STL and /dev/null differ diff --git a/src/core_rover_description/meshes/left_suspension_member.STL b/src/core_rover_description/meshes/left_suspension_member.STL deleted file mode 100644 index 0566c96..0000000 Binary files a/src/core_rover_description/meshes/left_suspension_member.STL and /dev/null differ diff --git a/src/core_rover_description/meshes/right_suspension_member.STL b/src/core_rover_description/meshes/right_suspension_member.STL deleted file mode 100644 index a34bfe8..0000000 Binary files a/src/core_rover_description/meshes/right_suspension_member.STL and /dev/null differ diff --git a/src/core_rover_description/package.xml b/src/core_rover_description/package.xml deleted file mode 100755 index df01630..0000000 --- a/src/core_rover_description/package.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - core_rover_description - 1.0.0 - This package contains configuration data, 3D models and launch files for Clucky Core - David Sharpe - AGPL-3.0-only - - rclpy - robot_state_publisher - rviz2 - - - ament_python - - diff --git a/src/core_rover_description/resource/core_rover_description b/src/core_rover_description/resource/core_rover_description deleted file mode 100644 index e69de29..0000000 diff --git a/src/core_rover_description/setup.cfg b/src/core_rover_description/setup.cfg deleted file mode 100644 index dd8cd4c..0000000 --- a/src/core_rover_description/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/core_ik_pkg -[install] -install_scripts=$base/lib/core_ik_pkg diff --git a/src/core_rover_description/setup.py b/src/core_rover_description/setup.py deleted file mode 100644 index 68c72b8..0000000 --- a/src/core_rover_description/setup.py +++ /dev/null @@ -1,28 +0,0 @@ -from setuptools import find_packages, setup -import os -from glob import glob - -package_name = 'core_rover_description' - -list_of_folders = ["config", "launch", "meshes", "textures", "urdf"] - -setup_data_files = [ - ('share/ament_index/resource_index/packages', ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']) -] - -for folder in list_of_folders: - setup_data_files.append((os.path.join('share', package_name, folder), glob(folder + '/*'))) - -setup( - name=package_name, - version='1.0.0', - packages=find_packages(exclude=['test']), - data_files=setup_data_files, # created above with for loop - install_requires=['setuptools'], - zip_safe=True, - maintainer='David Sharpe', - maintainer_email='ds0196@uah.edu', - description='This package contains configuration data, 3D models and launch files for Clucky Core', - license='BSD' -) diff --git a/src/core_rover_description/urdf/core_rover_description.csv b/src/core_rover_description/urdf/core_rover_description.csv deleted file mode 100644 index dfd36fa..0000000 --- a/src/core_rover_description/urdf/core_rover_description.csv +++ /dev/null @@ -1,9 +0,0 @@ -Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity -base_link,-6.65913085716885E-06,0.109571969438869,-0.0865730790907174,0,0,0,75.3855391061812,2.40019927956544,0.000116237424420155,-0.00156114013755156,2.05138658583389,0.00559155518698155,4.26537268155378,0,0,0,0,0,0,package://core_rover_description/meshes/base_link.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://core_rover_description/meshes/base_link.STL,,Shell & Averaging System-1/CSC Shell Assembly-1/CSC V4 Shell-1;Motor and 6 pin connector mount-2;Motor and 6 pin connector mount-1;Inside Motor and 6 pin connector mount plate-1;Shell & Averaging System-1/Diff Box Backing Plate V2-1;Shell & Averaging System-1/Averaging System Outer Plate Backing V1-1;Shell & Averaging System-1/Arm Bracket Assembly Right V3-1/L bracket-1;Shell & Averaging System-1/MirrorArm Bracket Assembly-2/MirrorArm Bolts-1;Shell & Averaging System-1/Arm Bracket Assembly Right V3-1/Arm Bolts-1;Elec_Box_Assem-1/Box_Base-1;Elec_Box_Assem-1/Box_Left_Wall-1;Elec_Box_Assem-1/Box_Front_Wall-1;Elec_Box_Assem-1/Box_Right_Wall-1;Elec_Box_Assem-1/POE Switch (Measured with hole pattern)-1;Elec_Box_Assem-1/Ethernet Switch (Measured with hole pattern)-1;Elec_Box_Assem-1/NUC13ANH_NUC13LCH-1/NUC13ANH_NUC13LCH.STP-1/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1/WS_TOP_COVER_ASM_ASM_1_ASM_1.STP-1/AN_TOP_COVER_1_2.STP-1;Elec_Box_Assem-1/NUC13ANH_NUC13LCH-1/NUC13ANH_NUC13LCH.STP-1/00_WS_ALL_ASM_CHECK_ASM_1_ASM_1.STP-1/WS_ME_PLACEMENT_ASM_ASM_1_ASM_2.STP-1/WS_ME_TALL_ASSY_ASM_1_ASM_1.STP-1/WS_TALL_MID_FRAME_ASM_ASM_1_ASM_1.STP-1/WS_TALL_MID_FRAME_NEW_1_1.STP-1;Elec_Box_Assem-1/SolidStateRelay-1;Elec_Box_Assem-1/100AFuse-1;Elec_Box_Assem-1/Box_Back_Wall-1;Rear_Wall_Sheath_Outer-2;Rear_Wall_Sheath_Outer-1;Shell & Averaging System-1/MirrorArm Bracket Assembly-2/MirrorL bracket-1;Shell & Averaging System-1/Chasis C-Channel Lip-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/Core Mount Front Plate-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/Core Mount Front Plate-2;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/Easy To weld Tube Spacer-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/Easy To weld Tube Spacer-9;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/Easy To weld Tube Spacer-10;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/Easy To weld Tube Spacer-8;Shell & Averaging System-1/Averaging System Outer Plate V3-1;Shell & Averaging System-1/Diff V5 Assem-2/Diff Box V5-1;Shell & Averaging System-1/Averaging System Outer Plate V3-2;Shell & Averaging System-1/picatinny95mm-1;Shell & Averaging System-1/picatinny95mm-2;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/90044A425_Black-Oxide Alloy Steel Socket Head Screw-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/90044A425_Black-Oxide Alloy Steel Socket Head Screw-3;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/90044A425_Black-Oxide Alloy Steel Socket Head Screw-4;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/90044A425_Black-Oxide Alloy Steel Socket Head Screw-2;Shell & Averaging System-1/6436K14 .5 Shaft Collar-2;Shell & Averaging System-1/6436K14 .5 Shaft Collar-4;Shell & Averaging System-1/6436K14 .5 Shaft Collar-3;Shell & Averaging System-1/6436K14 .5 Shaft Collar-1;Rear_Wall_Sheath_Inner-1;Shell & Averaging System-1/8896T69 SS U Bolt 1.375in-1;Shell & Averaging System-1/8896T69 SS U Bolt 1.375in-2;Shell & Averaging System-1/Averaging Shaft V3-2;Shell & Averaging System-1/Averaging Shaft V3-3;Shell & Averaging System-1/Diff V5 Assem-2/2342K186_Bearing .5 shaft sealed-3;Shell & Averaging System-1/2342K186_Bearing .5 shaft sealed-1;Shell & Averaging System-1/2342K186_Bearing .5 shaft sealed-2,Origin_global,,,,0,0,0,0,0,0,,0,0,0,,,,,,,,,,,, -right_suspension_member,0.0011302,-0.12483,0.029359,0,0,0,1.7681,0.0021448,-1.4957E-06,-2.5225E-08,0.0068473,0.00021191,0.0058417,0,0,0,0,0,0,package://core_rover_description/meshes/right_suspension_member.STL,1,1,1,1,0,0,0,0,0,0,package://core_rover_description/meshes/right_suspension_member.STL,,A- POST BOND SUSPENSION (1)-4/P- CENTER LEG [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-4/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-4/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-4/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-4/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2;A- POST BOND SUSPENSION (1)-4/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2;Gearbox-Wheel Assembly - MIRROR-6/Gearbox Casing-1;Gearbox-Wheel Assembly - MIRROR-6/REV-21-1651.step-1;Gearbox-Wheel Assembly - MIRROR-6/Bonding Tube-1;Gearbox-Wheel Assembly - MIRROR-6/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1;Gearbox-Wheel Assembly - MIRROR-6/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-3765 - 57 Sport Motor Block.STEP-1;Gearbox-Wheel Assembly - MIRROR-7/Gearbox Casing-1;A- POST BOND SUSPENSION (1)-4/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1;Gearbox-Wheel Assembly - MIRROR-7/REV-21-1651.step-1;Gearbox-Wheel Assembly - MIRROR-7/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-3765 - 57 Sport Motor Block.STEP-1;Gearbox-Wheel Assembly - MIRROR-7/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1;Gearbox-Wheel Assembly - MIRROR-7/Bonding Tube-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/6045N122_Low-Carbon Steel Round Tube 2-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/94645A111_High-Strength Steel Nylon-Insert Locknut-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/96144A239_Fine-Thread Alloy Steel Socket Head Screw-1,Origin_right_suspension_manual,right_suspension_axis,right_suspension_joint,revolute,-0.33067,0.028531,-0.15443,1.5708,0,-1.5708,base_link,0,0,-1,0,0,-0.38,0.38,,,,,,,, -br_wheel,-0.0476013497459569,-1.09801088221673E-08,6.12845485470359E-09,0,0,0,5.74175792756056,0.115468209215025,7.19767266741869E-10,-2.90603405999934E-10,0.0647068246341468,7.16669744358495E-07,0.0632464587169257,0,0,0,0,0,0,package://core_rover_description/meshes/br_wheel.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://core_rover_description/meshes/br_wheel.STL,,Gearbox-Wheel Assembly - MIRROR-7/Updated Wheel Starboard-1,Origin_br_wheel_axis,br_wheel_axis,br_wheel_axis,continuous,-0.41838,-0.17155,0.12984,0.52965,-1.5708,0,right_suspension_member,1,0,0,,,,,,,,,,,, -fr_wheel,-0.0476013497450763,-1.09822306249008E-08,6.12913009234717E-09,0,0,0,5.74175792767292,0.115468209216444,7.20424942594475E-10,-2.90800382125705E-10,0.0647068246345494,7.16670201096685E-07,0.063246458718483,0,0,0,0,0,0,package://core_rover_description/meshes/fr_wheel.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://core_rover_description/meshes/fr_wheel.STL,,Gearbox-Wheel Assembly - MIRROR-6/Updated Wheel Starboard-1,Origin_fr_wheel_joint,fr_wheel_axis,fr_wheel_joint,continuous,0.41838,-0.17155,0.12984,1.5769,-1.5708,0,right_suspension_member,1,0,0,,,,,,,,,,,, -averaging_bar,5.12266309124314E-10,0.0103345512865068,6.28647148226413E-10,0,0,0,0.872230516841863,0.000102234478668288,1.26173058927933E-11,-1.00509715989169E-11,0.0236921798518964,1.54032135551904E-11,0.0236577000709469,0,0,0,0,0,0,package://core_rover_description/meshes/averaging_bar.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://core_rover_description/meshes/averaging_bar.STL,,A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/Old Averaging Bar (Modified)-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/92981A220_Alloy Steel Shoulder Screws-2;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/92981A220_Alloy Steel Shoulder Screws-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/6045N122_Low-Carbon Steel Round Tube-2;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/6045N122_Low-Carbon Steel Round Tube-1,Origin_averaging_bar_axis,averaging_bar_axis,averaging_bar_axis,revolute,0,-0.23362,-0.0508,0,-0.0060774,-3.1416,base_link,0,-1,0,0,0,-0.38,0.38,,,,,,,, -left_suspension_member,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,package://core_rover_description/meshes/left_suspension_member.STL,1,1,1,1,0,0,0,0,0,0,package://core_rover_description/meshes/left_suspension_member.STL,,A- POST BOND SUSPENSION (1)-3/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-3/P- CENTER LEG [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-3/P- LEG ATTACHMENT CF COVER [POST BOND SUSPENSION] (1)-2;A- POST BOND SUSPENSION (1)-3/P- SIDE LEGS [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-3/P- SIDE LEGS [POST BOND SUSPENSION] (1)-2;Gearbox-Wheel Assembly - MIRROR-2/Gearbox Casing-1;Gearbox-Wheel Assembly - MIRROR-2/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1;Gearbox-Wheel Assembly - MIRROR-2/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-3765 - 57 Sport Motor Block.STEP-1;Gearbox-Wheel Assembly - MIRROR-1/Gearbox Casing-1;Gearbox-Wheel Assembly - MIRROR-1/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-XXXX - 57 Sport 3 Stage Ring Gear Housing.STEP-1;Gearbox-Wheel Assembly - MIRROR-1/3 Stage HD - 57 Sport-1/3 Stage HD - 57 Sport.STEP-1/am-3765 - 57 Sport Motor Block.STEP-1;Gearbox-Wheel Assembly - MIRROR-1/REV-21-1651.step-1;Gearbox-Wheel Assembly - MIRROR-1/Bonding Tube-1;Gearbox-Wheel Assembly - MIRROR-2/REV-21-1651.step-1;Gearbox-Wheel Assembly - MIRROR-2/Bonding Tube-1;A- POST BOND SUSPENSION (1)-3/P- CORE ATTACHMENT [POST BOND SUSPENSION] (1)-1;A- POST BOND SUSPENSION (1)-3/P- AXIS PLATE [POST BOND SUSPENSION] (1)-1;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/6045N122_Low-Carbon Steel Round Tube 2-2;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/96144A239_Fine-Thread Alloy Steel Socket Head Screw-2;A - AVERAGING BAR ASSEMBLY [CORE ROVER WITH PBS] (1)-1/94645A111_High-Strength Steel Nylon-Insert Locknut-2,Origin_left_suspension_manual,left_suspension_axis,left_suspension_joint,revolute,0.33067,0.028531,-0.15443,1.5708,0,1.5708,base_link,0,0,-1,0,0,-0.38,0.38,,,,,,,, -bl_wheel,-0.0476013497470983,-1.09827822947217E-08,6.12940226352165E-09,0,0,0,5.7417579274106,0.115468209213072,7.20585760708907E-10,-2.90859312873504E-10,0.0647068246335877,7.16669141063303E-07,0.0632464587148044,0,0,0,0,0,0,package://core_rover_description/meshes/bl_wheel.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://core_rover_description/meshes/bl_wheel.STL,,Gearbox-Wheel Assembly - MIRROR-1/Updated Wheel Starboard-1,Origin_bl_wheel_joint,bl_wheel_axis,bl_wheel_joint,continuous,0.41838,-0.17155,0.12984,1.5769,-1.5708,0,left_suspension_member,1,0,0,,,,,,,,,,,, -fl_wheel,-0.0476013497448114,-1.09827921201955E-08,6.12933048760311E-09,0,0,0,5.74175792770551,0.115468209216877,7.20541990109492E-10,-2.90874836866816E-10,0.0647068246346634,7.16670369639572E-07,0.06324645871897,0,0,0,0,0,0,package://core_rover_description/meshes/fl_wheel.STL,0.792156862745098,0.819607843137255,0.933333333333333,1,0,0,0,0,0,0,package://core_rover_description/meshes/fl_wheel.STL,,Gearbox-Wheel Assembly - MIRROR-2/Updated Wheel Starboard-1,Origin_fl_wheel_joint,fl_wheel_axis,fl_wheel_joint,continuous,-0.418377874454344,-0.171553199039643,0.129841324042317,0.529654981264331,-1.5707963267949,0,left_suspension_member,1,0,0,,,,,,,,,,,, diff --git a/src/core_rover_description/urdf/core_rover_description.urdf b/src/core_rover_description/urdf/core_rover_description.urdf deleted file mode 100644 index bf37292..0000000 --- a/src/core_rover_description/urdf/core_rover_description.urdf +++ /dev/null @@ -1,457 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/src/headless_pkg/package.xml b/src/headless_pkg/package.xml index b5f3b52..bc06dde 100644 --- a/src/headless_pkg/package.xml +++ b/src/headless_pkg/package.xml @@ -8,6 +8,8 @@ AGPL-3.0-only rclpy + common_interfaces + python3-pygame ros2_interfaces_pkg ament_copyright diff --git a/src/headless_pkg/src/headless_node.py b/src/headless_pkg/src/headless_node.py index fd23a8c..fa5e3ff 100755 --- a/src/headless_pkg/src/headless_node.py +++ b/src/headless_pkg/src/headless_node.py @@ -7,11 +7,11 @@ import signal import time import atexit -import serial import os import sys import threading import glob +from math import copysign from std_msgs.msg import String from geometry_msgs.msg import Twist @@ -48,6 +48,14 @@ class Headless(Node): # Initialize pygame first pygame.init() pygame.joystick.init() + super().__init__("headless") + + # Wait for anchor to start + pub_info = self.get_publishers_info_by_topic('/anchor/from_vic/debug') + while len(pub_info) == 0: + self.get_logger().info("Waiting for anchor to start...") + time.sleep(1.0) + pub_info = self.get_publishers_info_by_topic('/anchor/from_vic/debug') # Wait for a gamepad to be connected print("Waiting for gamepad connection...") @@ -65,8 +73,6 @@ class Headless(Node): self.gamepad.init() print(f'Gamepad Found: {self.gamepad.get_name()}') - # Now initialize the ROS2 node - super().__init__("headless") self.create_timer(0.15, self.send_controls) self.core_publisher = self.create_publisher(CoreControl, '/core/control', 2) @@ -173,7 +179,7 @@ class Headless(Node): # Forward/back and Turn input.linear.x = -1.0 * left_stick_y - input.angular.z = -1.0 * right_stick_x ** 2 # Exponent for finer control (curve) + input.angular.z = -1.0 * copysign(right_stick_x ** 2, right_stick_x) # Exponent for finer control (curve) # Publish self.core_twist_pub_.publish(input) @@ -262,7 +268,14 @@ class Headless(Node): # BIO - bio_input = BioControl(bio_arm=int(left_stick_y * -100), drill_arm=int(round(right_stick_y) * -100)) + bio_input = BioControl( + bio_arm=int(left_stick_y * -100), + drill_arm=int(round(right_stick_y) * -100) + ) + + # Drill motor (FAERIE) + if deadzone(left_trigger) > 0 or deadzone(right_trigger) > 0: + bio_input.drill = 100 * right_trigger - 100 * left_trigger self.core_publisher.publish(CORE_STOP_MSG) self.arm_publisher.publish(arm_input) diff --git a/src/latency_tester/CMakeLists.txt b/src/latency_tester/CMakeLists.txt index 6fea0db..6c214e8 100644 --- a/src/latency_tester/CMakeLists.txt +++ b/src/latency_tester/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.8) +cmake_minimum_required(VERSION 3.22) project(latency_tester) # Default to C++14 diff --git a/src/latency_tester/package.xml b/src/latency_tester/package.xml index 23de138..121816d 100644 --- a/src/latency_tester/package.xml +++ b/src/latency_tester/package.xml @@ -9,7 +9,7 @@ ament_cmake rclcpp - std_msgs + common_interfaces ament_lint_auto ament_lint_common