浏览代码

Updated pick & place tutorial for new message naming (#250)

/merge-resolve-conflicts
peifeng-unity 3 年前
当前提交
3a95ceed
共有 6 个文件被更改,包括 22 次插入22 次删除
  1. 14
      tutorials/pick_and_place/2_ros_tcp.md
  2. 12
      tutorials/pick_and_place/3_pick_and_place.md
  3. 2
      tutorials/pick_and_place/4_pick_and_place.md
  4. 2
      tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Unity.Robotics.RosMessages.asmdef
  5. 2
      tutorials/pick_and_place/PickAndPlaceProject/Packages/manifest.json
  6. 12
      tutorials/pick_and_place/Scripts_Part4/RealSimPickAndPlace.cs

14
tutorials/pick_and_place/2_ros_tcp.md


![](img/2_robottraj.png)
- One new C# script should populate the `Assets/RosMessages/Moveit/msg` directory: MRobotTrajectory. This name is the same as the message you built, with an "M" prefix (for message).
- One new C# script should populate the `Assets/RosMessages/Moveit/msg` directory: RobotTrajectoryMsg.cs. This name is the same as the message you built, with an "Msg" suffix (for message).
1. Next, the custom message scripts for this tutorial will need to be generated.

- Two new C# scripts should populate the `Assets/RosMessages/NiryoMoveit/msg` directory: MNiryoMoveitJoints and MNiryoTrajectory. MNiryoMoveitJoints describes a value for each joint in the Niryo arm as well as poses for the target object and target goal. MNiryoTrajectory describes a list of RobotTrajectory values, which will hold the calculated trajectories for the pick-and-place task.
- Two new C# scripts should populate the `Assets/RosMessages/NiryoMoveit/msg` directory: NiryoMoveitJointsMsg.cs and NiryoTrajectoryMsg.cs. The NiryoMoveitJoints message describes a value for each joint in the Niryo arm as well as poses for the target object and target goal. NiryoTrajectory describes a list of RobotTrajectory values, which will hold the calculated trajectories for the pick-and-place task.
> MessageGeneration generates a C# class from a ROS msg file with protections for use of C# reserved keywords and conversion to C# datatypes. Learn more about [ROS Messages](https://wiki.ros.org/Messages).

![](img/2_srv.png)
- Two new C# scripts should populate the `Assets/RosMessages/NiryoMoveit/srv` directory: MMoverServiceRequest and MMoverServiceResponse. These files describe the expected input and output formats for the service requests and responses when calculating trajectories.
- Two new C# scripts should populate the `Assets/RosMessages/NiryoMoveit/srv` directory: MoverServiceRequest and MoverServiceResponse. These files describe the expected input and output formats for the service requests and responses when calculating trajectories.
> MessageGeneration generates two C# classes, a request and response, from a ROS srv file with protections for use of C# reserved keywords and conversion to C# datatypes. Learn more about [ROS Services](https://wiki.ros.org/Services).

```csharp
public void Publish()
{
MNiryoMoveitJoints sourceDestinationMessage = new MNiryoMoveitJoints();
NiryoMoveitJointsMsg sourceDestinationMessage = new NiryoMoveitJointsMsg();
sourceDestinationMessage.joint_00 = jointArticulationBodies[0].xDrive.target;
sourceDestinationMessage.joint_01 = jointArticulationBodies[1].xDrive.target;

sourceDestinationMessage.joint_05 = jointArticulationBodies[5].xDrive.target;
// Pick Pose
sourceDestinationMessage.pick_pose = new MPose
sourceDestinationMessage.pick_pose = new PoseMsg
{
position = target.transform.position.To<FLU>(),
// The hardcoded x/z angles assure that the gripper is always positioned above the target cube before grasping.

// Place Pose
sourceDestinationMessage.place_pose = new MPose
sourceDestinationMessage.place_pose = new PoseMsg
{
position = targetPlacement.transform.position.To<FLU>(),
orientation = pickOrientation.To<FLU>()

> This function first takes in the current joint target values. Then, it grabs the poses of the `target` and the `targetPlacement` objects, adds them to the newly created message `sourceDestinationMessage`, and calls `Send()` to send this information to the ROS topic `topicName` (defined as `"SourceDestination_input"`).
> Note: Going from Unity world space to ROS world space requires a conversion. Unity's `(x,y,z)` is equivalent to the ROS `(z,-x,y)` coordinate. These conversions are provided via the [ROSGeometry component](https://github.com/Unity-Technologies/ROS-TCP-Connector/blob/main/ROSGeometry.md) in the ROS-TCP-Connector package.
> Note: Going from Unity world space to ROS world space requires a conversion. Unity's coordinate space has x Right, y Up, and z Forward (hence "RUF" coordinates); ROS has x Forward, y Left and z Up (hence "FLU"). So a Unity `(x,y,z)` coordinate is equivalent to the ROS `(z,-x,y)` coordinate. These conversions are done by the `To<FLU>` function in the ROS-TCP-Connector package's [ROSGeometry component](https://github.com/Unity-Technologies/ROS-TCP-Connector/blob/main/ROSGeometry.md).
1. Return to the Unity Editor. Now that the message contents have been defined and the publisher script added, it needs to be added to the Unity world to run its functionality.

12
tutorials/pick_and_place/3_pick_and_place.md


```csharp
public void PublishJoints()
{
MMoverServiceRequest request = new MMoverServiceRequest();
MoverServiceRequest request = new MoverServiceRequest();
request.pick_pose = new MPose
request.pick_pose = new PoseMsg
{
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.

// Place Pose
request.place_pose = new MPose
request.place_pose = new PoseMsg
ros.SendServiceMessage<MMoverServiceResponse>(rosServiceName, request, TrajectoryResponse);
ros.SendServiceMessage<MoverServiceResponse>(rosServiceName, request, TrajectoryResponse);
void TrajectoryResponse(MMoverServiceResponse response)
void TrajectoryResponse(MoverServiceResponse response)
{
if (response.trajectories != null)
{

> The `response.trajectories` are received in the `TrajectoryResponse()` callback, as defined in the `ros.SendServiceMessage` parameters. These trajectories are passed to `ExecuteTrajectories()` and executed as a [coroutine](https://docs.unity3d.com/Manual/Coroutines.html):
```csharp
private IEnumerator ExecuteTrajectories(MMoverServiceResponse response)
private IEnumerator ExecuteTrajectories(MoverServiceResponse response)
{
if (response.trajectories != null)
{

2
tutorials/pick_and_place/4_pick_and_place.md


- The ExecuteTrajectories function has been updated to accept a single RobotTrajectory object and execute the robot poses one at a time:
```csharp
private IEnumerator ExecuteTrajectories(RobotTrajectory trajectories)
private IEnumerator ExecuteTrajectories(RobotTrajectoryMsg trajectories)
{
// For every robot pose in trajectory plan
foreach (var point in trajectories.joint_trajectory.points)

2
tutorials/pick_and_place/PickAndPlaceProject/Assets/RosMessages/Unity.Robotics.RosMessages.asmdef


"autoReferenced": true,
"defineConstraints": [],
"versionDefines": [],
"noEngineReferences": true
"noEngineReferences": false
}

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


"com.unity.ide.rider": "2.0.7",
"com.unity.ide.visualstudio": "2.0.8",
"com.unity.ide.vscode": "1.2.3",
"com.unity.robotics.ros-tcp-connector": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git?path=/com.unity.robotics.ros-tcp-connector#v0.4.0",
"com.unity.robotics.ros-tcp-connector": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git?path=/com.unity.robotics.ros-tcp-connector#dev",
"com.unity.robotics.urdf-importer": "https://github.com/Unity-Technologies/URDF-Importer.git?path=/com.unity.robotics.urdf-importer#stl-package-import-fix",
"com.unity.test-framework": "1.1.24",
"com.unity.textmeshpro": "3.0.6",

12
tutorials/pick_and_place/Scripts_Part4/RealSimPickAndPlace.cs


/// </summary>
public void PublishJoints()
{
MMoverServiceRequest request = new MMoverServiceRequest
MoverServiceRequest request = new MoverServiceRequest
{
joints_input =
{

joint_04 = jointArticulationBodies[4].xDrive.target,
joint_05 = jointArticulationBodies[5].xDrive.target
},
pick_pose = new MPose
pick_pose = new PoseMsg
place_pose = new MPose
place_pose = new PoseMsg
{
position = (targetPlacement.transform.position + PICK_POSE_OFFSET).To<FLU>(),
orientation = pickOrientation.To<FLU>()

void Start()
{
ros.Subscribe<MRobotMoveActionGoal>(rosRobotCommandsTopicName, ExecuteRobotCommands);
ros.Subscribe<RobotMoveActionGoal>(rosRobotCommandsTopicName, ExecuteRobotCommands);
}
/// <summary>

/// </summary>
/// <param name="robotAction"> RobotMoveActionGoal of trajectory or gripper commands</param>
void ExecuteRobotCommands(MRobotMoveActionGoal robotAction)
void ExecuteRobotCommands(RobotMoveActionGoal robotAction)
{
if (robotAction.goal.cmd.cmd_type == TRAJECTORY_COMMAND_EXECUTION)
{

///
/// </summary>
/// <param name="trajectories"> The array of poses for the robot to execute</param>
private IEnumerator ExecuteTrajectories(MRobotTrajectory trajectories)
private IEnumerator ExecuteTrajectories(RobotTrajectoryMsg trajectories)
{
// For every robot pose in trajectory plan
foreach (var point in trajectories.joint_trajectory.points)

正在加载...
取消
保存