From 3a8620f64a5f8c16cbfe62e895185b8a1732fe62 Mon Sep 17 00:00:00 2001 From: alex Date: Wed, 13 Apr 2022 09:37:31 -0400 Subject: [PATCH 1/4] Added 4wd differential drive controller --- .../ZO4wdDifferentialDriveController.cs | 383 ++++++++++++++++++ .../ZO4wdDifferentialDriveControllerEditor.cs | 91 +++++ 2 files changed, 474 insertions(+) create mode 100644 Editor/CustomEditors/ZO4wdDifferentialDriveController.cs create mode 100644 Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs diff --git a/Editor/CustomEditors/ZO4wdDifferentialDriveController.cs b/Editor/CustomEditors/ZO4wdDifferentialDriveController.cs new file mode 100644 index 0000000..ad550b1 --- /dev/null +++ b/Editor/CustomEditors/ZO4wdDifferentialDriveController.cs @@ -0,0 +1,383 @@ +using System; +using System.Threading.Tasks; +using UnityEngine; +using Newtonsoft.Json.Linq; +using ZO.ROS.MessageTypes; +using ZO.ROS.MessageTypes.Geometry; +using ZO.ROS.MessageTypes.Nav; +using ZO.ROS; +using ZO.ROS.Unity; +using ZO.Util; +using ZO.Physics; +using ZO.Document; + + +namespace ZO.ROS.Controllers { + + /// + /// Overview: + /// -------- + /// Controller for differential drive wheel systems. Control is in the + /// form of a velocity command, that is split then sent on the two wheels + /// of a differential drive wheel base. Odometry is computed from the + /// feedback from the hardware, and published. + /// + /// Velocity commands: + /// ------------------ + /// The controller works with a velocity twist from which it extracts + /// the x component of the linear velocity and the z component of the angular + /// velocity. Velocities on other components are ignored. + /// + /// + /// See: https://github.com/ros-controls/ros_controllers/blob/indigo-devel/diff_drive_controller/include/diff_drive_controller/diff_drive_controller.h + /// + /// TODO: Make this a ZOROSUnityGameObjectBase and a controller interface + public class ZO4wdDifferentialDriveController : ZOROSUnityGameObjectBase { + + + public ZOSimOccurrence _connectedBody; + + /// + /// The main rigid body of the controller. Would usually be the "main chassis" of a robot. + /// + /// + public Rigidbody ConnectedRigidBody { + get { return _connectedBody.GetComponent(); } + } + [SerializeField] [ZOReadOnly] public ZOHingeJoint _frontRightWheelMotor; + + /// + /// Hinge joint that drives the right Front wheel. + /// + /// + public ZOHingeJoint FrontRightWheelMotor { + get => _frontRightWheelMotor; + set => _frontRightWheelMotor = value; + } + + [SerializeField] [ZOReadOnly] public ZOHingeJoint _rearRightWheelMotor; + + /// + /// Hinge joint that drives the right Back wheel. + /// + /// + public ZOHingeJoint RearRightWheelMotor { + get => _rearRightWheelMotor; + set => _rearRightWheelMotor = value; + } + + [SerializeField] [ZOReadOnly] public ZOHingeJoint _frontLeftWheelMotor; + + /// + /// Hinge joint that drive the left Front wheel. + /// + /// + public ZOHingeJoint FrontLeftWheelMotor { + get => _frontLeftWheelMotor; + set => _frontLeftWheelMotor = value; + } + + [SerializeField] [ZOReadOnly] public ZOHingeJoint _rearLeftWheelMotor; + + /// + /// Hinge joint that drive the left Back wheel. + /// + /// + public ZOHingeJoint RearLeftWheelMotor + { + get => _rearLeftWheelMotor; + set => _rearLeftWheelMotor = value; + } + + + public float _wheelRadius = 0; + public float _wheelSeperation = 0; + public bool _steerOpposite = false; + + private float _linearVelocity = 0; + private float _angularVelocity = 0; + + // NOTE: this can only be called in FixedUpdate + public float LinearVelocity { + set { + _linearVelocity = value; + UpdateMotors(); + } + get => _linearVelocity; + } + + // NOTE: this can only be called in FixedUpdate + public float AngularVelocity { + set { + _angularVelocity = value; + UpdateMotors(); + } + get => _angularVelocity; + } + + + + + public override string Type { + get { + return "controller.differential_drive"; + } + } + + void OnValidate() { + // make sure we have a name + if (string.IsNullOrEmpty(Name)) { + Name = gameObject.name + "_" + Type; + } + + } + + protected override void ZOAwake() { + base.ZOAwake(); + + // make sure we have a name + if (string.IsNullOrEmpty(Name)) { + Name = gameObject.name + "_" + Type; + } + + } + + + + protected override void ZOFixedUpdate() { + // update the motors from the twist message + LinearVelocity = (float)-_twistMessage.linear.x * Mathf.Rad2Deg; + if (_steerOpposite == true) { + AngularVelocity = (float)-_twistMessage.angular.z * Mathf.Rad2Deg; + } else { + AngularVelocity = (float)_twistMessage.angular.z * Mathf.Rad2Deg; + } + + } + protected override void ZOFixedUpdateHzSynchronized() { + + // publish odometry + if (ZOROSBridgeConnection.Instance.IsConnected) { + + // Publish odom on TF as well + _transformMessage.header.Update(); + _transformMessage.header.frame_id = ZOROSUnityManager.Instance.WorldFrameId; // connect to the world + _transformMessage.child_frame_id = "odom_combined"; + _transformMessage.UnityLocalTransform = ConnectedRigidBody.transform; + ZOROSUnityManager.Instance.BroadcastTransform(_transformMessage); + + + // NOTE: Just echoing back the true odometry. + // TODO: calculat the odometry see: CalculateOdometryOpenLoop + _odometryMessage.Update(); // update times stamps + + // BUGBUG: not super clear on where the pose should be? + _odometryMessage.pose.pose.GlobalUnityTransform = ConnectedRigidBody.transform; + + // get velocity in /odom frame + Vector3 linear = ConnectedRigidBody.velocity; + _odometryMessage.twist.twist.angular.z = -ConnectedRigidBody.angularVelocity.y; // NOTE: negating velocity? + + float yaw = ConnectedRigidBody.transform.localRotation.eulerAngles.y * Mathf.Deg2Rad; + _odometryMessage.twist.twist.linear.x = Mathf.Cos(yaw) * linear.z + Mathf.Sin(yaw) * linear.x; + _odometryMessage.twist.twist.linear.y = Mathf.Cos(yaw) * linear.x - Mathf.Sin(yaw) * linear.z; + // set covariance + // see: https://robotics.stackexchange.com/questions/15265/ros-gazebo-odometry-issue + // # Odometry covariances for the encoder output of the robot. These values should + // # be tuned to your robot's sample odometry data, but these values are a good place + // # to start + // pose_covariance_diagonal : [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + // twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0] + _odometryMessage.pose.covariance[0] = 1e-3; + _odometryMessage.pose.covariance[7] = 1e-3; + _odometryMessage.pose.covariance[14] = 1e6; + + _odometryMessage.pose.covariance[21] = 1e6; + _odometryMessage.pose.covariance[28] = 1e6; + _odometryMessage.pose.covariance[35] = 1e3; + + _odometryMessage.twist.covariance[0] = 1e-3; + _odometryMessage.twist.covariance[7] = 1e-3; + _odometryMessage.twist.covariance[14] = 1e6; + _odometryMessage.twist.covariance[21] = 1e6; + _odometryMessage.twist.covariance[28] = 1e6; + _odometryMessage.twist.covariance[35] = 1e3; + + // BUGBUG: not super clear on this being a child of map? + _odometryMessage.header.frame_id = ZOROSUnityManager.Instance.WorldFrameId; + _odometryMessage.child_frame_id = "odom"; + + ZOROSBridgeConnection.Instance.Publish(_odometryMessage, "/odom"); + } + + + // todo broadcast various joint transforms + // see: https://github.com/ros-simulation/gazebo_ros_pkgs/blob/kinetic-devel/gazebo_plugins/src/gazebo_ros_diff_drive.cpp + /* +void GazeboRosDiffDrive::publishWheelTF() +{ + ros::Time current_time = ros::Time::now(); + for ( int i = 0; i < 2; i++ ) { + + std::string wheel_frame = gazebo_ros_->resolveTF(joints_[i]->GetChild()->GetName ()); + std::string wheel_parent_frame = gazebo_ros_->resolveTF(joints_[i]->GetParent()->GetName ()); + +#if GAZEBO_MAJOR_VERSION >= 8 + ignition::math::Pose3d poseWheel = joints_[i]->GetChild()->RelativePose(); +#else + ignition::math::Pose3d poseWheel = joints_[i]->GetChild()->GetRelativePose().Ign(); +#endif + + tf::Quaternion qt ( poseWheel.Rot().X(), poseWheel.Rot().Y(), poseWheel.Rot().Z(), poseWheel.Rot().W() ); + tf::Vector3 vt ( poseWheel.Pos().X(), poseWheel.Pos().Y(), poseWheel.Pos().Z() ); + + tf::Transform tfWheel ( qt, vt ); + transform_broadcaster_->sendTransform ( + tf::StampedTransform ( tfWheel, current_time, wheel_parent_frame, wheel_frame ) ); + } +} */ + + } + private void UpdateMotors() { + float leftVelocity = (LinearVelocity + AngularVelocity * _wheelSeperation / 2.0f) / _wheelRadius; + float rightVelocity = (LinearVelocity - AngularVelocity * _wheelSeperation / 2.0f) / _wheelRadius; + + // BUGBUG: if this seems to fast the do a deg2rad on it? + _frontRightWheelMotor.Velocity = rightVelocity * Mathf.Deg2Rad; + _rearRightWheelMotor.Velocity = rightVelocity * Mathf.Deg2Rad; + _frontLeftWheelMotor.Velocity = leftVelocity * Mathf.Deg2Rad; + _rearLeftWheelMotor.Velocity = leftVelocity * Mathf.Deg2Rad; + } + + private float _odomHeading = 0; + private float _odomX = 0; + private float _odomY = 0; + + /// + /// See: https://github.com/ros-controls/ros_controllers/blob/noetic-devel/diff_drive_controller/src/odometry.cpp + /// + private void CalculateOdometryOpenLoop() { + /* see: https://github.com/ros-simulation/gazebo_ros_pkgs/blob/kinetic-devel/gazebo_plugins/src/gazebo_ros_diff_drive.cpp +void GazeboRosDiffDrive::UpdateOdometryEncoder() +{ + double vl = joints_[LEFT]->GetVelocity ( 0 ); + double vr = joints_[RIGHT]->GetVelocity ( 0 ); +#if GAZEBO_MAJOR_VERSION >= 8 + common::Time current_time = parent->GetWorld()->SimTime(); +#else + common::Time current_time = parent->GetWorld()->GetSimTime(); +#endif + double seconds_since_last_update = ( current_time - last_odom_update_ ).Double(); + last_odom_update_ = current_time; + + double b = wheel_separation_; + + // Book: Sigwart 2011 Autonompus Mobile Robots page:337 + double sl = vl * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update; + double sr = vr * ( wheel_diameter_ / 2.0 ) * seconds_since_last_update; + double ssum = sl + sr; + + double sdiff; + if(legacy_mode_) + { + sdiff = sl - sr; + } + else + { + + sdiff = sr - sl; + } + + double dx = ( ssum ) /2.0 * cos ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) ); + double dy = ( ssum ) /2.0 * sin ( pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) ); + double dtheta = ( sdiff ) /b; + + pose_encoder_.x += dx; + pose_encoder_.y += dy; + pose_encoder_.theta += dtheta; + + double w = dtheta/seconds_since_last_update; + double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update; + + tf::Quaternion qt; + tf::Vector3 vt; + qt.setRPY ( 0,0,pose_encoder_.theta ); + vt = tf::Vector3 ( pose_encoder_.x, pose_encoder_.y, 0 ); + + odom_.pose.pose.position.x = vt.x(); + odom_.pose.pose.position.y = vt.y(); + odom_.pose.pose.position.z = vt.z(); + + odom_.pose.pose.orientation.x = qt.x(); + odom_.pose.pose.orientation.y = qt.y(); + odom_.pose.pose.orientation.z = qt.z(); + odom_.pose.pose.orientation.w = qt.w(); + + odom_.twist.twist.angular.z = w; + odom_.twist.twist.linear.x = dx/seconds_since_last_update; + odom_.twist.twist.linear.y = dy/seconds_since_last_update; +} + */ + float dt = Time.deltaTime; + + if (Mathf.Abs(AngularVelocity) < 1e-6f) { + // Runge-Kutta 2nd order integration + float direction = _odomHeading + AngularVelocity * 0.5f; + _odomX += LinearVelocity * Mathf.Cos(direction); + _odomY += LinearVelocity * Mathf.Sin(direction); + _odomHeading += AngularVelocity; + } else { + float headingOld = _odomHeading; + float r = LinearVelocity / AngularVelocity; + _odomHeading += AngularVelocity; + _odomX += r * (Mathf.Sin(_odomHeading) - Mathf.Sin(headingOld)); + _odomY += r * (Mathf.Cos(_odomHeading) - Mathf.Cos(headingOld)); + } + } + + /// + /// ROS control twist message topic. + /// To test: `rosrun turtlebot3 turtlebot3_teleop_key` + /// + public string _ROSTopicSubscription = "/cmd_vel"; + private TwistMessage _twistMessage = new TwistMessage(); + private OdometryMessage _odometryMessage = new OdometryMessage(); + + /// + /// The "odom" transform published on TF. + /// + private TransformStampedMessage _transformMessage = new TransformStampedMessage(); + + + public override void OnROSBridgeConnected(ZOROSUnityManager rosUnityManager) { + Debug.Log("INFO: ZO4wdDifferentialDriveController::OnROSBridgeConnected"); + + // subscribe to Twist Message + ZOROSBridgeConnection.Instance.Subscribe(Name, _ROSTopicSubscription, _twistMessage.MessageType, OnROSTwistMessageReceived); + + // adverise Odometry Message + ZOROSBridgeConnection.Instance.Advertise("/odom", _odometryMessage.MessageType); + } + + public override void OnROSBridgeDisconnected(ZOROSUnityManager rosUnityManager) { + ZOROSBridgeConnection.Instance.UnAdvertise(_ROSTopicSubscription); + Debug.Log("INFO: ZO4wdDifferentialDriveController::OnROSBridgeDisconnected"); + } + + + /// + /// Handles subscribed to `TwistMessage` which controls the differential control steering and drive. + /// + /// ROS Bridge Connection + /// TwistMessage + /// + public Task OnROSTwistMessageReceived(ZOROSBridgeConnection rosBridgeConnection, ZOROSMessageInterface msg) { + _twistMessage = (TwistMessage)msg; + // Debug.Log("INFO: Twist Message Received: linear " + _twistMessage.linear.ToString() + " angular: " + _twistMessage.angular.ToString()); + + return Task.CompletedTask; + } + + + } +} diff --git a/Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs b/Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs new file mode 100644 index 0000000..8123095 --- /dev/null +++ b/Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs @@ -0,0 +1,91 @@ +using System.Linq; +using System.Collections; +using System.Collections.Generic; +using UnityEngine; +using UnityEditor; +using ZO.ROS.Controllers; +using ZO.Physics; + + +namespace ZO.Editor { + + [CustomEditor(typeof(ZO4wdDifferentialDriveController))] + public class ZO4wdDifferentialDriveControllerEditor : UnityEditor.Editor { + + // int _hingeChoiceIndex = 0; + string[] _motorChoiceNames; + SerializedObject _diffDriveSerializedObject; + SerializedProperty _frontRightMotorProp; + SerializedProperty _rearRightMotorProp; + SerializedProperty _frontLeftMotorProp; + SerializedProperty _rearLeftMotorProp; + + private void OnEnable() { + _diffDriveSerializedObject = new SerializedObject(target); + _frontRightMotorProp = _diffDriveSerializedObject.FindProperty("_frontRightWheelMotor"); + _rearRightMotorProp = _diffDriveSerializedObject.FindProperty("_rearRightWheelMotor"); + _frontLeftMotorProp = _diffDriveSerializedObject.FindProperty("_frontLeftWheelMotor"); + _rearLeftMotorProp = _diffDriveSerializedObject.FindProperty("_rearLeftWheelMotor"); + } + public override void OnInspectorGUI() { + _diffDriveSerializedObject.Update(); + + DrawDefaultInspector(); + + ZO4wdDifferentialDriveController diffDrive = (ZO4wdDifferentialDriveController)target; + + // get the hinge joints on this object + ZOHingeJoint[] hingeJoints = diffDrive.GetComponentsInChildren(); + _motorChoiceNames = new string[hingeJoints.Length]; + + // check if we already have set the hinge joints + int frontRightWheelIndex = -1; + int rearRightWheelIndex = -1; + int frontLeftWheelIndex = -1; + int rearLeftWheelIndex = -1; + for (int i = 0; i < hingeJoints.Length; i++) { + _motorChoiceNames[i] = hingeJoints[i].Name; + if (hingeJoints[i] == diffDrive.FrontRightWheelMotor) { + frontRightWheelIndex = i; + } + if (hingeJoints[i] == diffDrive.RearRightWheelMotor) { + rearRightWheelIndex = i; + } + if (hingeJoints[i] == diffDrive.FrontLeftWheelMotor) { + frontLeftWheelIndex = i; + } + if (hingeJoints[i] == diffDrive.RearLeftWheelMotor) { + rearLeftWheelIndex = i; + } + + } + + int frontLeftMotorChosenIndex = UnityEditor.EditorGUILayout.Popup("Front Left Wheel Motor Name", frontLeftWheelIndex, _motorChoiceNames); + int frontRightMotorChosenIndex = UnityEditor.EditorGUILayout.Popup("Front Right Wheel Motor Name", frontRightWheelIndex, _motorChoiceNames); + + int rearLeftMotorChosenIndex = UnityEditor.EditorGUILayout.Popup("Rear Left Wheel Motor Name", rearLeftWheelIndex, _motorChoiceNames); + int rearRightMotorChosenIndex = UnityEditor.EditorGUILayout.Popup("Rear Right Wheel Motor Name", rearRightWheelIndex, _motorChoiceNames); + + // if we chose something different then what is already selected then set it + if (frontRightMotorChosenIndex != frontRightWheelIndex) { + _frontRightMotorProp.objectReferenceValue = hingeJoints[frontRightMotorChosenIndex]; + } + if (rearRightMotorChosenIndex != rearRightWheelIndex) { + _rearRightMotorProp.objectReferenceValue = hingeJoints[rearRightMotorChosenIndex]; + } + + if (frontLeftMotorChosenIndex != frontLeftWheelIndex) { + _frontLeftMotorProp.objectReferenceValue = hingeJoints[frontLeftMotorChosenIndex]; + } + if (rearLeftMotorChosenIndex != rearLeftWheelIndex) { + _rearLeftMotorProp.objectReferenceValue = hingeJoints[rearLeftMotorChosenIndex]; + } + + + // apply the properties + _diffDriveSerializedObject.ApplyModifiedProperties(); + + } + } + +} From 02f740095d291a8119ae761c211b6db0476efd1d Mon Sep 17 00:00:00 2001 From: alex Date: Wed, 13 Apr 2022 11:28:48 -0400 Subject: [PATCH 2/4] Tested 4wd diff_drive controller + how to modify package --- .../ZO4wdDifferentialDriveControllerEditor.cs.meta | 11 +++++++++++ README.md | 7 +++++++ .../Controllers}/ZO4wdDifferentialDriveController.cs | 0 .../ZO4wdDifferentialDriveController.cs.meta | 11 +++++++++++ 4 files changed, 29 insertions(+) create mode 100644 Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs.meta rename {Editor/CustomEditors => Runtime/Scripts/ROS/Unity/Controllers}/ZO4wdDifferentialDriveController.cs (100%) create mode 100644 Runtime/Scripts/ROS/Unity/Controllers/ZO4wdDifferentialDriveController.cs.meta diff --git a/Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs.meta b/Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs.meta new file mode 100644 index 0000000..eb86b8a --- /dev/null +++ b/Editor/CustomEditors/ZO4wdDifferentialDriveControllerEditor.cs.meta @@ -0,0 +1,11 @@ +fileFormatVersion: 2 +guid: ecc23b5222971344aa4acc5a2faaa84e +MonoImporter: + externalObjects: {} + serializedVersion: 2 + defaultReferences: [] + executionOrder: 0 + icon: {instanceID: 0} + userData: + assetBundleName: + assetBundleVariant: diff --git a/README.md b/README.md index bab973e..5d896ad 100644 --- a/README.md +++ b/README.md @@ -14,6 +14,7 @@ - [Export URDF](#export-urdf) - [Import URDF](#import-urdf) - [LEO Robot Example](#leo-robot-example) + - [Modifying package source](#modifying-package-source) ZeroSim is a robotics simulation engine built on the easy to use [Unity 3D](https://unity.com/) development platform and the power of the [Robotics Operating System (ROS)](https://www.ros.org/). ZeroSim is designed for ease of use and rapid development of all sorts of robotics and simulation -- from warehouses and industrial settings, to farming and outdoors -- from robotic arms to ground and drone based mobile robots. @@ -298,3 +299,9 @@ sed -i 's#package://#./#g' my_leo_robot/leo_sim.urdf ``` 10. In Unity import URDF by: Right click and select `ZeroSim --> Import URDF...` + +### Modifying package source +You can download and install the packages of this repositories on your Unity project and modify the package source code. You can do that by one of the following methods: + +1. Clone this repository in any folder on your computer. Install them as local packages into your project. +2. Clone this repository inside a Packages folder in your Unity project. diff --git a/Editor/CustomEditors/ZO4wdDifferentialDriveController.cs b/Runtime/Scripts/ROS/Unity/Controllers/ZO4wdDifferentialDriveController.cs similarity index 100% rename from Editor/CustomEditors/ZO4wdDifferentialDriveController.cs rename to Runtime/Scripts/ROS/Unity/Controllers/ZO4wdDifferentialDriveController.cs diff --git a/Runtime/Scripts/ROS/Unity/Controllers/ZO4wdDifferentialDriveController.cs.meta b/Runtime/Scripts/ROS/Unity/Controllers/ZO4wdDifferentialDriveController.cs.meta new file mode 100644 index 0000000..0183fc5 --- /dev/null +++ b/Runtime/Scripts/ROS/Unity/Controllers/ZO4wdDifferentialDriveController.cs.meta @@ -0,0 +1,11 @@ +fileFormatVersion: 2 +guid: 6b9230a08e2f476c781f4964c3dfee63 +MonoImporter: + externalObjects: {} + serializedVersion: 2 + defaultReferences: [] + executionOrder: 0 + icon: {instanceID: 0} + userData: + assetBundleName: + assetBundleVariant: From 17f080e80d90e1d2982af40a454db4745d2fdfe2 Mon Sep 17 00:00:00 2001 From: Alex <90333090+alex-ssom@users.noreply.github.com> Date: Wed, 13 Apr 2022 11:32:34 -0400 Subject: [PATCH 3/4] Fix typos --- README.md | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 5d896ad..ae8dcfb 100644 --- a/README.md +++ b/README.md @@ -301,7 +301,6 @@ sed -i 's#package://#./#g' my_leo_robot/leo_sim.urdf 10. In Unity import URDF by: Right click and select `ZeroSim --> Import URDF...` ### Modifying package source -You can download and install the packages of this repositories on your Unity project and modify the package source code. You can do that by one of the following methods: - -1. Clone this repository in any folder on your computer. Install them as local packages into your project. -2. Clone this repository inside a Packages folder in your Unity project. +You can download and install this package in your Unity project and modify the package source code. You can do that by one of the following methods: +1. Clone this repository in any folder on your computer. Install it with `Package Manager --> Add package from disk...`. +2. Clone this repository inside the `Packages` folder in your Unity project. From 6b2d706a6d16524ff846d7ed814436c955b959f1 Mon Sep 17 00:00:00 2001 From: alex Date: Wed, 13 Apr 2022 13:20:44 -0400 Subject: [PATCH 4/4] added simpleAmr4wdRobot scene --- .../Robots/SimpleAMR/SimpleAMR4wd.prefab | 2111 +++++++++++++++++ .../Robots/SimpleAMR/SimpleAMR4wd.prefab.meta | 7 + .../Scenes/SimpleRobot4WD_test.unity | 1147 +++++++++ .../Scenes/SimpleRobot4WD_test.unity.meta | 7 + 4 files changed, 3272 insertions(+) create mode 100644 Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab create mode 100644 Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab.meta create mode 100644 Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity create mode 100644 Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity.meta diff --git a/Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab b/Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab new file mode 100644 index 0000000..dc4b050 --- /dev/null +++ b/Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab @@ -0,0 +1,2111 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!1 &340507533779495956 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 4518602586022028242} + m_Layer: 0 + m_Name: visuals + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &4518602586022028242 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 340507533779495956} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 293700382973635161} + m_Father: {fileID: 615631443772879986} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &1443506210700296418 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 5747588838467132886} + - component: {fileID: 8689044166771805659} + - component: {fileID: 6680406541478373870} + m_Layer: 0 + m_Name: front_left_wheel + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &5747588838467132886 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1443506210700296418} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 1942401776155733103} + - {fileID: 5664123494003141302} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 6 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &8689044166771805659 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1443506210700296418} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: cd2f2e3616277d4579d5a38545164e1a, type: 3} + m_Name: + m_EditorClassIdentifier: + _documentRoot: {fileID: 6698692810316458237} +--- !u!54 &6680406541478373870 +Rigidbody: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1443506210700296418} + serializedVersion: 2 + m_Mass: 1 + m_Drag: 0 + m_AngularDrag: 0.05 + m_UseGravity: 1 + m_IsKinematic: 0 + m_Interpolate: 0 + m_Constraints: 0 + m_CollisionDetection: 0 +--- !u!1 &1784391799965911495 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 7028497365664568377} + - component: {fileID: 862192049185227016} + - component: {fileID: 7709306216224966411} + - component: {fileID: 6342275605246321759} + m_Layer: 0 + m_Name: Cylinder + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 0 +--- !u!4 &7028497365664568377 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1784391799965911495} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 0.1, y: 0.01, z: 0.1} + m_Children: [] + m_Father: {fileID: 7041759074014604295} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!33 &862192049185227016 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1784391799965911495} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &7709306216224966411 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1784391799965911495} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!136 &6342275605246321759 +CapsuleCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1784391799965911495} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 0 + m_Radius: 0.5000001 + m_Height: 2 + m_Direction: 1 + m_Center: {x: 0.000000059604645, y: 0, z: -0.00000008940697} +--- !u!1 &1949428794401804555 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 293700382973635161} + - component: {fileID: 6422098779342119016} + - component: {fileID: 7000833567593538959} + - component: {fileID: 1711388395262819652} + m_Layer: 0 + m_Name: Cube + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 0 +--- !u!4 &293700382973635161 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1949428794401804555} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 0.01, y: 0.01, z: 0.01} + m_Children: [] + m_Father: {fileID: 4518602586022028242} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!33 &6422098779342119016 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1949428794401804555} + m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &7000833567593538959 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1949428794401804555} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!65 &1711388395262819652 +BoxCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1949428794401804555} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 2 + m_Size: {x: 1, y: 1, z: 1} + m_Center: {x: 0, y: 0, z: 0} +--- !u!1 &2256837069804019364 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 4920751528867295256} + m_Layer: 0 + m_Name: collisions + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &4920751528867295256 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 2256837069804019364} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 4081052963794407410} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &2362904230812445934 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 1942401776155733103} + m_Layer: 0 + m_Name: visuals + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &1942401776155733103 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 2362904230812445934} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 7990924510994162431} + m_Father: {fileID: 5747588838467132886} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &3086472622410138958 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 7990924510994162431} + - component: {fileID: 5851887486119349805} + - component: {fileID: 2871867430785177393} + - component: {fileID: 2157312085263687557} + m_Layer: 0 + m_Name: left_wheel_visual + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &7990924510994162431 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 3086472622410138958} + m_LocalRotation: {x: -0, y: -0, z: 0.7071068, w: 0.7071068} + m_LocalPosition: {x: -0.17, y: -0.01, z: -0.1} + m_LocalScale: {x: 0.10000001, y: 0.009999998, z: 0.099999994} + m_Children: [] + m_Father: {fileID: 1942401776155733103} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 90} +--- !u!33 &5851887486119349805 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 3086472622410138958} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &2871867430785177393 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 3086472622410138958} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!136 &2157312085263687557 +CapsuleCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 3086472622410138958} + m_Material: {fileID: 13400000, guid: 006b6fc65c33dc9298961c5af7494b3a, type: 2} + m_IsTrigger: 0 + m_Enabled: 1 + m_Radius: 0.5000001 + m_Height: 2 + m_Direction: 1 + m_Center: {x: 0.000000059604645, y: 0, z: -0.00000008940697} +--- !u!1 &3571865006441780010 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 8402476309065344816} + m_Layer: 0 + m_Name: visuals + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &8402476309065344816 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 3571865006441780010} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 8489885574144769606} + m_Father: {fileID: 4081052963794407410} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &3959553052456765484 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 5664123494003141302} + m_Layer: 0 + m_Name: collisions + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &5664123494003141302 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 3959553052456765484} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 5747588838467132886} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &4071223512090611748 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 3954562668498932686} + - component: {fileID: 2813356702075989999} + - component: {fileID: 5530694846666074993} + - component: {fileID: 6724902590840379041} + - component: {fileID: 8810797865417319382} + m_Layer: 0 + m_Name: lidar_2d + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &3954562668498932686 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 4071223512090611748} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0.15, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 7041759074014604295} + - {fileID: 6162816310870386290} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 4 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &2813356702075989999 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 4071223512090611748} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: cd2f2e3616277d4579d5a38545164e1a, type: 3} + m_Name: + m_EditorClassIdentifier: + _documentRoot: {fileID: 6698692810316458237} +--- !u!114 &5530694846666074993 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 4071223512090611748} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 12e3f183b8e3d462c8acb6acaee3cb60, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 10 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _minAngleDegrees: 0 + _maxAngleDegrees: 360 + _angleIncrementDegrees: 1 + _minRangeDistanceMeters: 0.1 + _maxRangeDistanceMeters: 20 + _name: lidar_2d_sensor.lidar2d +--- !u!114 &6724902590840379041 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 4071223512090611748} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 6013e0556113f1e9f95189e724e765fc, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 10 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: + _name: ros.publisher.transform_lidar_2d + _frameId: base_link + _childFrameId: scan +--- !u!114 &8810797865417319382 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 4071223512090611748} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: bc23ecdd2eb539484ba9b103d1e1be49, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 10 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: scan + _name: ros.publisher.scan_lidar_2d + _lidar2DSensor: {fileID: 5530694846666074993} + _parentTransformId: base_link +--- !u!1 &5100000875187032302 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6162816310870386290} + m_Layer: 0 + m_Name: collisions + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6162816310870386290 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 5100000875187032302} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 3954562668498932686} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6182253667204711308 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 2029710062312338289} + m_Layer: 0 + m_Name: collisions + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &2029710062312338289 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6182253667204711308} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 615631443772879986} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6566873766978202409 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 615631443772879986} + - component: {fileID: 2161468062805216556} + - component: {fileID: 6508992627479591912} + - component: {fileID: 5029759530237128661} + - component: {fileID: 6373476428716480160} + m_Layer: 0 + m_Name: color_camera + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &615631443772879986 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6566873766978202409} + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0.19999999, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 4518602586022028242} + - {fileID: 2029710062312338289} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 5 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &2161468062805216556 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6566873766978202409} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: cd2f2e3616277d4579d5a38545164e1a, type: 3} + m_Name: + m_EditorClassIdentifier: + _documentRoot: {fileID: 6698692810316458237} +--- !u!20 &6508992627479591912 +Camera: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6566873766978202409} + m_Enabled: 1 + serializedVersion: 2 + m_ClearFlags: 1 + m_BackGroundColor: {r: 0.19215687, g: 0.3019608, b: 0.4745098, a: 0} + m_projectionMatrixMode: 1 + m_GateFitMode: 2 + m_FOVAxisMode: 0 + m_SensorSize: {x: 36, y: 24} + m_LensShift: {x: 0, y: 0} + m_FocalLength: 50 + m_NormalizedViewPortRect: + serializedVersion: 2 + x: 0 + y: 0 + width: 1 + height: 1 + near clip plane: 0.3 + far clip plane: 1000 + field of view: 60 + orthographic: 0 + orthographic size: 5 + m_Depth: 0 + m_CullingMask: + serializedVersion: 2 + m_Bits: 4294967295 + m_RenderingPath: -1 + m_TargetTexture: {fileID: 0} + m_TargetDisplay: 0 + m_TargetEye: 3 + m_HDR: 1 + m_AllowMSAA: 1 + m_AllowDynamicResolution: 0 + m_ForceIntoRT: 0 + m_OcclusionCulling: 1 + m_StereoConvergence: 10 + m_StereoSeparation: 0.022 +--- !u!114 &5029759530237128661 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6566873766978202409} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 7de0e78cad1cc57a3b409bbb96c7af6a, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 30 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _camera: {fileID: 6508992627479591912} + _width: 640 + _height: 480 + _postProcessMaterial: {fileID: 2100000, guid: d2f03b5f033866ec6b3b16cabc66b331, type: 2} + _debugWindowPosition: {x: 10, y: 10} + _name: color_camera_camera +--- !u!114 &6373476428716480160 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6566873766978202409} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 4eab68bc499af59ddb04d723f31065f2, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 0 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: + _name: ros.publisher.image_color_camera + _rgbCameraSensor: {fileID: 5029759530237128661} + _imageROSTopic: image/image_raw + _cameraInfoROSTopic: image/camera_info +--- !u!1 &6698692809657540419 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692809657540420} + - component: {fileID: 6698692809657540421} + - component: {fileID: 6698692809657540422} + m_Layer: 0 + m_Name: rear_right_wheel + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692809657540420 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692809657540419} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692811355797724} + - {fileID: 6698692811177350983} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 2 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &6698692809657540421 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692809657540419} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: cd2f2e3616277d4579d5a38545164e1a, type: 3} + m_Name: + m_EditorClassIdentifier: + _documentRoot: {fileID: 6698692810316458237} +--- !u!54 &6698692809657540422 +Rigidbody: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692809657540419} + serializedVersion: 2 + m_Mass: 1 + m_Drag: 0 + m_AngularDrag: 0.05 + m_UseGravity: 1 + m_IsKinematic: 0 + m_Interpolate: 0 + m_Constraints: 0 + m_CollisionDetection: 0 +--- !u!1 &6698692809717887722 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692809717887723} + m_Layer: 0 + m_Name: collisions + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692809717887723 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692809717887722} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 6698692811637545783} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6698692810200528043 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692810200528044} + - component: {fileID: 6698692810200528047} + - component: {fileID: 6698692810200528046} + - component: {fileID: 6698692810200528045} + m_Layer: 0 + m_Name: right_wheel_visual + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692810200528044 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810200528043} + m_LocalRotation: {x: 0, y: 0, z: 0.7071068, w: 0.7071068} + m_LocalPosition: {x: 0.17, y: -0.01, z: 0.1} + m_LocalScale: {x: 0.1, y: 0.01, z: 0.1} + m_Children: [] + m_Father: {fileID: 6698692811355797724} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 90} +--- !u!33 &6698692810200528047 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810200528043} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &6698692810200528046 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810200528043} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!136 &6698692810200528045 +CapsuleCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810200528043} + m_Material: {fileID: 13400000, guid: 006b6fc65c33dc9298961c5af7494b3a, type: 2} + m_IsTrigger: 0 + m_Enabled: 1 + m_Radius: 0.5000001 + m_Height: 2 + m_Direction: 1 + m_Center: {x: 0.000000059604645, y: 0, z: -0.00000008940697} +--- !u!1 &6698692810278590368 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692810278590369} + m_Layer: 0 + m_Name: collisions + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692810278590369 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810278590368} + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692811598083582} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6698692810316458236 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692810316458238} + - component: {fileID: 6698692810316458237} + - component: {fileID: 6698692810316458208} + - component: {fileID: 6698692810316458239} + - component: {fileID: 1733081356533547074} + - component: {fileID: 8254790492665882515} + m_Layer: 0 + m_Name: SimpleAMR4wd + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692810316458238 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810316458236} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0.06, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692811621179079} + m_Father: {fileID: 0} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &6698692810316458237 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810316458236} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 5f63db7f27f0b322ab785c2fe0b3e4c1, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 0 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: + _name: + _publishRobotDescription: 0 +--- !u!114 &6698692810316458208 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810316458236} + m_Enabled: 0 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 30dd28dd015d2676095dc80c2226e3ae, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 30 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: + _name: SimpleAMR_controller.differential_drive + _connectedBody: {fileID: 6698692811621179080} + _rightWheelMotor: {fileID: 6698692811621179085} + _leftWheelMotor: {fileID: 6698692811621179083} + _wheelRadius: 0.05 + _wheelSeperation: 0.34 + _steerOpposite: 0 + _ROSTopicSubscription: /cmd_vel +--- !u!114 &6698692810316458239 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810316458236} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 129fe926cb5f9784893878adb84b7b04, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 4 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: /zerosim/joint_states + _name: ros.publisher.joint_states_SimpleAMR +--- !u!114 &1733081356533547074 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810316458236} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 6b9230a08e2f476c781f4964c3dfee63, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 30 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: + _name: controller.differential_drive_SimpleAMR + _connectedBody: {fileID: 6698692811621179080} + _frontRightWheelMotor: {fileID: 3649147453390373136} + _rearRightWheelMotor: {fileID: 6698692811621179085} + _frontLeftWheelMotor: {fileID: 3538145605875767238} + _rearLeftWheelMotor: {fileID: 6698692811621179083} + _wheelRadius: 0.5 + _wheelSeperation: 0.34 + _steerOpposite: 0 + _ROSTopicSubscription: /cmd_vel +--- !u!114 &8254790492665882515 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810316458236} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 92d51467c4cc0f96098e2785b3b15847, type: 3} + m_Name: + m_EditorClassIdentifier: +--- !u!1 &6698692810479416265 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692810479416266} + m_Layer: 0 + m_Name: visuals + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692810479416266 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810479416265} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692810551264531} + m_Father: {fileID: 6698692811637545783} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6698692810551264530 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692810551264531} + - component: {fileID: 6698692810551264534} + - component: {fileID: 6698692810551264533} + - component: {fileID: 6698692810551264532} + m_Layer: 0 + m_Name: left_wheel_visual + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692810551264531 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810551264530} + m_LocalRotation: {x: -0, y: -0, z: 0.7071068, w: 0.7071068} + m_LocalPosition: {x: -0.1700001, y: -0.00999999, z: 0.099999905} + m_LocalScale: {x: 0.10000001, y: 0.009999998, z: 0.099999994} + m_Children: [] + m_Father: {fileID: 6698692810479416266} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 90} +--- !u!33 &6698692810551264534 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810551264530} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &6698692810551264533 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810551264530} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!136 &6698692810551264532 +CapsuleCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692810551264530} + m_Material: {fileID: 13400000, guid: 006b6fc65c33dc9298961c5af7494b3a, type: 2} + m_IsTrigger: 0 + m_Enabled: 1 + m_Radius: 0.5000001 + m_Height: 2 + m_Direction: 1 + m_Center: {x: 0.000000059604645, y: 0, z: -0.00000008940697} +--- !u!1 &6698692811177350982 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692811177350983} + m_Layer: 0 + m_Name: collisions + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692811177350983 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811177350982} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 6698692809657540420} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6698692811242464925 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692811242464926} + m_Layer: 0 + m_Name: visuals + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692811242464926 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811242464925} + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692811583409810} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6698692811355797723 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692811355797724} + m_Layer: 0 + m_Name: visuals + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692811355797724 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811355797723} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692810200528044} + m_Father: {fileID: 6698692809657540420} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &6698692811583409809 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692811583409810} + - component: {fileID: 6698692811583409812} + - component: {fileID: 6698692811583409811} + m_Layer: 0 + m_Name: main_chassis_visual + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692811583409810 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811583409809} + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 0.3, y: 0.1, z: 0.3} + m_Children: [] + m_Father: {fileID: 6698692811242464926} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!33 &6698692811583409812 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811583409809} + m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &6698692811583409811 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811583409809} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 1 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!1 &6698692811598083581 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692811598083582} + - component: {fileID: 6698692811598083583} + m_Layer: 0 + m_Name: main_chassis_collision + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692811598083582 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811598083581} + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 6698692810278590369} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!65 &6698692811598083583 +BoxCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811598083581} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 2 + m_Size: {x: 0.3, y: 0.1, z: 0.3} + m_Center: {x: 0, y: 0, z: 0} +--- !u!1 &6698692811621179078 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692811621179079} + - component: {fileID: 6698692811621179080} + - component: {fileID: 6698692811621179081} + - component: {fileID: 6698692811621179085} + - component: {fileID: 6698692811621179084} + - component: {fileID: 6698692811621179083} + - component: {fileID: 6698692811621179082} + - component: {fileID: 5874798588211439065} + - component: {fileID: 3538145605875767238} + - component: {fileID: 702755312490549457} + - component: {fileID: 3649147453390373136} + - component: {fileID: 2807253056984941029} + m_Layer: 0 + m_Name: base_link + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692811621179079 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692811242464926} + - {fileID: 6698692810278590369} + - {fileID: 6698692809657540420} + - {fileID: 6698692811637545783} + - {fileID: 3954562668498932686} + - {fileID: 615631443772879986} + - {fileID: 5747588838467132886} + - {fileID: 4081052963794407410} + m_Father: {fileID: 6698692810316458238} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &6698692811621179080 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: cd2f2e3616277d4579d5a38545164e1a, type: 3} + m_Name: + m_EditorClassIdentifier: + _documentRoot: {fileID: 6698692810316458237} +--- !u!54 &6698692811621179081 +Rigidbody: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + serializedVersion: 2 + m_Mass: 10 + m_Drag: 0 + m_AngularDrag: 0.05 + m_UseGravity: 1 + m_IsKinematic: 0 + m_Interpolate: 0 + m_Constraints: 0 + m_CollisionDetection: 0 +--- !u!114 &6698692811621179085 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 56f9311082fd720b2b050874db2664ed, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 0 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _connectedBody: {fileID: 6698692809657540422} + _anchor: {x: 0.15, y: -0.01, z: 0.1} + _axis: {x: 1, y: 0, z: 0} + _useMotor: 1 + _motorForce: 10 + _useSpring: 0 + _springConstant: 100 + _springDampening: 20 + _hingeJoint: {fileID: 6698692811621179084} + _name: joint.hinge_from_base_link_to_RR_wheel +--- !u!59 &6698692811621179084 +HingeJoint: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_ConnectedBody: {fileID: 6698692809657540422} + m_ConnectedArticulationBody: {fileID: 0} + m_Anchor: {x: 0.15, y: -0.01, z: 0.1} + m_Axis: {x: 1, y: 0, z: 0} + m_AutoConfigureConnectedAnchor: 1 + m_ConnectedAnchor: {x: 0.15, y: -0.010000002, z: 0.1} + m_UseSpring: 0 + m_Spring: + spring: 100 + damper: 20 + targetPosition: 0 + m_UseMotor: 1 + m_Motor: + targetVelocity: 0 + force: 10 + freeSpin: 0 + m_UseLimits: 0 + m_Limits: + min: 0 + max: 0 + bounciness: 0 + bounceMinVelocity: 0.2 + contactDistance: 0 + m_BreakForce: Infinity + m_BreakTorque: Infinity + m_EnableCollision: 0 + m_EnablePreprocessing: 1 + m_MassScale: 1 + m_ConnectedMassScale: 1 +--- !u!114 &6698692811621179083 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 56f9311082fd720b2b050874db2664ed, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 0 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _connectedBody: {fileID: 6698692811637545785} + _anchor: {x: -0.15, y: -0.01, z: 0.1} + _axis: {x: 1, y: 0, z: 0} + _useMotor: 1 + _motorForce: 10 + _useSpring: 0 + _springConstant: 100 + _springDampening: 20 + _hingeJoint: {fileID: 6698692811621179082} + _name: joint.hinge_from_base_link_to_RL_wheel +--- !u!59 &6698692811621179082 +HingeJoint: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_ConnectedBody: {fileID: 6698692811637545785} + m_ConnectedArticulationBody: {fileID: 0} + m_Anchor: {x: -0.15, y: -0.01, z: 0.1} + m_Axis: {x: 1, y: 0, z: 0} + m_AutoConfigureConnectedAnchor: 1 + m_ConnectedAnchor: {x: -0.15, y: -0.010000002, z: 0.1} + m_UseSpring: 0 + m_Spring: + spring: 100 + damper: 20 + targetPosition: 0 + m_UseMotor: 1 + m_Motor: + targetVelocity: 0 + force: 10 + freeSpin: 0 + m_UseLimits: 0 + m_Limits: + min: 0 + max: 0 + bounciness: 0 + bounceMinVelocity: 0.2 + contactDistance: 0 + m_BreakForce: Infinity + m_BreakTorque: Infinity + m_EnableCollision: 0 + m_EnablePreprocessing: 1 + m_MassScale: 1 + m_ConnectedMassScale: 1 +--- !u!114 &5874798588211439065 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 6013e0556113f1e9f95189e724e765fc, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 10 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: + _name: ros.publisher.transform_base_link + _frameId: map + _childFrameId: base_link +--- !u!114 &3538145605875767238 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 56f9311082fd720b2b050874db2664ed, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 0 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _connectedBody: {fileID: 6680406541478373870} + _anchor: {x: 0.15, y: -0.01, z: -0.1} + _axis: {x: 1, y: 0, z: 0} + _useMotor: 1 + _motorForce: 10 + _useSpring: 0 + _springConstant: 100 + _springDampening: 20 + _hingeJoint: {fileID: 702755312490549457} + _name: joint.hinge_from_base_link_to_FL_wheel +--- !u!59 &702755312490549457 +HingeJoint: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_ConnectedBody: {fileID: 6680406541478373870} + m_ConnectedArticulationBody: {fileID: 0} + m_Anchor: {x: 0.15, y: -0.01, z: -0.1} + m_Axis: {x: 1, y: 0, z: 0} + m_AutoConfigureConnectedAnchor: 1 + m_ConnectedAnchor: {x: 0.15, y: -0.010000002, z: -0.1} + m_UseSpring: 0 + m_Spring: + spring: 100 + damper: 20 + targetPosition: 0 + m_UseMotor: 1 + m_Motor: + targetVelocity: 0 + force: 10 + freeSpin: 0 + m_UseLimits: 0 + m_Limits: + min: 0 + max: 0 + bounciness: 0 + bounceMinVelocity: 0.2 + contactDistance: 0 + m_BreakForce: Infinity + m_BreakTorque: Infinity + m_EnableCollision: 0 + m_EnablePreprocessing: 1 + m_MassScale: 1 + m_ConnectedMassScale: 1 +--- !u!114 &3649147453390373136 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 56f9311082fd720b2b050874db2664ed, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 0 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _connectedBody: {fileID: 1846854308041689141} + _anchor: {x: -0.15, y: -0.01, z: -0.1} + _axis: {x: 1, y: 0, z: 0} + _useMotor: 1 + _motorForce: 10 + _useSpring: 0 + _springConstant: 100 + _springDampening: 20 + _hingeJoint: {fileID: 2807253056984941029} + _name: joint.hinge_from_base_link_to_FR_wheel +--- !u!59 &2807253056984941029 +HingeJoint: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811621179078} + m_ConnectedBody: {fileID: 1846854308041689141} + m_ConnectedArticulationBody: {fileID: 0} + m_Anchor: {x: -0.15, y: -0.01, z: -0.1} + m_Axis: {x: 1, y: 0, z: 0} + m_AutoConfigureConnectedAnchor: 1 + m_ConnectedAnchor: {x: -0.15, y: -0.010000002, z: -0.1} + m_UseSpring: 0 + m_Spring: + spring: 100 + damper: 20 + targetPosition: 0 + m_UseMotor: 1 + m_Motor: + targetVelocity: 0 + force: 10 + freeSpin: 0 + m_UseLimits: 0 + m_Limits: + min: 0 + max: 0 + bounciness: 0 + bounceMinVelocity: 0.2 + contactDistance: 0 + m_BreakForce: Infinity + m_BreakTorque: Infinity + m_EnableCollision: 0 + m_EnablePreprocessing: 1 + m_MassScale: 1 + m_ConnectedMassScale: 1 +--- !u!1 &6698692811637545782 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 6698692811637545783} + - component: {fileID: 6698692811637545784} + - component: {fileID: 6698692811637545785} + m_Layer: 0 + m_Name: rear_left_wheel + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &6698692811637545783 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811637545782} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 6698692810479416266} + - {fileID: 6698692809717887723} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 3 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &6698692811637545784 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811637545782} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: cd2f2e3616277d4579d5a38545164e1a, type: 3} + m_Name: + m_EditorClassIdentifier: + _documentRoot: {fileID: 6698692810316458237} +--- !u!54 &6698692811637545785 +Rigidbody: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 6698692811637545782} + serializedVersion: 2 + m_Mass: 1 + m_Drag: 0 + m_AngularDrag: 0.05 + m_UseGravity: 1 + m_IsKinematic: 0 + m_Interpolate: 0 + m_Constraints: 0 + m_CollisionDetection: 0 +--- !u!1 &7021910287981836270 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 7041759074014604295} + m_Layer: 0 + m_Name: visuals + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &7041759074014604295 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 7021910287981836270} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 7028497365664568377} + m_Father: {fileID: 3954562668498932686} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &8360345738636226133 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 4081052963794407410} + - component: {fileID: 1909132087199892673} + - component: {fileID: 1846854308041689141} + m_Layer: 0 + m_Name: front_right_wheel + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &4081052963794407410 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 8360345738636226133} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 8402476309065344816} + - {fileID: 4920751528867295256} + m_Father: {fileID: 6698692811621179079} + m_RootOrder: 7 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &1909132087199892673 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 8360345738636226133} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: cd2f2e3616277d4579d5a38545164e1a, type: 3} + m_Name: + m_EditorClassIdentifier: + _documentRoot: {fileID: 6698692810316458237} +--- !u!54 &1846854308041689141 +Rigidbody: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 8360345738636226133} + serializedVersion: 2 + m_Mass: 1 + m_Drag: 0 + m_AngularDrag: 0.05 + m_UseGravity: 1 + m_IsKinematic: 0 + m_Interpolate: 0 + m_Constraints: 0 + m_CollisionDetection: 0 +--- !u!1 &8476149641634163636 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 8489885574144769606} + - component: {fileID: 2350633692197235798} + - component: {fileID: 8157718813092807422} + - component: {fileID: 4602369082354991715} + m_Layer: 0 + m_Name: right_wheel_visual + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &8489885574144769606 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 8476149641634163636} + m_LocalRotation: {x: 0, y: 0, z: 0.7071068, w: 0.7071068} + m_LocalPosition: {x: 0.17, y: -0.01, z: -0.1} + m_LocalScale: {x: 0.1, y: 0.01, z: 0.1} + m_Children: [] + m_Father: {fileID: 8402476309065344816} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 90} +--- !u!33 &2350633692197235798 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 8476149641634163636} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &8157718813092807422 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 8476149641634163636} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!136 &4602369082354991715 +CapsuleCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 8476149641634163636} + m_Material: {fileID: 13400000, guid: 006b6fc65c33dc9298961c5af7494b3a, type: 2} + m_IsTrigger: 0 + m_Enabled: 1 + m_Radius: 0.5000001 + m_Height: 2 + m_Direction: 1 + m_Center: {x: 0.000000059604645, y: 0, z: -0.00000008940697} diff --git a/Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab.meta b/Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab.meta new file mode 100644 index 0000000..49b52dd --- /dev/null +++ b/Samples~/ZeroSimSamples/Robots/SimpleAMR/SimpleAMR4wd.prefab.meta @@ -0,0 +1,7 @@ +fileFormatVersion: 2 +guid: 82ffd3a3b33fc80f7ab4c15174364269 +PrefabImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity b/Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity new file mode 100644 index 0000000..feaa427 --- /dev/null +++ b/Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity @@ -0,0 +1,1147 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!29 &1 +OcclusionCullingSettings: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_OcclusionBakeSettings: + smallestOccluder: 5 + smallestHole: 0.25 + backfaceThreshold: 100 + m_SceneGUID: 00000000000000000000000000000000 + m_OcclusionCullingData: {fileID: 0} +--- !u!104 &2 +RenderSettings: + m_ObjectHideFlags: 0 + serializedVersion: 9 + m_Fog: 0 + m_FogColor: {r: 0.5, g: 0.5, b: 0.5, a: 1} + m_FogMode: 3 + m_FogDensity: 0.01 + m_LinearFogStart: 0 + m_LinearFogEnd: 300 + m_AmbientSkyColor: {r: 0.212, g: 0.227, b: 0.259, a: 1} + m_AmbientEquatorColor: {r: 0.114, g: 0.125, b: 0.133, a: 1} + m_AmbientGroundColor: {r: 0.047, g: 0.043, b: 0.035, a: 1} + m_AmbientIntensity: 1 + m_AmbientMode: 0 + m_SubtractiveShadowColor: {r: 0.42, g: 0.478, b: 0.627, a: 1} + m_SkyboxMaterial: {fileID: 10304, guid: 0000000000000000f000000000000000, type: 0} + m_HaloStrength: 0.5 + m_FlareStrength: 1 + m_FlareFadeSpeed: 3 + m_HaloTexture: {fileID: 0} + m_SpotCookie: {fileID: 10001, guid: 0000000000000000e000000000000000, type: 0} + m_DefaultReflectionMode: 0 + m_DefaultReflectionResolution: 128 + m_ReflectionBounces: 1 + m_ReflectionIntensity: 1 + m_CustomReflection: {fileID: 0} + m_Sun: {fileID: 0} + m_IndirectSpecularColor: {r: 0.44278473, g: 0.4919318, b: 0.5717111, a: 1} + m_UseRadianceAmbientProbe: 0 +--- !u!157 &3 +LightmapSettings: + m_ObjectHideFlags: 0 + serializedVersion: 12 + m_GIWorkflowMode: 1 + m_GISettings: + serializedVersion: 2 + m_BounceScale: 1 + m_IndirectOutputScale: 1 + m_AlbedoBoost: 1 + m_EnvironmentLightingMode: 0 + m_EnableBakedLightmaps: 1 + m_EnableRealtimeLightmaps: 0 + m_LightmapEditorSettings: + serializedVersion: 12 + m_Resolution: 2 + m_BakeResolution: 40 + m_AtlasSize: 1024 + m_AO: 0 + m_AOMaxDistance: 1 + m_CompAOExponent: 1 + m_CompAOExponentDirect: 0 + m_ExtractAmbientOcclusion: 0 + m_Padding: 2 + m_LightmapParameters: {fileID: 0} + m_LightmapsBakeMode: 1 + m_TextureCompression: 1 + m_FinalGather: 0 + m_FinalGatherFiltering: 1 + m_FinalGatherRayCount: 256 + m_ReflectionCompression: 2 + m_MixedBakeMode: 2 + m_BakeBackend: 1 + m_PVRSampling: 1 + m_PVRDirectSampleCount: 32 + m_PVRSampleCount: 512 + m_PVRBounces: 2 + m_PVREnvironmentSampleCount: 256 + m_PVREnvironmentReferencePointCount: 2048 + m_PVRFilteringMode: 1 + m_PVRDenoiserTypeDirect: 1 + m_PVRDenoiserTypeIndirect: 1 + m_PVRDenoiserTypeAO: 1 + m_PVRFilterTypeDirect: 0 + m_PVRFilterTypeIndirect: 0 + m_PVRFilterTypeAO: 0 + m_PVREnvironmentMIS: 1 + m_PVRCulling: 1 + m_PVRFilteringGaussRadiusDirect: 1 + m_PVRFilteringGaussRadiusIndirect: 5 + m_PVRFilteringGaussRadiusAO: 2 + m_PVRFilteringAtrousPositionSigmaDirect: 0.5 + m_PVRFilteringAtrousPositionSigmaIndirect: 2 + m_PVRFilteringAtrousPositionSigmaAO: 1 + m_ExportTrainingData: 0 + m_TrainingDataDestination: TrainingData + m_LightProbeSampleCountMultiplier: 4 + m_LightingDataAsset: {fileID: 0} + m_LightingSettings: {fileID: 0} +--- !u!196 &4 +NavMeshSettings: + serializedVersion: 2 + m_ObjectHideFlags: 0 + m_BuildSettings: + serializedVersion: 2 + agentTypeID: 0 + agentRadius: 0.5 + agentHeight: 2 + agentSlope: 45 + agentClimb: 0.4 + ledgeDropHeight: 0 + maxJumpAcrossDistance: 0 + minRegionArea: 2 + manualCellSize: 0 + cellSize: 0.16666667 + manualTileSize: 0 + tileSize: 256 + accuratePlacement: 0 + maxJobWorkers: 0 + preserveTilesOutsideBounds: 0 + debug: + m_Flags: 0 + m_NavMeshData: {fileID: 0} +--- !u!1 &155950647 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 155950651} + - component: {fileID: 155950650} + - component: {fileID: 155950649} + - component: {fileID: 155950648} + m_Layer: 0 + m_Name: Plane + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!64 &155950648 +MeshCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 155950647} + m_Material: {fileID: 13400000, guid: 006b6fc65c33dc9298961c5af7494b3a, type: 2} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 4 + m_Convex: 0 + m_CookingOptions: 30 + m_Mesh: {fileID: 10209, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &155950649 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 155950647} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 2100000, guid: e115d419d8845cbbfb2488170128cdbd, type: 2} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!33 &155950650 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 155950647} + m_Mesh: {fileID: 10209, guid: 0000000000000000e000000000000000, type: 0} +--- !u!4 &155950651 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 155950647} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 10, y: 1, z: 10} + m_Children: [] + m_Father: {fileID: 0} + m_RootOrder: 2 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &310625171 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 310625172} + - component: {fileID: 310625175} + - component: {fileID: 310625174} + - component: {fileID: 310625173} + m_Layer: 0 + m_Name: Sphere + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &310625172 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 310625171} + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 1, y: 0.125, z: 1} + m_LocalScale: {x: 0.25, y: 0.25, z: 0.25} + m_Children: [] + m_Father: {fileID: 1751196169} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!135 &310625173 +SphereCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 310625171} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 2 + m_Radius: 0.5 + m_Center: {x: 0, y: 0, z: 0} +--- !u!23 &310625174 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 310625171} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 2100000, guid: ee87d3c7aff907920a745c6fd0164cf6, type: 2} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!33 &310625175 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 310625171} + m_Mesh: {fileID: 10207, guid: 0000000000000000e000000000000000, type: 0} +--- !u!1 &320649892 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 320649893} + - component: {fileID: 320649896} + - component: {fileID: 320649895} + - component: {fileID: 320649894} + m_Layer: 0 + m_Name: Cube + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &320649893 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 320649892} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: -1, y: 0.125, z: 1} + m_LocalScale: {x: 0.25, y: 0.25, z: 0.25} + m_Children: [] + m_Father: {fileID: 1751196169} + m_RootOrder: 2 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!65 &320649894 +BoxCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 320649892} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 2 + m_Size: {x: 1, y: 1, z: 1} + m_Center: {x: 0, y: 0, z: 0} +--- !u!23 &320649895 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 320649892} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 2100000, guid: bb8225f36fe78919ea691eba2e1551d3, type: 2} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!33 &320649896 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 320649892} + m_Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0} +--- !u!1 &445573325 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 445573327} + - component: {fileID: 445573326} + m_Layer: 0 + m_Name: Directional Light + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!108 &445573326 +Light: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 445573325} + m_Enabled: 1 + serializedVersion: 10 + m_Type: 1 + m_Shape: 0 + m_Color: {r: 1, g: 0.95686275, b: 0.8392157, a: 1} + m_Intensity: 1.5 + m_Range: 10 + m_SpotAngle: 30 + m_InnerSpotAngle: 21.80208 + m_CookieSize: 10 + m_Shadows: + m_Type: 2 + m_Resolution: -1 + m_CustomResolution: -1 + m_Strength: 1 + m_Bias: 0.05 + m_NormalBias: 0.4 + m_NearPlane: 0.2 + m_CullingMatrixOverride: + e00: 1 + e01: 0 + e02: 0 + e03: 0 + e10: 0 + e11: 1 + e12: 0 + e13: 0 + e20: 0 + e21: 0 + e22: 1 + e23: 0 + e30: 0 + e31: 0 + e32: 0 + e33: 1 + m_UseCullingMatrixOverride: 0 + m_Cookie: {fileID: 0} + m_DrawHalo: 0 + m_Flare: {fileID: 0} + m_RenderMode: 0 + m_CullingMask: + serializedVersion: 2 + m_Bits: 4294967295 + m_RenderingLayerMask: 1 + m_Lightmapping: 4 + m_LightShadowCasterMode: 0 + m_AreaSize: {x: 1, y: 1} + m_BounceIntensity: 1 + m_ColorTemperature: 6570 + m_UseColorTemperature: 0 + m_BoundingSphereOverride: {x: 0, y: 0, z: 0, w: 0} + m_UseBoundingSphereOverride: 0 + m_UseViewFrustumForShadowCasterCull: 1 + m_ShadowRadius: 0 + m_ShadowAngle: 0 +--- !u!4 &445573327 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 445573325} + m_LocalRotation: {x: 0.8266662, y: -0.17349371, z: 0.24594332, w: 0.47543132} + m_LocalPosition: {x: 0, y: 3, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 0} + m_RootOrder: 1 + m_LocalEulerAnglesHint: {x: 119.38, y: -29.51, z: 6.2} +--- !u!1001 &581202623 +PrefabInstance: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_Modification: + m_TransformParent: {fileID: 0} + m_Modifications: + - target: {fileID: 1733081356533547074, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_Enabled + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 1784391799965911495, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_IsActive + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 1949428794401804555, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_IsActive + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458208, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_Enabled + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458236, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_Name + value: SimpleAMR4wd + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_RootOrder + value: 6 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalPosition.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalPosition.y + value: 0.06 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalPosition.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalRotation.w + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalRotation.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalRotation.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalRotation.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalEulerAnglesHint.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalEulerAnglesHint.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 6698692810316458238, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + propertyPath: m_LocalEulerAnglesHint.z + value: 0 + objectReference: {fileID: 0} + m_RemovedComponents: [] + m_SourcePrefab: {fileID: 100100000, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} +--- !u!1 &679584921 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 679584923} + - component: {fileID: 679584922} + - component: {fileID: 679584924} + m_Layer: 0 + m_Name: ROSUnityManager + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!114 &679584922 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 679584921} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 9e021f5f19ac66f578dc0cb3ac939b09, type: 3} + m_Name: + m_EditorClassIdentifier: + _namespace: /zerosim + Hostname: localhost + Port: 9090 + _serializationType: 1 + _worldFrameId: map + _rootMapTransformPublisher: {fileID: 679584924} +--- !u!4 &679584923 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 679584921} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: -1.4877291, y: 1.0058386, z: 1.6348329} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 0} + m_RootOrder: 4 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &679584924 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 679584921} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 6013e0556113f1e9f95189e724e765fc, type: 3} + m_Name: + m_EditorClassIdentifier: + _updateRateHz: 1 + _debug: 0 + _currentUpdateHz: 0 + _currentFixedUpdateHz: 0 + _ROSTopic: + _name: ros.publisher.transform_ROSUnityManager + _frameId: map + _childFrameId: ros.publisher.transform_ROSUnityManager +--- !u!1 &1189395066 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 1189395070} + - component: {fileID: 1189395069} + - component: {fileID: 1189395068} + - component: {fileID: 1189395067} + m_Layer: 0 + m_Name: Sphere + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 0 +--- !u!135 &1189395067 +SphereCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1189395066} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 0 + serializedVersion: 2 + m_Radius: 0.5 + m_Center: {x: 0, y: 0, z: 0} +--- !u!23 &1189395068 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1189395066} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 10303, guid: 0000000000000000f000000000000000, type: 0} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!33 &1189395069 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1189395066} + m_Mesh: {fileID: 10207, guid: 0000000000000000e000000000000000, type: 0} +--- !u!4 &1189395070 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1189395066} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: -0.001, y: 0.2255, z: -0.0003} + m_LocalScale: {x: 0.01, y: 0.01, z: 0.01} + m_Children: [] + m_Father: {fileID: 0} + m_RootOrder: 3 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!4 &1292560734 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 6698692811621179079, guid: 82ffd3a3b33fc80f7ab4c15174364269, type: 3} + m_PrefabInstance: {fileID: 581202623} + m_PrefabAsset: {fileID: 0} +--- !u!1 &1298881059 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 1298881062} + - component: {fileID: 1298881061} + - component: {fileID: 1298881060} + - component: {fileID: 1298881063} + m_Layer: 0 + m_Name: Main Camera + m_TagString: MainCamera + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!81 &1298881060 +AudioListener: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1298881059} + m_Enabled: 1 +--- !u!20 &1298881061 +Camera: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1298881059} + m_Enabled: 1 + serializedVersion: 2 + m_ClearFlags: 1 + m_BackGroundColor: {r: 0.19215687, g: 0.3019608, b: 0.4745098, a: 0} + m_projectionMatrixMode: 1 + m_GateFitMode: 2 + m_FOVAxisMode: 0 + m_SensorSize: {x: 36, y: 24} + m_LensShift: {x: 0, y: 0} + m_FocalLength: 50 + m_NormalizedViewPortRect: + serializedVersion: 2 + x: 0 + y: 0 + width: 1 + height: 1 + near clip plane: 0.1 + far clip plane: 1000 + field of view: 39.9 + orthographic: 0 + orthographic size: 5 + m_Depth: -1 + m_CullingMask: + serializedVersion: 2 + m_Bits: 4294967295 + m_RenderingPath: -1 + m_TargetTexture: {fileID: 0} + m_TargetDisplay: 0 + m_TargetEye: 3 + m_HDR: 1 + m_AllowMSAA: 1 + m_AllowDynamicResolution: 0 + m_ForceIntoRT: 0 + m_OcclusionCulling: 1 + m_StereoConvergence: 10 + m_StereoSeparation: 0.022 +--- !u!4 &1298881062 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1298881059} + m_LocalRotation: {x: 0.33100855, y: 0, z: 0, w: 0.9436278} + m_LocalPosition: {x: 0, y: 0.3, z: -0.19} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: [] + m_Father: {fileID: 0} + m_RootOrder: 0 + m_LocalEulerAnglesHint: {x: 38.66, y: 0, z: 0} +--- !u!114 &1298881063 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1298881059} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 3e0e3af0b8141964b85373790012f3b9, type: 3} + m_Name: + m_EditorClassIdentifier: + target: {fileID: 1292560734} + _distance: 5 + _xSpeed: 120 + _ySpeed: 120 + _yMinLimit: -20 + _yMaxLimit: 80 + _distanceMin: 0.5 + _distanceMax: 15 +--- !u!1 &1719666800 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 1719666801} + - component: {fileID: 1719666804} + - component: {fileID: 1719666803} + - component: {fileID: 1719666802} + m_Layer: 0 + m_Name: Cylinder + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &1719666801 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1719666800} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: -1, y: 0.125, z: -1} + m_LocalScale: {x: 0.25, y: 0.25, z: 0.25} + m_Children: [] + m_Father: {fileID: 1751196169} + m_RootOrder: 3 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!136 &1719666802 +CapsuleCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1719666800} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + m_Radius: 0.5000001 + m_Height: 2 + m_Direction: 1 + m_Center: {x: 0.000000059604645, y: 0, z: -0.00000008940697} +--- !u!23 &1719666803 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1719666800} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 2100000, guid: 46784e6d4cd185c93b27050520d4b6e9, type: 2} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!33 &1719666804 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1719666800} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!1 &1751196168 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 1751196169} + m_Layer: 0 + m_Name: WorldObjects + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &1751196169 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1751196168} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_Children: + - {fileID: 2007358012} + - {fileID: 310625172} + - {fileID: 320649893} + - {fileID: 1719666801} + m_Father: {fileID: 0} + m_RootOrder: 5 + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1001 &2007358011 +PrefabInstance: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_Modification: + m_TransformParent: {fileID: 1751196169} + m_Modifications: + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_RootOrder + value: 0 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalScale.x + value: 0.1 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalScale.y + value: 0.1 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalScale.z + value: 0.1 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalPosition.x + value: 1 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalPosition.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalPosition.z + value: -1 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalRotation.w + value: 1 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalRotation.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalRotation.y + value: -0 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalRotation.z + value: -0 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalEulerAnglesHint.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalEulerAnglesHint.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_LocalEulerAnglesHint.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: -1585712058811843351, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_Materials.Array.data[0] + value: + objectReference: {fileID: 2100000, guid: 37267edc452ac7e45ba5aa147fe7360b, type: 2} + - target: {fileID: -1016883013007109646, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_Materials.Array.data[0] + value: + objectReference: {fileID: 2100000, guid: 37267edc452ac7e45ba5aa147fe7360b, type: 2} + - target: {fileID: -927199367670048503, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_Name + value: teapot + objectReference: {fileID: 0} + - target: {fileID: -890894850248633325, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_Materials.Array.data[0] + value: + objectReference: {fileID: 2100000, guid: 37267edc452ac7e45ba5aa147fe7360b, type: 2} + - target: {fileID: 7069507564420078126, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + propertyPath: m_Materials.Array.data[0] + value: + objectReference: {fileID: 2100000, guid: 37267edc452ac7e45ba5aa147fe7360b, type: 2} + m_RemovedComponents: [] + m_SourcePrefab: {fileID: 100100000, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} +--- !u!4 &2007358012 stripped +Transform: + m_CorrespondingSourceObject: {fileID: -4216859302048453862, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + m_PrefabInstance: {fileID: 2007358011} + m_PrefabAsset: {fileID: 0} +--- !u!1 &2007358013 stripped +GameObject: + m_CorrespondingSourceObject: {fileID: 2508814012279786317, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + m_PrefabInstance: {fileID: 2007358011} + m_PrefabAsset: {fileID: 0} +--- !u!1 &2007358014 stripped +GameObject: + m_CorrespondingSourceObject: {fileID: -7898622417764908945, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + m_PrefabInstance: {fileID: 2007358011} + m_PrefabAsset: {fileID: 0} +--- !u!1 &2007358015 stripped +GameObject: + m_CorrespondingSourceObject: {fileID: -8335632085496274664, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + m_PrefabInstance: {fileID: 2007358011} + m_PrefabAsset: {fileID: 0} +--- !u!1 &2007358016 stripped +GameObject: + m_CorrespondingSourceObject: {fileID: 4148893375777612310, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} + m_PrefabInstance: {fileID: 2007358011} + m_PrefabAsset: {fileID: 0} +--- !u!64 &2007358017 +MeshCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 2007358013} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 4 + m_Convex: 0 + m_CookingOptions: 30 + m_Mesh: {fileID: 8022488761877085130, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} +--- !u!64 &2007358018 +MeshCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 2007358014} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 4 + m_Convex: 0 + m_CookingOptions: 30 + m_Mesh: {fileID: 883126711037108357, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} +--- !u!64 &2007358019 +MeshCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 2007358015} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 4 + m_Convex: 0 + m_CookingOptions: 30 + m_Mesh: {fileID: -3111557506051347654, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} +--- !u!64 &2007358020 +MeshCollider: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 2007358016} + m_Material: {fileID: 0} + m_IsTrigger: 0 + m_Enabled: 1 + serializedVersion: 4 + m_Convex: 0 + m_CookingOptions: 30 + m_Mesh: {fileID: 6192547391499243942, guid: 17be92f99b8fb14eaa65adc226ac3fd4, type: 3} diff --git a/Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity.meta b/Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity.meta new file mode 100644 index 0000000..8e5e4d0 --- /dev/null +++ b/Samples~/ZeroSimSamples/Scenes/SimpleRobot4WD_test.unity.meta @@ -0,0 +1,7 @@ +fileFormatVersion: 2 +guid: ff5ddbbcb009b976e8d5163595adca14 +DefaultImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: