浏览代码

Visualizers

/laurie-Visualizers
LaurieCheers 4 年前
当前提交
2e87d1b1
共有 49 个文件被更改,包括 1583 次插入207 次删除
  1. 656
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scenes/Part1DoneScene.unity
  2. 2
      tutorials/pick_and_place/PickAndPlaceProject/Packages/manifest.json
  3. 4
      tutorials/pick_and_place/PickAndPlaceProject/ProjectSettings/ProjectVersion.txt
  4. 16
      tutorials/pick_and_place/PickAndPlaceProject/Assets/DebugDrawTest.cs
  5. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/DebugDrawTest.cs.meta
  6. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Resources.meta
  7. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages.meta
  8. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts.meta
  9. 46
      tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlit.shader
  10. 10
      tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlit.shader.meta
  11. 78
      tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlitMaterial.mat
  12. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlitMaterial.mat.meta
  13. 16
      tutorials/pick_and_place/PickAndPlaceProject/Assets/msgbrowser_settings.asset
  14. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/msgbrowser_settings.asset.meta
  15. 52
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Resources/ROSConnectionPrefab.prefab
  16. 7
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Resources/ROSConnectionPrefab.prefab.meta
  17. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit.meta
  18. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit/msg.meta
  19. 52
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit/msg/RobotTrajectory.cs
  20. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit/msg/RobotTrajectory.cs.meta
  21. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit.meta
  22. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg.meta
  23. 94
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoMoveitJoints.cs
  24. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoMoveitJoints.cs.meta
  25. 57
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoTrajectory.cs
  26. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoTrajectory.cs.meta
  27. 8
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv.meta
  28. 58
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceRequest.cs
  29. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceRequest.cs.meta
  30. 57
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceResponse.cs
  31. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceResponse.cs.meta
  32. 22
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceRequest_Visualizer.cs
  33. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceRequest_Visualizer.cs.meta
  34. 21
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceResponse_Visualizer.cs
  35. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceResponse_Visualizer.cs.meta
  36. 81
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/SourceDestinationPublisher.cs
  37. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/SourceDestinationPublisher.cs.meta
  38. 241
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryPlanner.cs
  39. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryPlanner.cs.meta
  40. 19
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryVisualizer.cs
  41. 11
      tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryVisualizer.cs.meta

656
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scenes/Part1DoneScene.unity
文件差异内容过多而无法显示
查看文件

2
tutorials/pick_and_place/PickAndPlaceProject/Packages/manifest.json


"com.unity.ide.rider": "2.0.7",
"com.unity.ide.visualstudio": "2.0.3",
"com.unity.ide.vscode": "1.2.2",
"com.unity.robotics.ros-tcp-connector": "file:C:/Users/laurie.cheers/Documents/GitHub/ROS-TCP-Connector",
"com.unity.robotics.ros-tcp-connector": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git#v0.1.2",
"com.unity.test-framework": "1.1.18",
"com.unity.textmeshpro": "3.0.1",
"com.unity.timeline": "1.4.3",

4
tutorials/pick_and_place/PickAndPlaceProject/ProjectSettings/ProjectVersion.txt


m_EditorVersion: 2020.2.0b9
m_EditorVersionWithRevision: 2020.2.0b9 (ef2968fa77ae)
m_EditorVersion: 2020.2.0b10
m_EditorVersionWithRevision: 2020.2.0b10 (19f63eee530c)

16
tutorials/pick_and_place/PickAndPlaceProject/Assets/DebugDrawTest.cs


using System.Collections;
using System.Collections.Generic;
using UnityEngine;
using FLU = ROSGeometry.FLU;
using RVector3 = ROSGeometry.Vector3<ROSGeometry.FLU>;
using static ROSGeometry.CoordinateSpaceExtensions;
public class DebugDrawTest : MonoBehaviour
{
public GameObject pivot;
void Start()
{
DebugDraw.Drawing drawing = DebugDraw.instance.CreateDrawing();
MessageVisualizations<FLU>.DrawQuaternion(drawing, pivot.transform.rotation.To<FLU>(), pivot.transform.position);
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/DebugDrawTest.cs.meta


fileFormatVersion: 2
guid: f4875bae0f034f742a49babbd5510b63
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/Resources.meta


fileFormatVersion: 2
guid: 397a6ccd0b2d60c4b8dffb1f50146e61
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages.meta


fileFormatVersion: 2
guid: 2fb24d38534f8574dab9d1f5c711c6d4
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts.meta


fileFormatVersion: 2
guid: f6b11d99e2678074a9e9ed6a81e48895
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

46
tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlit.shader


Shader "Unlit/VertexColorDebug"
{
Properties
{
}
SubShader
{
Tags { "RenderType"="Opaque" }
LOD 100
Pass
{
CGPROGRAM
#pragma vertex vert
#pragma fragment frag
#include "UnityCG.cginc"
struct appdata
{
float4 vertex : POSITION;
fixed4 color : COLOR;
};
struct v2f
{
float4 vertex : SV_POSITION;
fixed4 vertexColor : COLOR;
};
v2f vert (appdata v)
{
v2f o;
o.vertex = UnityObjectToClipPos(v.vertex);
o.vertexColor = v.color;
return o;
}
fixed4 frag (v2f i) : SV_Target
{
return i.vertexColor;
}
ENDCG
}
}
}

10
tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlit.shader.meta


fileFormatVersion: 2
guid: b1651fbb071c06b409fe12536561208a
ShaderImporter:
externalObjects: {}
defaultTextures: []
nonModifiableTextures: []
preprocessorOverride: 0
userData:
assetBundleName:
assetBundleVariant:

78
tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlitMaterial.mat


%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!21 &2100000
Material:
serializedVersion: 6
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_Name: VertexColorUnlitMaterial
m_Shader: {fileID: 4800000, guid: b1651fbb071c06b409fe12536561208a, type: 3}
m_ShaderKeywords:
m_LightmapFlags: 4
m_EnableInstancingVariants: 0
m_DoubleSidedGI: 0
m_CustomRenderQueue: -1
stringTagMap: {}
disabledShaderPasses: []
m_SavedProperties:
serializedVersion: 3
m_TexEnvs:
- _BumpMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailAlbedoMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailMask:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _DetailNormalMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _EmissionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MainTex:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _MetallicGlossMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _OcclusionMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
- _ParallaxMap:
m_Texture: {fileID: 0}
m_Scale: {x: 1, y: 1}
m_Offset: {x: 0, y: 0}
m_Floats:
- _BumpScale: 1
- _Cutoff: 0.5
- _DetailNormalMapScale: 1
- _DstBlend: 0
- _GlossMapScale: 1
- _Glossiness: 0.5
- _GlossyReflections: 1
- _Metallic: 0
- _Mode: 0
- _OcclusionStrength: 1
- _Parallax: 0.02
- _SmoothnessTextureChannel: 0
- _SpecularHighlights: 1
- _SrcBlend: 1
- _UVSec: 0
- _ZWrite: 1
m_Colors:
- _Color: {r: 1, g: 1, b: 1, a: 1}
- _EmissionColor: {r: 0, g: 0, b: 0, a: 1}
m_BuildTextureStacks: []

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/VertexColorUnlitMaterial.mat.meta


fileFormatVersion: 2
guid: a67a64473612f1a4d8e89a842f9a7fdc
NativeFormatImporter:
externalObjects: {}
mainObjectFileID: 0
userData:
assetBundleName:
assetBundleVariant:

16
tutorials/pick_and_place/PickAndPlaceProject/Assets/msgbrowser_settings.asset


%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!114 &11400000
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 0}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: c444d6f85828f1b4f9b89c7c387f9ddd, type: 3}
m_Name: msgbrowser_settings
m_EditorClassIdentifier:
inputPath: C:/Users/laurie.cheers/Documents/GitHub/Unity-Robotics-Hub/tutorials/pick_and_place/ROS/src
relativeOutPath: RosMessages

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/msgbrowser_settings.asset.meta


fileFormatVersion: 2
guid: ab4ee1607f23fa840962ebe964e85fa8
NativeFormatImporter:
externalObjects: {}
mainObjectFileID: 0
userData:
assetBundleName:
assetBundleVariant:

52
tutorials/pick_and_place/PickAndPlaceProject/Assets/Resources/ROSConnectionPrefab.prefab


%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!1 &7991040137969877657
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 5992195016282220192}
- component: {fileID: 5440181160353031565}
m_Layer: 0
m_Name: ROSConnectionPrefab
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &5992195016282220192
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 7991040137969877657}
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: 0}
m_RootOrder: 0
m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!114 &5440181160353031565
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 7991040137969877657}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: 7acef0b79454c9b4dae3f8139bc4ba77, type: 3}
m_Name:
m_EditorClassIdentifier:
rosIPAddress: 192.168.1.85
rosPort: 10000
overrideUnityIP:
unityPort: 5005
awaitDataMaxRetries: 10
awaitDataSleepSeconds: 1
showHUD: 1

7
tutorials/pick_and_place/PickAndPlaceProject/Assets/Resources/ROSConnectionPrefab.prefab.meta


fileFormatVersion: 2
guid: 73fe92fd799143e4e92a310df275d570
PrefabImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit.meta


fileFormatVersion: 2
guid: 619880e5903b5c04d8116cb9e456fbc5
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit/msg.meta


fileFormatVersion: 2
guid: 62d5515bc2092774c9609c5e8af42194
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

52
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit/msg/RobotTrajectory.cs


//Do not edit! This file was generated by Unity-ROS MessageGeneration.
using System;
using System.Linq;
using System.Collections.Generic;
using System.Text;
using RosMessageGeneration;
namespace RosMessageTypes.Moveit
{
public class RobotTrajectory : Message
{
public const string RosMessageName = "moveit_msgs/RobotTrajectory";
public Trajectory.JointTrajectory joint_trajectory;
public Trajectory.MultiDOFJointTrajectory multi_dof_joint_trajectory;
public RobotTrajectory()
{
this.joint_trajectory = new Trajectory.JointTrajectory();
this.multi_dof_joint_trajectory = new Trajectory.MultiDOFJointTrajectory();
}
public RobotTrajectory(Trajectory.JointTrajectory joint_trajectory, Trajectory.MultiDOFJointTrajectory multi_dof_joint_trajectory)
{
this.joint_trajectory = joint_trajectory;
this.multi_dof_joint_trajectory = multi_dof_joint_trajectory;
}
public override List<byte[]> SerializationStatements()
{
var listOfSerializations = new List<byte[]>();
listOfSerializations.AddRange(joint_trajectory.SerializationStatements());
listOfSerializations.AddRange(multi_dof_joint_trajectory.SerializationStatements());
return listOfSerializations;
}
public override int Deserialize(byte[] data, int offset)
{
offset = this.joint_trajectory.Deserialize(data, offset);
offset = this.multi_dof_joint_trajectory.Deserialize(data, offset);
return offset;
}
public override string ToString()
{
return "RobotTrajectory: " +
"\njoint_trajectory: " + joint_trajectory.ToString() +
"\nmulti_dof_joint_trajectory: " + multi_dof_joint_trajectory.ToString();
}
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Moveit/msg/RobotTrajectory.cs.meta


fileFormatVersion: 2
guid: 8aeefc546ca197245b0f582be5775d0c
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit.meta


fileFormatVersion: 2
guid: 71d5dbe802a9c2f44be18168e67f565b
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg.meta


fileFormatVersion: 2
guid: 70c67b69654af4f488ed9cafa83f6f12
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

94
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoMoveitJoints.cs


//Do not edit! This file was generated by Unity-ROS MessageGeneration.
using System;
using System.Linq;
using System.Collections.Generic;
using System.Text;
using RosMessageGeneration;
namespace RosMessageTypes.NiryoMoveit
{
public class NiryoMoveitJoints : Message
{
public const string RosMessageName = "niryo_moveit/NiryoMoveitJoints";
public double joint_00;
public double joint_01;
public double joint_02;
public double joint_03;
public double joint_04;
public double joint_05;
public Geometry.Pose pick_pose;
public Geometry.Pose place_pose;
public NiryoMoveitJoints()
{
this.joint_00 = 0.0;
this.joint_01 = 0.0;
this.joint_02 = 0.0;
this.joint_03 = 0.0;
this.joint_04 = 0.0;
this.joint_05 = 0.0;
this.pick_pose = new Geometry.Pose();
this.place_pose = new Geometry.Pose();
}
public NiryoMoveitJoints(double joint_00, double joint_01, double joint_02, double joint_03, double joint_04, double joint_05, Geometry.Pose pick_pose, Geometry.Pose place_pose)
{
this.joint_00 = joint_00;
this.joint_01 = joint_01;
this.joint_02 = joint_02;
this.joint_03 = joint_03;
this.joint_04 = joint_04;
this.joint_05 = joint_05;
this.pick_pose = pick_pose;
this.place_pose = place_pose;
}
public override List<byte[]> SerializationStatements()
{
var listOfSerializations = new List<byte[]>();
listOfSerializations.Add(BitConverter.GetBytes(this.joint_00));
listOfSerializations.Add(BitConverter.GetBytes(this.joint_01));
listOfSerializations.Add(BitConverter.GetBytes(this.joint_02));
listOfSerializations.Add(BitConverter.GetBytes(this.joint_03));
listOfSerializations.Add(BitConverter.GetBytes(this.joint_04));
listOfSerializations.Add(BitConverter.GetBytes(this.joint_05));
listOfSerializations.AddRange(pick_pose.SerializationStatements());
listOfSerializations.AddRange(place_pose.SerializationStatements());
return listOfSerializations;
}
public override int Deserialize(byte[] data, int offset)
{
this.joint_00 = BitConverter.ToDouble(data, offset);
offset += 8;
this.joint_01 = BitConverter.ToDouble(data, offset);
offset += 8;
this.joint_02 = BitConverter.ToDouble(data, offset);
offset += 8;
this.joint_03 = BitConverter.ToDouble(data, offset);
offset += 8;
this.joint_04 = BitConverter.ToDouble(data, offset);
offset += 8;
this.joint_05 = BitConverter.ToDouble(data, offset);
offset += 8;
offset = this.pick_pose.Deserialize(data, offset);
offset = this.place_pose.Deserialize(data, offset);
return offset;
}
public override string ToString()
{
return "NiryoMoveitJoints: " +
"\njoint_00: " + joint_00.ToString() +
"\njoint_01: " + joint_01.ToString() +
"\njoint_02: " + joint_02.ToString() +
"\njoint_03: " + joint_03.ToString() +
"\njoint_04: " + joint_04.ToString() +
"\njoint_05: " + joint_05.ToString() +
"\npick_pose: " + pick_pose.ToString() +
"\nplace_pose: " + place_pose.ToString();
}
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoMoveitJoints.cs.meta


fileFormatVersion: 2
guid: 2f469104fe6a28647b21119c61d201b3
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

57
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoTrajectory.cs


//Do not edit! This file was generated by Unity-ROS MessageGeneration.
using System;
using System.Linq;
using System.Collections.Generic;
using System.Text;
using RosMessageGeneration;
namespace RosMessageTypes.NiryoMoveit
{
public class NiryoTrajectory : Message
{
public const string RosMessageName = "niryo_moveit/NiryoTrajectory";
public Moveit.RobotTrajectory[] trajectory;
public NiryoTrajectory()
{
this.trajectory = new Moveit.RobotTrajectory[0];
}
public NiryoTrajectory(Moveit.RobotTrajectory[] trajectory)
{
this.trajectory = trajectory;
}
public override List<byte[]> SerializationStatements()
{
var listOfSerializations = new List<byte[]>();
listOfSerializations.Add(BitConverter.GetBytes(trajectory.Length));
foreach(var entry in trajectory)
listOfSerializations.Add(entry.Serialize());
return listOfSerializations;
}
public override int Deserialize(byte[] data, int offset)
{
var trajectoryArrayLength = DeserializeLength(data, offset);
offset += 4;
this.trajectory= new Moveit.RobotTrajectory[trajectoryArrayLength];
for(var i = 0; i < trajectoryArrayLength; i++)
{
this.trajectory[i] = new Moveit.RobotTrajectory();
offset = this.trajectory[i].Deserialize(data, offset);
}
return offset;
}
public override string ToString()
{
return "NiryoTrajectory: " +
"\ntrajectory: " + System.String.Join(", ", trajectory.ToList());
}
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/msg/NiryoTrajectory.cs.meta


fileFormatVersion: 2
guid: 7ea35c3ba31041648947bb748a0fbae6
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

8
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv.meta


fileFormatVersion: 2
guid: 0b0c05361b742724dba37b8b8c9d6d7c
folderAsset: yes
DefaultImporter:
externalObjects: {}
userData:
assetBundleName:
assetBundleVariant:

58
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceRequest.cs


//Do not edit! This file was generated by Unity-ROS MessageGeneration.
using System;
using System.Linq;
using System.Collections.Generic;
using System.Text;
using RosMessageGeneration;
namespace RosMessageTypes.NiryoMoveit
{
public class MoverServiceRequest : Message
{
public const string RosMessageName = "niryo_moveit/MoverService";
public NiryoMoveitJoints joints_input;
public Geometry.Pose pick_pose;
public Geometry.Pose place_pose;
public MoverServiceRequest()
{
this.joints_input = new NiryoMoveitJoints();
this.pick_pose = new Geometry.Pose();
this.place_pose = new Geometry.Pose();
}
public MoverServiceRequest(NiryoMoveitJoints joints_input, Geometry.Pose pick_pose, Geometry.Pose place_pose)
{
this.joints_input = joints_input;
this.pick_pose = pick_pose;
this.place_pose = place_pose;
}
public override List<byte[]> SerializationStatements()
{
var listOfSerializations = new List<byte[]>();
listOfSerializations.AddRange(joints_input.SerializationStatements());
listOfSerializations.AddRange(pick_pose.SerializationStatements());
listOfSerializations.AddRange(place_pose.SerializationStatements());
return listOfSerializations;
}
public override int Deserialize(byte[] data, int offset)
{
offset = this.joints_input.Deserialize(data, offset);
offset = this.pick_pose.Deserialize(data, offset);
offset = this.place_pose.Deserialize(data, offset);
return offset;
}
public override string ToString()
{
return "MoverServiceRequest: " +
"\njoints_input: " + joints_input.ToString() +
"\npick_pose: " + pick_pose.ToString() +
"\nplace_pose: " + place_pose.ToString();
}
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceRequest.cs.meta


fileFormatVersion: 2
guid: f8d9508fd5b7f824fb4e8390fed02e5d
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

57
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceResponse.cs


//Do not edit! This file was generated by Unity-ROS MessageGeneration.
using System;
using System.Linq;
using System.Collections.Generic;
using System.Text;
using RosMessageGeneration;
namespace RosMessageTypes.NiryoMoveit
{
public class MoverServiceResponse : Message
{
public const string RosMessageName = "niryo_moveit/MoverService";
public Moveit.RobotTrajectory[] trajectories;
public MoverServiceResponse()
{
this.trajectories = new Moveit.RobotTrajectory[0];
}
public MoverServiceResponse(Moveit.RobotTrajectory[] trajectories)
{
this.trajectories = trajectories;
}
public override List<byte[]> SerializationStatements()
{
var listOfSerializations = new List<byte[]>();
listOfSerializations.Add(BitConverter.GetBytes(trajectories.Length));
foreach(var entry in trajectories)
listOfSerializations.Add(entry.Serialize());
return listOfSerializations;
}
public override int Deserialize(byte[] data, int offset)
{
var trajectoriesArrayLength = DeserializeLength(data, offset);
offset += 4;
this.trajectories= new Moveit.RobotTrajectory[trajectoriesArrayLength];
for(var i = 0; i < trajectoriesArrayLength; i++)
{
this.trajectories[i] = new Moveit.RobotTrajectory();
offset = this.trajectories[i].Deserialize(data, offset);
}
return offset;
}
public override string ToString()
{
return "MoverServiceResponse: " +
"\ntrajectories: " + System.String.Join(", ", trajectories.ToList());
}
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/NiryoMoveit/srv/MoverServiceResponse.cs.meta


fileFormatVersion: 2
guid: 05907045186b92843bea732c160bbad1
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

22
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceRequest_Visualizer.cs


using RosMessageGeneration;
using RosMessageTypes.NiryoMoveit;
using System.Collections;
using System.Collections.Generic;
using UnityEngine;
using ROSGeometry;
[VisualizeMessage(typeof(MoverServiceRequest))]
public class MoverServiceRequest_Visualizer : MessageVisualizerDrawing<MoverServiceRequest>
{
public override void DrawGUI(DebugDraw.Drawing drawing, MoverServiceRequest message)
{
GUILayout.Label(message.ToString());
}
public override void Draw(DebugDraw.Drawing drawing, MoverServiceRequest message)
{
MessageVisualizations<FLU>.DrawPose(drawing, message.pick_pose, Color.cyan, "pick", 0.01f);
MessageVisualizations<FLU>.DrawPose(drawing, message.place_pose, Color.red, "place", 0.01f);
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceRequest_Visualizer.cs.meta


fileFormatVersion: 2
guid: 8e13c05e4fab9f941b5b5a6640c877a4
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

21
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceResponse_Visualizer.cs


using RosMessageGeneration;
using RosMessageTypes.NiryoMoveit;
using System.Collections;
using System.Collections.Generic;
using UnityEngine;
using ROSGeometry;
using RosMessageTypes.Moveit;
using RosMessageTypes.Trajectory;
[VisualizeMessage(typeof(MoverServiceResponse))]
public class MoverServiceResponse_Visualizer : MessageVisualizerDrawing<MoverServiceResponse>
{
public override void DrawGUI(DebugDraw.Drawing drawing, MoverServiceResponse message)
{
base.DrawGUI(drawing, message);
}
public override void Draw(DebugDraw.Drawing drawing, MoverServiceResponse message)
{
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/MoverServiceResponse_Visualizer.cs.meta


fileFormatVersion: 2
guid: 74c0c5694c76aad4b8aa00cf86ac6068
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

81
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/SourceDestinationPublisher.cs


using RosMessageTypes.Geometry;
using RosMessageTypes.NiryoMoveit;
using UnityEngine;
using ROSGeometry;
using Quaternion = UnityEngine.Quaternion;
public class SourceDestinationPublisher : MonoBehaviour
{
// ROS Connector
private ROSConnection ros;
// Variables required for ROS communication
public string topicName = "SourceDestination_input";
public GameObject niryoOne;
public GameObject target;
public GameObject targetPlacement;
private int numRobotJoints = 6;
private readonly Quaternion pickOrientation = Quaternion.Euler(90, 90, 0);
// Articulation Bodies
private ArticulationBody[] jointArticulationBodies;
/// <summary>
///
/// </summary>
void Start()
{
// Get ROS connection static instance
ros = ROSConnection.instance;
jointArticulationBodies = new ArticulationBody[numRobotJoints];
string shoulder_link = "world/base_link/shoulder_link";
jointArticulationBodies[0] = niryoOne.transform.Find(shoulder_link).GetComponent<ArticulationBody>();
string arm_link = shoulder_link + "/arm_link";
jointArticulationBodies[1] = niryoOne.transform.Find(arm_link).GetComponent<ArticulationBody>();
string elbow_link = arm_link + "/elbow_link";
jointArticulationBodies[2] = niryoOne.transform.Find(elbow_link).GetComponent<ArticulationBody>();
string forearm_link = elbow_link + "/forearm_link";
jointArticulationBodies[3] = niryoOne.transform.Find(forearm_link).GetComponent<ArticulationBody>();
string wrist_link = forearm_link + "/wrist_link";
jointArticulationBodies[4] = niryoOne.transform.Find(wrist_link).GetComponent<ArticulationBody>();
string hand_link = wrist_link + "/hand_link";
jointArticulationBodies[5] = niryoOne.transform.Find(hand_link).GetComponent<ArticulationBody>();
}
public void Publish()
{
NiryoMoveitJoints sourceDestinationMessage = new NiryoMoveitJoints();
sourceDestinationMessage.joint_00 = jointArticulationBodies[0].xDrive.target;
sourceDestinationMessage.joint_01 = jointArticulationBodies[1].xDrive.target;
sourceDestinationMessage.joint_02 = jointArticulationBodies[2].xDrive.target;
sourceDestinationMessage.joint_03 = jointArticulationBodies[3].xDrive.target;
sourceDestinationMessage.joint_04 = jointArticulationBodies[4].xDrive.target;
sourceDestinationMessage.joint_05 = jointArticulationBodies[5].xDrive.target;
// Pick Pose
sourceDestinationMessage.pick_pose = new RosMessageTypes.Geometry.Pose
{
position = target.transform.position.To<FLU>(),
orientation = Quaternion.Euler(90, target.transform.eulerAngles.y, 0).To<FLU>()
};
// Place Pose
sourceDestinationMessage.place_pose = new RosMessageTypes.Geometry.Pose
{
position = targetPlacement.transform.position.To<FLU>(),
orientation = pickOrientation.To<FLU>()
};
// Finally send the message to server_endpoint.py running in ROS
ros.Send(topicName, sourceDestinationMessage);
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/SourceDestinationPublisher.cs.meta


fileFormatVersion: 2
guid: 06585ee7d659e6a469710af18e9e0ad1
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

241
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryPlanner.cs


using System.Collections;
using System.Linq;
using RosMessageTypes.Geometry;
using RosMessageTypes.NiryoMoveit;
using UnityEngine;
using ROSGeometry;
using Quaternion = UnityEngine.Quaternion;
using RosImage = RosMessageTypes.Sensor.Image;
using Transform = UnityEngine.Transform;
using Vector3 = UnityEngine.Vector3;
public class TrajectoryPlanner : MonoBehaviour
{
// ROS Connector
private ROSConnection ros;
// Hardcoded variables
private int numRobotJoints = 6;
private readonly float jointAssignmentWait = 0.1f;
private readonly float poseAssignmentWait = 0.5f;
private readonly Vector3 pickPoseOffset = Vector3.up * 0.1f;
// Assures that the gripper is always positioned above the target cube before grasping.
private readonly Quaternion pickOrientation = Quaternion.Euler(90, 90, 0);
// Variables required for ROS communication
public string rosServiceName = "niryo_moveit";
public GameObject niryoOne;
public GameObject target;
public GameObject targetPlacement;
// Articulation Bodies
private ArticulationBody[] jointArticulationBodies;
private ArticulationBody leftGripper;
private ArticulationBody rightGripper;
private Transform gripperBase;
private Transform leftGripperGameObject;
private Transform rightGripperGameObject;
private enum Poses
{
PreGrasp,
Grasp,
PickUp,
Place
};
/// <summary>
/// Close the gripper
/// </summary>
private void CloseGripper()
{
var leftDrive = leftGripper.xDrive;
var rightDrive = rightGripper.xDrive;
leftDrive.target = -0.01f;
rightDrive.target = 0.01f;
leftGripper.xDrive = leftDrive;
rightGripper.xDrive = rightDrive;
}
/// <summary>
/// Open the gripper
/// </summary>
private void OpenGripper()
{
var leftDrive = leftGripper.xDrive;
var rightDrive = rightGripper.xDrive;
leftDrive.target = 0.01f;
rightDrive.target = -0.01f;
leftGripper.xDrive = leftDrive;
rightGripper.xDrive = rightDrive;
}
/// <summary>
/// Get the current values of the robot's joint angles.
/// </summary>
/// <returns>NiryoMoveitJoints</returns>
NiryoMoveitJoints CurrentJointConfig()
{
NiryoMoveitJoints joints = new NiryoMoveitJoints();
joints.joint_00 = jointArticulationBodies[0].xDrive.target;
joints.joint_01 = jointArticulationBodies[1].xDrive.target;
joints.joint_02 = jointArticulationBodies[2].xDrive.target;
joints.joint_03 = jointArticulationBodies[3].xDrive.target;
joints.joint_04 = jointArticulationBodies[4].xDrive.target;
joints.joint_05 = jointArticulationBodies[5].xDrive.target;
return joints;
}
/// <summary>
/// Create a new MoverServiceRequest with the current values of the robot's joint angles,
/// the target cube's current position and rotation, and the targetPlacement position and rotation.
///
/// Call the MoverService using the ROSConnection and if a trajectory is successfully planned,
/// execute the trajectories in a coroutine.
/// </summary>
public void PublishJoints()
{
MoverServiceRequest request = new MoverServiceRequest();
request.joints_input = CurrentJointConfig();
// Pick Pose
request.pick_pose = new RosMessageTypes.Geometry.Pose
{
position = (target.transform.position + pickPoseOffset).To<FLU>(),
// The hardcoded x/z angles assure that the gripper is always positioned above the target cube before grasping.
orientation = Quaternion.Euler(90, target.transform.eulerAngles.y, 0).To<FLU>()
};
// Place Pose
request.place_pose = new RosMessageTypes.Geometry.Pose
{
position = (targetPlacement.transform.position + pickPoseOffset).To<FLU>(),
orientation = pickOrientation.To<FLU>()
};
ros.SendServiceMessage<MoverServiceResponse>(rosServiceName, request, TrajectoryResponse);
}
void TrajectoryResponse(MoverServiceResponse response)
{
if (response.trajectories != null)
{
Debug.Log("Trajectory returned.");
StartCoroutine(ExecuteTrajectories(response));
}
else
{
Debug.LogError("No trajectory returned from MoverService.");
}
}
/// <summary>
/// Execute the returned trajectories from the MoverService.
///
/// The expectation is that the MoverService will return four trajectory plans,
/// PreGrasp, Grasp, PickUp, and Place,
/// where each plan is an array of robot poses. A robot pose is the joint angle values
/// of the six robot joints.
///
/// Executing a single trajectory will iterate through every robot pose in the array while updating the
/// joint values on the robot.
///
/// </summary>
/// <param name="response"> MoverServiceResponse received from niryo_moveit mover service running in ROS</param>
/// <returns></returns>
private IEnumerator ExecuteTrajectories(MoverServiceResponse response)
{
if (response.trajectories != null)
{
// For every trajectory plan returned
for (int poseIndex = 0 ; poseIndex < response.trajectories.Length; poseIndex++)
{
// For every robot pose in trajectory plan
for (int jointConfigIndex = 0 ; jointConfigIndex < response.trajectories[poseIndex].joint_trajectory.points.Length; jointConfigIndex++)
{
var jointPositions = response.trajectories[poseIndex].joint_trajectory.points[jointConfigIndex].positions;
float[] result = jointPositions.Select(r=> (float)r * Mathf.Rad2Deg).ToArray();
// Set the joint values for every joint
for (int joint = 0; joint < jointArticulationBodies.Length; joint++)
{
var joint1XDrive = jointArticulationBodies[joint].xDrive;
joint1XDrive.target = result[joint];
jointArticulationBodies[joint].xDrive = joint1XDrive;
}
// Wait for robot to achieve pose for all joint assignments
yield return new WaitForSeconds(jointAssignmentWait);
}
// Close the gripper if completed executing the trajectory for the Grasp pose
if (poseIndex == (int)Poses.Grasp)
CloseGripper();
// Wait for the robot to achieve the final pose from joint assignment
yield return new WaitForSeconds(poseAssignmentWait);
}
// All trajectories have been executed, open the gripper to place the target cube
OpenGripper();
}
}
/// <summary>
/// Find all robot joints in Awake() and add them to the jointArticulationBodies array.
/// Find left and right finger joints and assign them to their respective articulation body objects.
/// </summary>
void Start()
{
// Get ROS connection static instance
ros = ROSConnection.instance;
jointArticulationBodies = new ArticulationBody[numRobotJoints];
string shoulder_link = "world/base_link/shoulder_link";
jointArticulationBodies[0] = niryoOne.transform.Find(shoulder_link).GetComponent<ArticulationBody>();
string arm_link = shoulder_link + "/arm_link";
jointArticulationBodies[1] = niryoOne.transform.Find(arm_link).GetComponent<ArticulationBody>();
string elbow_link = arm_link + "/elbow_link";
jointArticulationBodies[2] = niryoOne.transform.Find(elbow_link).GetComponent<ArticulationBody>();
string forearm_link = elbow_link + "/forearm_link";
jointArticulationBodies[3] = niryoOne.transform.Find(forearm_link).GetComponent<ArticulationBody>();
string wrist_link = forearm_link + "/wrist_link";
jointArticulationBodies[4] = niryoOne.transform.Find(wrist_link).GetComponent<ArticulationBody>();
string hand_link = wrist_link + "/hand_link";
jointArticulationBodies[5] = niryoOne.transform.Find(hand_link).GetComponent<ArticulationBody>();
// Find left and right fingers
string right_gripper = hand_link + "/tool_link/gripper_base/servo_head/control_rod_right/right_gripper";
string left_gripper = hand_link + "/tool_link/gripper_base/servo_head/control_rod_left/left_gripper";
string gripper_base = hand_link + "/tool_link/gripper_base/Collisions/unnamed";
gripperBase = niryoOne.transform.Find(gripper_base);
leftGripperGameObject = niryoOne.transform.Find(left_gripper);
rightGripperGameObject = niryoOne.transform.Find(right_gripper);
rightGripper = rightGripperGameObject.GetComponent<ArticulationBody>();
leftGripper = leftGripperGameObject.GetComponent<ArticulationBody>();
}
public void DrawTrajectory(double[] positions, DebugDraw drawing)
{
/* for (int Idx = 0; Idx < positions.Length; ++Idx)
{
jointArticulationBodies[Idx].;
}*/
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryPlanner.cs.meta


fileFormatVersion: 2
guid: d86e71019fc456d49be97a121599370f
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:

19
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryVisualizer.cs


using System.Collections;
using System.Collections.Generic;
using UnityEngine;
public class TrajectoryVisualizer : MonoBehaviour
{
public static TrajectoryVisualizer instance;
public GameObject niryoOne;
private void Awake()
{
instance = this;
}
public void DrawRobot(float[] joints, DebugDraw drawing)
{
}
}

11
tutorials/pick_and_place/PickAndPlaceProject/Assets/Scripts/TrajectoryVisualizer.cs.meta


fileFormatVersion: 2
guid: d148d7ef98cbb66459510b8edc9b4146
MonoImporter:
externalObjects: {}
serializedVersion: 2
defaultReferences: []
executionOrder: 0
icon: {instanceID: 0}
userData:
assetBundleName:
assetBundleVariant:
正在加载...
取消
保存