Robot sensor packages available on Unity. You can communicate sensor info via ROS and ROS2 using ROSTCPConnector and ROSTCPEndpoint.
The following sensors are added.
- 3D LiDAR (Velodyne VLP-16)
- 2D LiDAR (Hokuyo UST-30LX)
- RGB Camera (Logitech C910)
- IMU
There are several Prefab and Scene files available for testing each sensor. Check this directory.
Launch the ros_tcp_endpoint
with following command.
roslaunch ros_tcp_endpoint endpoint.launch
Launch the velodyne_pointcloud
package with following launch file.
Please create launch file by copy and paste following script.
The version of velodyne_pointcloud
package should be later than 1.6.0.
If you fail to lanch following launch file, please download velodyne package directoly into your workspace, build it, and launch them again.
https://github.com/ros-drivers/velodyne
<launch>
<arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml" />
<arg name="manager" default="velodyne_pointcloud" />
<arg name="max_range" default="100.0" />
<arg name="min_range" default="0.1" />
<node pkg="velodyne_pointcloud" type="transform_node" name="$(arg manager)">
<param name="model" value="VLP16"/>
<param name="calibration" value="$(arg calibration)"/>
<param name="max_range" value="$(arg max_range)"/>
<param name="min_range" value="$(arg min_range)"/>
<!-- <param name="view_direction" value="0"/> -->
<!-- <param name="view_width" value="360"/> -->
</node>
</launch>
Image communication between Unity and ROS is done using JPEG compression.
You can set the topic name in the Unity inspector window.
Note :
Message type is sensor_msgs/CompressedImage.
So, the topic name must end with "/compressed".
In order to handle sensor_msgs/CompressedImage,
launch the image_transport
package with following launch file.
Please create launch file by copy and paste following script.
<launch>
<node name="image_republish" pkg="image_transport"
type="republish" args="compressed raw">
<remap from="input" to="/image_raw/compressed" />
<remap from="output" to="/image_exp" />
</node>
</launch>
If you want to check the images in Rviz, you don't need to use the above launch file.
It can be used in the same way as a normal IMU sensor.
- Just to clone this repo with
git clone
command. - Then, open the project file with UnityHub.
- Finally, run the scene file for the sensor you want to test.
You can try all the sensors in the "Sensors
" scene file.
Copyright [2020-2021] Ryodo Tanaka groadpg@gmail.com
Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
- RosTCPConnector (Appache 2.0 LICENSE)