目录
- 概要
- 创建 Unity 发布服务器
- 启动 Echo 监视器
- 创建 Unity 订阅服务器
概要
创建 Unity 发布服务器
- 在 Unity 的“项目”选项卡中,创建一个新的 C# 脚本并为其命名
RosPublisherExample
。将以下代码粘贴到新的脚本文件中。
using UnityEngine;
using Unity.Robotics.ROSTCPConnector;
using RosMessageTypes.UnityRoboticsDemo;
/// <summary>
///
/// </summary>
public class RosPublisherExample : MonoBehaviour
{
ROSConnection ros;
public string topicName = "pos_rot";
// The game object
public GameObject cube;
// Publish the cube's position and rotation every N seconds
public float publishMessageFrequency = 0.5f;
// Used to determine how much time has elapsed since the last message was published
private float timeElapsed;
void Start()
{
// start the ROS connection
ros = ROSConnection.GetOrCreateInstance();
ros.RegisterPublisher<PosRotMsg>(topicName);
}
private void Update()
{
timeElapsed += Time.deltaTime;
if (timeElapsed > publishMessageFrequency)
{
cube.transform.rotation = Random.rotation;
PosRotMsg cubePos = new PosRotMsg(
cube.transform.position.x,
cube.transform.position.y,
cube.transform.position.z,
cube.transform.rotation.x,
cube.transform.rotation.y,
cube.transform.rotation.z,
cube.transform.rotation.w
);
// Finally send the message to server_endpoint.py running in ROS
ros.Publish(topicName, cubePos);
timeElapsed = 0;
}
}
}
- 将 Plane 和 Cube 添加到 Unity 场景。可以在 Unity 中创建简单的几何形状,方法是转到 Hierarchy 窗口,单击 + 按钮,然后导航到要创建的形状。

- 在层次结构窗口中选择立方体,然后单击 Unity 窗口左上角工具栏中的移动工具,将立方体向上移动一点,使其悬停在平面上方。
- 创建一个空游戏对象,为其命名
RosPublisher
并附加脚本 RosPublisherExample
(如图所示,脚本拖到右边以添加),同时将 Cube 游戏对象拖动到参数 Cube
上。

~/HardDisk/Unity/Unity-Robotics-Hub$ docker run -it --rm -p 10000:10000 melodic /bin/bash
roscore & rosrun ros_tcp_endpoint default_server_endpoint.py

Game 窗口左上角的连接指示灯变为蓝色,其中的 Cube 在旋转
[INFO] [1668060958.002336]: Connection from 172.17.0.1
[ERROR] [1668060958.004085]: Failed to resolve message name: No module named tf2_msgs.msg
[INFO] [1668060958.008458]: RegisterPublisher(pos_rot, <class 'unity_robotics_demo_msgs.msg._PosRot.PosRot'>) OK
[INFO] [1668060958.010205]: RegisterPublisher(pos_rot, <class 'unity_robotics_demo_msgs.msg._PosRot.PosRot'>) OK
启动 Echo 监视器
# 中间很长的那段是我的容器 id ,换成自己的即可
docker exec -it 371679e8a81c52185919524528c67909a80b9f97f6ae460e9bbc85f5bd704e20 /bin/bash
# 也可以使用容器的 name 来启动
docker ps # 查看正在运行的容器列表
docker exec -ti upbeat_lichterman bash # 其中,upbeat_lichterman 是我这个容器的 Name
- 为了证明 ROS 确实接收了消息,可以运行 rostopic echo 命令。
# 在 ROS1 中,打开一个新的终端窗口,导航到 ROS 工作区,然后运行以下命令:
source devel/setup.bash
rostopic echo pos_rot
# 在 ROS2 中,要运行的命令是
source install/setup.bash
ros2 topic echo pos_rot

Unity 发送的消息的内容每 0.5 秒出现一次
创建 Unity 订阅服务器
- 在 Unity 中,创建一个新的 C# 脚本并为其命名
RosSubscriberExample
。将以下代码粘贴到新的脚本文件中。
- 创建一个空游戏对象,为其命名
RosSubscriber
并附加脚本 RosSubscriberExample
(如图所示,脚本拖到右边以添加),同时将 Cube 游戏对象拖动到参数 Cube
上。

chmod 777 src/unity_robotics_demo/scripts/color_publisher.py
- 发送一条颜色消息,将 Unity 中立方体游戏对象的颜色更改为随机颜色。
roscore
rosrun ros_tcp_endpoint default_server_endpoint.py
rosrun unity_robotics_demo color_publisher.py # 如果使用的是 ROS2 ,除了前面的命令不一样,这一步也要改成 ros2 run unity_robotics_demo color_publisher

可以看到立方体会随机切换颜色
评论(2)
您还未登录,请登录后发表或查看评论