Skip to content

Commit 3ada90b

Browse files
Final commits for v0.1.2 (#96)
* Final commits for v0.1.2
1 parent 0fa3ee3 commit 3ada90b

File tree

8 files changed

+55
-55
lines changed

8 files changed

+55
-55
lines changed

tutorials/pick_and_place/2_ros_tcp.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,7 @@ To enable communication between Unity and ROS, a TCP endpoint running as a ROS n
146146

147147
Opening the ROS Settings has created a ROSConnectionPrefab in `Assets/Resources` with the user-input settings. When the static `ROSConnection.instance` is referenced in a script, if a `ROSConnection` instance is not already present, the prefab will be instantiated in the Unity scene, and the connection will begin.
148148

149-
> Note: While using the ROS Settings menu is the suggested workflow, you may still manually create a GameObject with an attached ROSConnection component.
149+
> Note: While using the ROS Settings menu is the suggested workflow as of this version, you may still manually create a GameObject with an attached ROSConnection component.
150150
151151
1. Next, we will add a UI element that will allow user input to trigger the `Publish()` function. In the Hierarchy window, right click to add a new UI > Button. Note that this will create a new Canvas parent as well.
152152
> Note: In the `Game` view, you will see the button appear in the bottom left corner as an overlay. In `Scene` view the button will be rendered on a canvas object that may not be visible.

tutorials/pick_and_place/PickAndPlaceProject/Assets/DemoScripts/Demo.cs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ public class Demo : MonoBehaviour
5353
string scriptPattern = "*.cs";
5454

5555
string externalScriptsDirectory = "../Scripts";
56-
string scriptsDirectory = "Assets/Scripts";
56+
//string scriptsDirectory = "Assets/Scripts";
5757

5858
string rosConnectName = "ROSConnect";
5959
string publisherName = "Publisher";

tutorials/pick_and_place/PickAndPlaceProject/Packages/manifest.json

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,8 @@
44
"com.unity.ide.rider": "2.0.7",
55
"com.unity.ide.visualstudio": "2.0.3",
66
"com.unity.ide.vscode": "1.2.2",
7-
"com.unity.robotics.urdf-importer": "https://github.com/Unity-Technologies/URDF-Importer.git#v0.0.5",
8-
"com.unity.robotics.ros-tcp-connector": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git#v0.1.1",
7+
"com.unity.robotics.urdf-importer": "https://github.com/Unity-Technologies/URDF-Importer.git#v0.1.2",
8+
"com.unity.robotics.ros-tcp-connector": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git#v0.1.2",
99
"com.unity.test-framework": "1.1.18",
1010
"com.unity.textmeshpro": "3.0.1",
1111
"com.unity.timeline": "1.4.3",

tutorials/pick_and_place/ROS/src/niryo_moveit/scripts/server_endpoint.py

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -3,25 +3,22 @@
33
import rospy
44

55
from ros_tcp_endpoint import TcpServer, RosPublisher, RosSubscriber, RosService
6-
76
from niryo_moveit.msg import NiryoMoveitJoints, NiryoTrajectory
87
from niryo_moveit.srv import MoverService
98

109

1110
def main():
1211
ros_node_name = rospy.get_param("/TCP_NODE_NAME", 'TCPServer')
1312
tcp_server = TcpServer(ros_node_name)
13+
rospy.init_node(ros_node_name, anonymous=True)
1414

15-
# Create ROS communication objects dictionary for routing messages
16-
tcp_server.source_destination_dict = {
15+
# Start the Server Endpoint with a ROS communication objects dictionary for routing messages
16+
tcp_server.start({
1717
'SourceDestination_input': RosPublisher('SourceDestination', NiryoMoveitJoints, queue_size=10),
1818
'NiryoTrajectory': RosSubscriber('NiryoTrajectory', NiryoTrajectory, tcp_server),
1919
'niryo_moveit': RosService('niryo_moveit', MoverService)
20-
}
21-
22-
# Start the Server Endpoint
23-
rospy.init_node(ros_node_name, anonymous=True)
24-
tcp_server.start()
20+
})
21+
2522
rospy.spin()
2623

2724

16.4 KB
Loading

tutorials/ros_packages/robotics_demo/scripts/server_endpoint.py

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
import rospy
44

55
from ros_tcp_endpoint import TcpServer, RosPublisher, RosSubscriber, RosService
6-
76
from robotics_demo.msg import PosRot, UnityColor
87
from robotics_demo.srv import PositionService
98

@@ -12,15 +11,14 @@ def main():
1211
buffer_size = rospy.get_param("/TCP_BUFFER_SIZE", 1024)
1312
connections = rospy.get_param("/TCP_CONNECTIONS", 10)
1413
tcp_server = TcpServer(ros_node_name, buffer_size, connections)
15-
16-
tcp_server.source_destination_dict = {
14+
rospy.init_node(ros_node_name, anonymous=True)
15+
16+
tcp_server.start({
1717
'pos_srv': RosService('position_service', PositionService),
1818
'pos_rot': RosPublisher('pos_rot', PosRot, queue_size=10),
1919
'color': RosSubscriber('color', UnityColor, tcp_server)
20-
}
21-
22-
rospy.init_node(ros_node_name, anonymous=True)
23-
tcp_server.start()
20+
})
21+
2422
rospy.spin()
2523

2624

tutorials/ros_unity_integration/server_endpoint.md

Lines changed: 40 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@ The following is an example of a server endpoint Python script that:
1515
import rospy
1616

1717
from ros_tcp_endpoint import TcpServer, RosPublisher, RosSubscriber, RosService
18-
1918
from robotics_demo.msg import PosRot, UnityColor
2019
from robotics_demo.srv import PositionService
2120

@@ -24,15 +23,14 @@ def main():
2423
buffer_size = rospy.get_param("/TCP_BUFFER_SIZE", 1024)
2524
connections = rospy.get_param("/TCP_CONNECTIONS", 10)
2625
tcp_server = TcpServer(ros_node_name, buffer_size, connections)
27-
28-
tcp_server.source_destination_dict = {
26+
rospy.init_node(ros_node_name, anonymous=True)
27+
28+
tcp_server.start({
2929
'pos_srv': RosService('position_service', PositionService),
3030
'pos_rot': RosPublisher('pos_rot', PosRot, queue_size=10),
3131
'color': RosSubscriber('color', UnityColor, tcp_server)
32-
}
33-
34-
rospy.init_node(ros_node_name, anonymous=True)
35-
tcp_server.start()
32+
})
33+
3634
rospy.spin()
3735

3836

@@ -44,7 +42,6 @@ if __name__ == "__main__":
4442
## Import Statements for Services and Messages
4543
```python
4644
from ros_tcp_endpoint import TcpServer, RosPublisher, RosSubscriber, RosService
47-
4845
from robotics_demo.msg import PosRot, UnityColor
4946
from robotics_demo.srv import PositionService
5047
```
@@ -56,63 +53,71 @@ Requires:
5653
- The ROS node name
5754

5855
```python
59-
tcp_server = TcpServer(ros_node_name, buffer_size=1024, connections=10)
56+
tcp_server = TcpServer(ros_node_name, buffer_size, connections)
6057
```
6158

62-
The `ros_node_name` is required and the `buffer_size` and `connections` are optional. They are set to `1024` and `10` by default if not provided in the constructor arguments.
59+
The `ros_node_name` argument is required and the `buffer_size` and `connections` are optional. They are set to `1024` and `10` by default if not provided in the constructor arguments.
6360

64-
## Source Destination Dictionary
61+
## Instantiate the ROS Node
6562

66-
Create a dictionary keyed by topic or service with the corresponding ROS communication class as the value. The dictionary is used by the TCP server to direct messages to and from the ROS network.
63+
```python
64+
rospy.init_node(ros_node_name, anonymous=True)
65+
```
66+
67+
## Starting the Server
6768

6869
```python
69-
tcp_server.source_destination_dict = {
70+
tcp_server.start({
7071
'pos_srv': RosService('position_service', PositionService),
7172
'pos_rot': RosPublisher('pos_rot', PosRot, queue_size=10),
72-
'color': RosSubscriber('color', Color, tcp_server),
73-
}
73+
'color': RosSubscriber('color', UnityColor, tcp_server)
74+
})
75+
76+
rospy.spin()
7477
```
7578

76-
## ROS Service
77-
A ROS Service requires two components:
78-
79-
- Service name
80-
- ROS Service class generated from running `catkin_make` command
79+
## Source Destination Dictionary
8180

82-
`RosService('position_service', PositionService)`
81+
The argument to start() is a dictionary keyed by topic or service with the corresponding ROS communication class as the value. The dictionary is used by the TCP server to direct messages to and from the ROS network.
8382

8483
## ROS Publisher
85-
A ROS Publisher requires three components:
84+
A ROS Publisher allows a Unity component to send messages on a given topic to other ROS nodes. It requires three components:
8685

8786
- Topic name
8887
- ROS message class generated from running `catkin_make` command
89-
- Queue size
88+
- Queue size (optional)
9089

9190
`RosPublisher('pos_rot', PosRot, queue_size=10)`
9291

9392
## ROS Subscriber
94-
A ROS Subscriber requires three components:
93+
A ROS Subscriber allows a Unity component to receive messages from other ROS nodes on a given topic. It requires three components:
9594

9695
- Topic name
9796
- ROS message class generated from running `catkin_make` command
9897
- The tcp server that will connect to Unity
9998

10099
`RosSubscriber('color', UnityColor, tcp_server)`
101100

102-
## Instantiate the ROS Node
101+
## ROS Service
102+
A ROS Service is similar to a RosPublisher, in that a Unity component sends a Request message to another ROS node. Unlike a Publisher, the Unity component then waits for a Response back. It requires two components:
103103

104-
```python
105-
rospy.init_node(ros_node_name, anonymous=True)
106-
```
104+
- Service name
105+
- ROS Service class generated from running `catkin_make` command
107106

108-
## Starting the Server
107+
`RosService('position_service', PositionService)`
108+
109+
## Unity Service
110+
111+
A Unity Service is similar to a RosSubscriber, in that a Unity component receives a Request message from another ROS node. It then sends a Response back. It requires three components:
112+
113+
- Service name
114+
- ROS Service class generated from running `catkin_make` command
115+
- The tcp server that will connect to Unity
116+
117+
`UnityService('unity_service', PositionService, tcp_server)`
109118

110-
```python
111-
tcp_server.start()
112-
rospy.spin()
113-
114-
```
115119

120+
## Parameters
116121

117122
The following parameters can be hardcoded, but for the sake of portability, we recommend setting the parameters using the `rosparam set` command, or a `rosparam` YAML file.
118123

@@ -132,7 +137,7 @@ An example launch file that will set the appropriate ROSPARAM values required fo
132137
```
133138
<launch>
134139
135-
<env name="ROS_IP" value="192.168.1.116"/>
140+
<env name="ROS_IP" value="127.0.0.1"/>
136141
<env name="ROS_HOSTNAME" value="$(env ROS_IP)"/>
137142
138143
<param name="ROS_IP" type="str" value="$(env ROS_IP)" />

0 commit comments

Comments
 (0)