Skip to content

Commit

Permalink
Merge pull request #45 from MartinBischoff/master
Browse files Browse the repository at this point in the history
New ROS# message handling framework
  • Loading branch information
MartinBischoff authored Mar 9, 2018
2 parents da2af1f + b74dfa6 commit b36dcfb
Show file tree
Hide file tree
Showing 147 changed files with 30,824 additions and 1,437 deletions.
60 changes: 29 additions & 31 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,37 +1,34 @@
# [<img src="https://github.com/siemens/ros-sharp/wiki/img/RosSharpLogo.png" width="480" alt ="ROS#"/>](https://github.com/siemens/ros-sharp) #

... is a set of open source software libraries and tools in [C\# ](https://docs.microsoft.com/de-de/dotnet/csharp/csharp) for communicating with [ROS](http://www.ros.org/) from .[NET](https://www.microsoft.com/net) applications, in particular [Unity3D](https://unity3d.com/).
[ROS#](https://github.com/siemens/ros-sharp) is a set of open source software libraries and tools in [C\# ](https://docs.microsoft.com/de-de/dotnet/csharp/csharp) for communicating with [ROS](http://www.ros.org/) from .[NET](https://www.microsoft.com/net) applications, in particular [Unity](https://unity3d.com/).

Find some examples what you can do with ROS# [here](https://github.com/siemens/ros-sharp/wiki/Info_Showcases).

## Contents: ##
## Contents ##

### [RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient) ###
... provides a [.NET](https://www.microsoft.com/net) API to [ROS](http://www.ros.org/) via [rosbridge_suite](http://wiki.ros.org/rosbridge_suite).
* [RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient): a [.NET](https://www.microsoft.com/net) API to [ROS](http://www.ros.org/) via [rosbridge_suite](http://wiki.ros.org/rosbridge_suite)
* [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter): a [URDF](http://wiki.ros.org/urdf) file parser for [.NET](https://www.microsoft.com/net) applications
* [ROS](https://github.com/siemens/ros-sharp/tree/master/ROS) some helpful [ROS](http://wiki.ros.org/) packages
* [Unity3D](https://github.com/siemens/ros-sharp/tree/master/Unity3D): a [Unity](https://unity3d.com/) project
providing Unity-specific extensions to
[RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient) and
[UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter)

### [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter) ###
... provides a [URDF](http://wiki.ros.org/urdf) file parser for [.NET](https://www.microsoft.com/net) applications.
## Releases ##
In addition to the source code, [Releases](https://github.com/siemens/ros-sharp/releases) contain:

### [ROS](https://github.com/siemens/ros-sharp/tree/master/ROS) ###
... contains code for [ROS](http://wiki.ros.org/) nodes and [ROS](http://wiki.ros.org/) launch files which are useful to [RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient) and/or [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter).

### [Unity3D](https://github.com/siemens/ros-sharp/tree/master/Unity3D) ###
... is a [Unity3D](https://unity3d.com/) reference project providing [Unity3D](https://unity3d.com/)-specifc extensions to
* [RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient)
* [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter)
* a [Unity Asset Package](https://docs.unity3d.com/Manual/AssetPackages.html) containing the [Unity3D](https://github.com/siemens/ros-sharp/tree/master/Unity3D) project assets:
* to be imported in other Unity projects using ROS#.
* binaries of [RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient) and [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter)
* to be used in other .NET projects using these libraries.

### [Release](https://github.com/siemens/ros-sharp/tree/master/Release) ###
... contains [RosSharp.unitypackage](https://github.com/siemens/ros-sharp/tree/master/Release/RosSharp.unitypackage)
the latest package of [ROS#](https://github.com/siemens/ros-sharp) assets from the [Unity3D](https://github.com/siemens/ros-sharp/tree/master/Unity3D) project.
Please get the latest development version directly from the [tip of the ROS# master branch](https://github.com/siemens/ros-sharp).

### [Tutorials](https://github.com/siemens/ros-sharp/tree/master/Tutorials) ###
... contains Unity3D tutorial projects described described in the [Wiki](https://github.com/siemens/ros-sharp/wiki).

## Licensing: ##
## Licensing ##

ROS# is open source under the [Apache 2.0 license](http://www.apache.org/licenses/LICENSE-2.0) and is free for commercial use.

## External Dependencies: ##
## External Dependencies ##

[RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient) uses the following 3rd party libraries:
* `websocket-sharp.dll` from [websocket-sharp](https://github.com/sta/websocket-sharp) provided under MIT License.
Expand All @@ -41,29 +38,30 @@ ROS# is open source under the [Apache 2.0 license](http://www.apache.org/license
* `MathNet.Numerics.dll` from [Math.NET Numerics](https://numerics.mathdotnet.com/) provided under MIT License.
* `System.Threading.dll` from [TaskParallelLibrary for .NET 3.5](https://www.nuget.org/packages/TaskParallelLibrary/1.0.2856) provided under [MS-EULA License](https://msdn.microsoft.com/en-us/hh295787).

## .NET Standard 2.0: ##
## .NET Standard 2.0 ##
Both [RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient)
and [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter)
are running on .NET Framework 3.5 as this is the .NET platform currently supported by official Unity3D releases.
are running on .NET Framework 3.5 as this is the .NET platform currently supported by official Unity releases.

For Non-Unity3D-Applications [blommers](https://github.com/blommers) kindly provides a
For Non-Unity-Applications [blommers](https://github.com/blommers) kindly provides a
[.NET Standard 2.0 version of UrdfImporter](https://github.com/blommers/UdrfImporter).

## Special Thanks: ##
## Special Thanks ##

* [Rahul Warrier](https://github.com/jaguar243) for adjusting the code to enable its open source publication.
* [Verena Roehrl](https://github.com/roehrlverena) for providing the Wiki pages and the tutorial projects.
* [Karl Henkel](https://github.com/karl-) for providing the [reference](https://github.com/karl-/pb_Stl) for the Unity3D STL mesh importer used in this project.
* [Jeremy Fix](https://github.com/jeremyfix) for providing the [CameraImagePublisher](https://github.com/siemens/ros-sharp/blob/master/Unity3D/Assets/RosSharp/Scripts/CameraImagePublisher.cs) and [VelocitySubscriber](https://github.com/siemens/ros-sharp/blob/master/Unity3D/Assets/RosSharp/Scripts/VelocitySubscriber.cs)
* [Verena Roehrl](https://github.com/roehrlverena) for providing ROS packages, Wiki pages and Unity example scenes.
* [Karl Henkel](https://github.com/karl-) for providing the [reference](https://github.com/karl-/pb_Stl) for the Unity STL mesh importer used in this project.
* [Jeremy Fix](https://github.com/jeremyfix) for providing some helpful ROS communication example scripts in Unity.
* [Berkay Alp Cakal](https://github.com/berkayalpcakal) for providing ROS packages, Wiki pages and Unity example scenes.

* [Interested in contributing as well?](CONTRIBUTING.md)

## Further Info: ##
## Further Info ##
* [Read the Wiki](https://github.com/siemens/ros-sharp/wiki).
* [Contact the Project Team](mailto:[email protected]).
* [Contact the project team](mailto:[email protected]).

---

© Siemens AG, 2017
© Siemens AG, 2017-2018

Author: Dr. Martin Bischoff ([email protected])
21 changes: 11 additions & 10 deletions ROS/README.md
Original file line number Diff line number Diff line change
@@ -1,20 +1,21 @@
# [ROS](https://github.com/siemens/ros-sharp/tree/master/ROS) #
... contains code for [ROS](http://wiki.ros.org/) nodes and [ROS](http://wiki.ros.org/) launch files which are useful to [RosBridgeClient](https://github.com/siemens/ros-sharp/tree/master/RosBridgeClient) and/or [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter).
contains the following [ROS](http://wiki.ros.org/) packages:

## [file_server](https://github.com/siemens/ros-sharp/tree/master/ROS/file_server)
... provides a [ROS](http://www.ros.org/) node with a service to send file contents.
* [file_server](https://github.com/siemens/ros-sharp/tree/master/ROS/file_server)
* Launch [file_server.launch](https://github.com/MartinBischoff/ros-sharp/blob/master/ROS/file_server/launch/file_server.launch) to provide the ROS service `/file_server/get_file` for sending file contents.
This service is called by [UrdfIUmporter.cs](https://github.com/siemens/ros-sharp/blob/master/RosBridgeClient/UrdfImporter.cs) to receive URDF resource files (meshes and textures) via [rosbridge_suite](http://wiki.ros.org/rosbridge_suite).
* Launch [publish_description_turtlebot2.launch] (https://github.com/MartinBischoff/ros-sharp/blob/master/ROS/file_server/launch/publish_description_turtlebot2.launch) to provide the ROS `/robot_description` parameter for [Turtlebot2](http://wiki.ros.org/Robots/TurtleBot).

... is required for receiving meshes and textures referenced in a [URDF](http://wiki.ros.org/urdf) via [UrdfImporter](https://github.com/siemens/ros-sharp/tree/master/UrdfImporter).
* [gazebo_simulation_scene](https://github.com/siemens/ros-sharp/tree/master/ROS/gazebo_simulation_scene)
* Launch ``gazebo_simulation_scene.launch`` to initialize ROS for the Gazebo Simulation Scene.

## [joy_to_vel](https://github.com/siemens/ros-sharp/tree/master/ROS/joy_to_vel)
... provides a [ROS](http://www.ros.org/) node subscribing a [Joy message](http://docs.ros.org/api/sensor_msgs/html/msg/Joy.html) and publishing corresponding [Twist message](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html)
* [unity_simulation_scene](https://github.com/siemens/ros-sharp/tree/master/ROS/unity_simulation_scene)
* Launch ``unity_simulation_scene`` to initialize ROS for the Unity Simulation Scene.

... is useful for working with [VelocitySubscriber](https://github.com/siemens/ros-sharp/blob/master/Unity3D/Assets/RosSharp/Scripts/VelocitySubscriber.cs) and there is no other ROS node providing a `\cmd_vel` topic.

### Please see the [Wiki](https://github.com/siemens/ros-sharp/wiki) for further info. ###
__Please see the [Wiki](https://github.com/siemens/ros-sharp/wiki) for further info.__

---

© Siemens AG, 2017
© Siemens AG, 2017-2018

Author: Dr. Martin Bischoff ([email protected])
13 changes: 0 additions & 13 deletions ROS/file_server/README.md

This file was deleted.

18 changes: 18 additions & 0 deletions ROS/file_server/launch/file_server.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<!--
© Siemens AG, 2017-2018
Author: Verena Röhrl ([email protected])
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.
-->

<launch>
<node name="file_server" pkg="file_server" type="file_server" output="screen"/>
</launch>
33 changes: 33 additions & 0 deletions ROS/file_server/launch/publish_description_turtlebot2.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<!--
© Siemens AG, 2018
Author: Berkay Alp Cakal ([email protected])
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.
-->

<launch>

<include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch">
<param name="port" value="9090"/>
</include>

<node name="file_server" pkg="file_server" type="file_server" output="screen"/>

<arg name="base" default="$(env TURTLEBOT_BASE)" />
<arg name="stacks" default="$(env TURTLEBOT_STACKS)" />
<arg name="3d_sensor" default="$(env TURTLEBOT_3D_SENSOR)"/>
<arg name="urdf_file" default="$(find xacro)/xacro.py '$(find turtlebot_description)/robots/$(arg base)_$(arg stacks)_$(arg 3d_sensor).urdf.xacro'" />

<param name="robot_description" command="$(arg urdf_file)" />

</launch>


3 changes: 1 addition & 2 deletions ROS/file_server/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,7 @@
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>

<license>Apache License, Version 2.0</license>

<!-- Url tags are optional, but mutiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
Expand Down
4 changes: 1 addition & 3 deletions ROS/file_server/src/file_server.cpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
/*
© Siemens AG, 2017
© Siemens AG, 2017-2018
Author: Dr. Martin Bischoff ([email protected])
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.
Expand Down
Loading

0 comments on commit b36dcfb

Please sign in to comment.