├── .gitignore
├── .travis.yml
├── CMakeLists.txt
├── LICENSE
├── README.md
├── Vagrantfile
├── msg
├── Audio.msg
├── Close.msg
├── Constraint.msg
├── Data.msg
├── DataChannel.msg
├── ExampleCall.msg
├── IceCandidate.msg
├── IceConnectionState.msg
├── IceServer.msg
├── MediaConstraints.msg
├── PeerConnection.msg
├── PeerConnectionKey.msg
├── SessionDescription.msg
├── SignalingState.msg
├── Source.msg
├── Stream.msg
└── Track.msg
├── package.xml
├── ros_webrtc.launch
├── scripts
├── ros_webrtc_example
├── ros_webrtc_rosbridge
└── ros_webrtc_signaling
├── setup.py
├── src
├── cpp
│ ├── config.cpp
│ ├── config.h
│ ├── convert.cpp
│ ├── convert.h
│ ├── data_channel.cpp
│ ├── data_channel.h
│ ├── geocam_cfg.h
│ ├── host.cpp
│ ├── host.h
│ ├── main.cpp
│ ├── media_constraints.cpp
│ ├── media_constraints.h
│ ├── media_type.cpp
│ ├── media_type.h
│ ├── peer_connection.cpp
│ ├── peer_connection.h
│ ├── renderer.cpp
│ ├── renderer.h
│ ├── util.cpp
│ ├── util.h
│ ├── video_capture.cpp
│ └── video_capture.h
└── py
│ └── ros_webrtc
│ ├── __init__.py
│ ├── application.py
│ ├── peer_connection.py
│ └── signaling.py
├── srv
├── AddIceCandidate.srv
├── CreateDataChannel.srv
├── CreateOffer.srv
├── CreatePeerConnection.srv
├── DeletePeerConnection.srv
├── ExampleCallPeer.srv
├── ExampleGetCalls.srv
├── ExampleHangup.srv
├── GetHost.srv
├── GetPeerConnection.srv
├── OnAddStream.srv
├── OnDataChannel.srv
├── OnIceCandidate.srv
├── OnIceConnectionStateChange.srv
├── OnNegotiationNeeded.srv
├── OnRemoveStream.srv
├── OnSetSessionDescription.srv
├── OnSignalingStateChange.srv
├── RotateVideoSource.srv
├── SendData.srv
├── SetIceServers.srv
└── SetRemoteDescription.srv
└── test
├── fixtures
├── bags
│ └── .gitignore
├── params
│ ├── cameras.yaml
│ ├── ice_servers.yaml
│ └── peer_connection.yaml
└── site
│ ├── .gitignore
│ ├── bower.json
│ ├── gruntfile.js
│ ├── package.json
│ └── src
│ ├── demo.css
│ ├── demo.js
│ ├── index.html
│ └── ros_webrtc.js
├── integration
├── .coveragerc
├── host-test.launch
├── host_test.py
├── peer-connection-test.launch
├── peer_connection_test.py
├── ros_coverage.py
├── site-call-test.launch
├── site-wait-test.launch
└── site_test.py
├── provision
├── ansible.cfg
├── dev.yml
├── inventories
│ └── local
├── requirements.yml
├── roles
│ ├── .gitignore
│ ├── base
│ │ ├── defaults
│ │ │ └── main.yml
│ │ ├── files
│ │ │ └── etc
│ │ │ │ ├── profile.d
│ │ │ │ ├── bash_aliases.sh
│ │ │ │ └── bashrc.sh
│ │ │ │ ├── resolvconf
│ │ │ │ └── resolv.conf.d
│ │ │ │ │ └── base
│ │ │ │ └── rosdep
│ │ │ │ ├── ros_webrtc.yaml
│ │ │ │ └── sources.list.d
│ │ │ │ └── 30-ros_webrtc.list
│ │ └── tasks
│ │ │ ├── deps.yml
│ │ │ ├── main.yml
│ │ │ ├── network.yml
│ │ │ ├── swap.yml
│ │ │ └── users.yml
│ ├── ros-webrtc
│ │ ├── defaults
│ │ │ └── main.yml
│ │ ├── files
│ │ │ └── etc
│ │ │ │ └── ros
│ │ │ │ └── rosdep
│ │ │ │ ├── ros_webrtc.yaml
│ │ │ │ └── sources.list.d
│ │ │ │ └── 30-ros_webrtc.list
│ │ └── tasks
│ │ │ ├── deps.yml
│ │ │ ├── main.yml
│ │ │ ├── test-site.yml
│ │ │ └── workspace.yml
│ └── webrtc
│ │ ├── defaults
│ │ └── main.yml
│ │ └── tasks
│ │ └── main.yml
├── travis.yml
└── vagrant.yml
└── unit
├── main.cpp
├── test_media_constraints.cpp
└── test_media_type.cpp
/.gitignore:
--------------------------------------------------------------------------------
1 | cmake/
2 |
--------------------------------------------------------------------------------
/.travis.yml:
--------------------------------------------------------------------------------
1 | language: cpp
2 |
3 | python:
4 | - "2.7"
5 |
6 | sudo: required
7 |
8 | dist: trusty
9 |
10 | group: deprecated-2017Q2
11 |
12 | notifications:
13 | email:
14 | recipients:
15 | - dev@mayfieldrobotics.com
16 | on_success: change
17 | on_failure: change
18 |
19 | before_install:
20 | # https://github.com/travis-ci/travis-ci/issues/5326
21 | - export PATH=$(echo $PATH | tr ':' "\n" | sed '/\/opt\/python/d' | tr "\n" ":" | sed "s|::|:|g")
22 |
23 | # http://docs.travis-ci.com/user/gui-and-headless-browsers/#Configuring-xvfb-screen-size-and-more
24 | - "/sbin/start-stop-daemon --start --quiet --pidfile /tmp/custom_xvfb_99.pid --make-pidfile --background --exec /usr/bin/Xvfb -- :99 -ac -screen 0 1024x768x24"
25 | - "export DISPLAY=:99.0"
26 |
27 | install:
28 | # setup env for ansible travis.yml
29 | - export TRAVIS_CI_PATH=$(pwd)
30 | - export ROS_STATE_PATH=~/.ros
31 | - mkdir ../ros-webrtc-ws
32 | - export TRAVIS_WS_PATH=$(readlink -f $(pwd)/../ros-webrtc-ws)
33 |
34 | # ansible travis.yml
35 | - cd test/provision
36 | - sudo pip install "ansible >=2,<3"
37 | - ansible-galaxy install -r requirements.yml
38 | - ansible-playbook -i "localhost," -c local travis.yml
39 |
40 | script:
41 | # tests
42 | - cd $TRAVIS_WS_PATH
43 | - source devel/setup.bash
44 | - catkin_make run_tests
45 | - catkin_test_results
46 |
47 | # py coverage
48 | - coverage combine $ROS_STATE_PATH/.coverage.*
49 | - coverage report -m
50 | - coverage xml
51 | - cp coverage.xml $TRAVIS_CI_PATH/
52 |
53 | # cpp coverage
54 | - lcov --path . --directory . --capture --no-external --output-file lcov.info
55 | - lcov --remove lcov.info 'test/*' 'devel/*' --output-file lcov.info
56 | - lcov --list lcov.info
57 | - rm lcov.info
58 | - find . -type f -name "*.gcda" -exec gcov -pb {} +
59 | - find . -name "*.gcov" -a -not -name "*#src#ros_webrtc#src#cpp#*" -exec rm {} +
60 | - find . -name "*.gcov" -exec sed -i "s|$TRAVIS_WS_PATH/src/ros_webrtc|$TRAVIS_CI_PATH|g" {} +
61 | - cp *.gcov $TRAVIS_CI_PATH/
62 |
63 | after_success:
64 | - cd $TRAVIS_CI_PATH
65 | - bash <(curl -s https://codecov.io/bash) -X gcov -X coveragepy
66 |
--------------------------------------------------------------------------------
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(ros_webrtc)
3 |
4 | ## Find catkin macros and libraries
5 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
6 | ## is used, also find other catkin packages
7 | find_package(catkin REQUIRED COMPONENTS
8 | roscpp
9 | std_msgs
10 | genmsg
11 | cv_bridge
12 | image_transport
13 | bondcpp
14 | )
15 |
16 | set(USE_MADMUX false CACHE BOOL "use madmux")
17 | if(USE_MADMUX)
18 | find_package(madmux REQUIRED)
19 | add_definitions("-DUSE_MADMUX")
20 | endif()
21 |
22 | ## System dependencies are found with CMake's conventions
23 | # find_package(Boost REQUIRED COMPONENTS system)
24 | find_package(PkgConfig REQUIRED COMPONENTS system)
25 | find_package(OpenCV)
26 |
27 | ## System dependencies also found via PkgConfig's conventions
28 | set(LIBJINGLE_VER "555cfe9" CACHE STRING "libjingle version.")
29 | pkg_check_modules(jingle REQUIRED libjingle${LIBJINGLE_VER})
30 | set(jingle_STATIC_LDFLAGS "-l:libjingle.a ${jingle_STATIC_LDFLAGS}")
31 | pkg_check_modules(jsoncpp REQUIRED jsoncpp)
32 |
33 | ## Uncomment this if the package has a setup.py. This macro ensures
34 | ## modules and global scripts declared therein get installed
35 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
36 | catkin_python_setup()
37 |
38 | ## Coverage
39 | set(COVERAGE "OFF" CACHE STRING "Enable coverage generation.")
40 | message(STATUS "Using COVERAGE: ${COVERAGE}")
41 | if("${COVERAGE}" STREQUAL "ON")
42 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} --coverage -fprofile-arcs -ftest-coverage")
43 | endif()
44 |
45 | ################################################
46 | ## Declare ROS messages, services and actions ##
47 | ################################################
48 |
49 | ## To declare and build messages, services or actions from within this
50 | ## package, follow these steps:
51 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
52 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
53 | ## * In the file package.xml:
54 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
55 | ## * If MSG_DEP_SET isn't empty the following dependencies might have been
56 | ## pulled in transitively but can be declared for certainty nonetheless:
57 | ## * add a build_depend tag for "message_generation"
58 | ## * add a run_depend tag for "message_runtime"
59 | ## * In this file (CMakeLists.txt):
60 | ## * add "message_generation" and every package in MSG_DEP_SET to
61 | ## find_package(catkin REQUIRED COMPONENTS ...)
62 | ## * add "message_runtime" and every package in MSG_DEP_SET to
63 | ## catkin_package(CATKIN_DEPENDS ...)
64 | ## * uncomment the add_*_files sections below as needed
65 | ## and list every .msg/.srv/.action file to be processed
66 | ## * uncomment the generate_messages entry below
67 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
68 |
69 | ## Generate messages in the 'msg' folder
70 | add_message_files(
71 | FILES
72 | Audio.msg
73 | Close.msg
74 | Constraint.msg
75 | DataChannel.msg
76 | Data.msg
77 | ExampleCall.msg
78 | IceCandidate.msg
79 | IceConnectionState.msg
80 | IceServer.msg
81 | MediaConstraints.msg
82 | PeerConnectionKey.msg
83 | PeerConnection.msg
84 | SessionDescription.msg
85 | SignalingState.msg
86 | Source.msg
87 | Stream.msg
88 | Track.msg
89 | )
90 |
91 | ## Generate services in the 'srv' folder
92 | add_service_files(
93 | FILES
94 | AddIceCandidate.srv
95 | CreateDataChannel.srv
96 | CreateOffer.srv
97 | CreatePeerConnection.srv
98 | DeletePeerConnection.srv
99 | ExampleCallPeer.srv
100 | ExampleGetCalls.srv
101 | ExampleHangup.srv
102 | GetHost.srv
103 | GetPeerConnection.srv
104 | OnAddStream.srv
105 | OnDataChannel.srv
106 | OnIceCandidate.srv
107 | OnIceConnectionStateChange.srv
108 | OnNegotiationNeeded.srv
109 | OnRemoveStream.srv
110 | OnSetSessionDescription.srv
111 | OnSignalingStateChange.srv
112 | RotateVideoSource.srv
113 | SendData.srv
114 | SetIceServers.srv
115 | SetRemoteDescription.srv
116 | )
117 |
118 | ## Generate actions in the 'action' folder
119 | # add_action_files(
120 | # FILES
121 | # Action1.action
122 | # Action2.action
123 | # )
124 |
125 | ## Generate added messages and services with any dependencies listed here
126 | generate_messages(
127 | DEPENDENCIES
128 | std_msgs
129 | ros_webrtc
130 | )
131 |
132 | ###################################
133 | ## catkin specific configuration ##
134 | ###################################
135 | ## The catkin_package macro generates cmake config files for your package
136 | ## Declare things to be passed to dependent projects
137 | ## INCLUDE_DIRS: uncomment this if you package contains header files
138 | ## LIBRARIES: libraries you create in this project that dependent projects also need
139 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
140 | ## DEPENDS: system dependencies of this project that dependent projects also need
141 | #catkin_package(
142 | # INCLUDE_DIRS include
143 | # LIBRARIES ros_webrtc
144 | # CATKIN_DEPENDS roscpp std_msgs
145 | # DEPENDS system_lib
146 | #)
147 | catkin_package()
148 |
149 | ###########
150 | ## Build ##
151 | ###########
152 |
153 | ## Specify additional locations of header files
154 | ## Your package locations should be listed before other locations
155 | # include_directories(include)
156 | include_directories(
157 | ${catkin_INCLUDE_DIRS}
158 | ${jingle_INCLUDE_DIRS}
159 | ${jsoncpp_INCLUDE_DIRS}
160 | ${OpenCV_INCLUDE_DIRS}
161 | ${madmux_INCLUDE_DIRS}
162 | )
163 |
164 | ## Declare a cpp library
165 | # add_library(ros_webrtc
166 | # src/${PROJECT_NAME}/ros_webrtc.cpp
167 | # )
168 |
169 | ## Declare a cpp executable
170 | add_executable(ros_webrtc_host
171 | src/cpp/main.cpp
172 | src/cpp/config.cpp
173 | src/cpp/convert.cpp
174 | src/cpp/data_channel.cpp
175 | src/cpp/host.cpp
176 | src/cpp/media_constraints.cpp
177 | src/cpp/media_type.cpp
178 | src/cpp/renderer.cpp
179 | src/cpp/video_capture.cpp
180 | src/cpp/peer_connection.cpp
181 | src/cpp/util.cpp
182 | )
183 |
184 | ## Add cmake target dependencies of the executable/library
185 | ## as an example, message headers may need to be generated before nodes
186 | add_dependencies(ros_webrtc_host
187 | ros_webrtc_generate_messages_cpp
188 | )
189 |
190 | ## Specify libraries to link a library or executable target against
191 | target_link_libraries(ros_webrtc_host
192 | ${catkin_LIBRARIES}
193 | ${jingle_STATIC_LDFLAGS}
194 | ${jsoncpp_STATIC_LDFLAGS}
195 | ${OpenCV_LIBRARIES}
196 | ${CMAKE_DL_LIBS}
197 | ${madmux_LIBRARIES}
198 | )
199 |
200 | ## Specify additional compile flags
201 | foreach(cxx_flag "-std=c++0x" ${jingle_CFLAGS} ${jsoncpp_CFLAGS})
202 | set_property(TARGET ros_webrtc_host APPEND_STRING PROPERTY COMPILE_FLAGS " ${cxx_flag}")
203 | endforeach(cxx_flag)
204 |
205 | #############
206 | ## Install ##
207 | #############
208 |
209 | # all install targets should use catkin DESTINATION variables
210 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
211 |
212 | ## Mark executable scripts (Python etc.) for installation
213 | ## in contrast to setup.py, you can choose the destination
214 | install(PROGRAMS
215 | scripts/ros_webrtc_example
216 | scripts/ros_webrtc_rosbridge
217 | scripts/ros_webrtc_signaling
218 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
219 | )
220 |
221 | ## Mark executables and/or libraries for installation
222 | install(TARGETS ros_webrtc_host
223 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
224 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
225 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
226 | )
227 |
228 | ## Mark cpp header files for installation
229 | # install(DIRECTORY include/${PROJECT_NAME}/
230 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
231 | # FILES_MATCHING PATTERN "*.h"
232 | # PATTERN ".svn" EXCLUDE
233 | # )
234 |
235 | ## Mark other files for installation (e.g. launch and bag files, etc.)
236 | install(FILES
237 | ros_webrtc.launch
238 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
239 | )
240 |
241 | #############
242 | ## Testing ##
243 | #############
244 |
245 | ## Add gtest based cpp test target and link libraries
246 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_ros_webrtc.cpp)
247 | # if(TARGET ${PROJECT_NAME}-test)
248 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
249 | # endif()
250 |
251 | ## Add folders to be run by python nosetests
252 | # catkin_add_nosetests(test)
253 |
254 | if(CATKIN_ENABLE_TESTING)
255 | ## Data
256 | catkin_download_test_data(
257 | ${PROJECT_NAME}_sim_2015-02-23-15-14-55.bag
258 | https://s3-us-west-1.amazonaws.com/ai-mf-data/sim_2015-02-23-15-14-55.bag
259 | DESTINATION ${CMAKE_CURRENT_SOURCE_DIR}/test/fixtures/bags
260 | FILENAME sim_2015-02-23-15-14-55.bag
261 | MD5 1832f700f1066590f0323bceda474bd7
262 | )
263 |
264 | ## Integration
265 | find_package(rostest REQUIRED)
266 | foreach(T
267 | test/integration/host-test.launch
268 | test/integration/peer-connection-test.launch
269 | test/integration/site-call-test.launch
270 | test/integration/site-wait-test.launch
271 | )
272 | add_rostest(${T})
273 | endforeach()
274 |
275 | ## Unit
276 | include_directories(src)
277 | catkin_add_gtest(unit_test
278 | test/unit/test_media_type.cpp
279 | src/cpp/media_type.cpp
280 | test/unit/test_media_constraints.cpp
281 | src/cpp/media_constraints.cpp
282 | test/unit/main.cpp
283 | )
284 | foreach(cxx_flag "-std=c++11" ${jingle_CFLAGS} ${jsoncpp_CFLAGS})
285 | set_property(TARGET unit_test APPEND_STRING PROPERTY COMPILE_FLAGS " ${cxx_flag}")
286 | endforeach(cxx_flag)
287 | target_link_libraries(unit_test
288 | ${catkin_LIBRARIES}
289 | ${jingle_STATIC_LDFLAGS}
290 | ${jsoncpp_STATIC_LDFLAGS}
291 | ${OpenCV_LIBRARIES}
292 | ${CMAKE_DL_LIBS}
293 | )
294 | endif()
295 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | Software License Agreement (BSD License)
2 |
3 | Copyright (c) 2016, Robert Bosch Startup Platform North America LLC,
4 | DBA Mayfield Robotics.
5 |
6 | All rights reserved.
7 |
8 | Redistribution and use in source and binary forms, with or without
9 | modification, are permitted provided that the following conditions
10 | are met:
11 |
12 | * Redistributions of source code must retain the above copyright
13 | notice, this list of conditions and the following disclaimer.
14 | * Redistributions in binary form must reproduce the above
15 | copyright notice, this list of conditions and the following
16 | disclaimer in the documentation and/or other materials provided
17 | with the distribution.
18 | * Neither the name of the Robert Bosch LLC. nor the names of its
19 | contributors may be used to endorse or promote products derived
20 | from this software without specific prior written permission.
21 |
22 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 | "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 | LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 | FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 | COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 | INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 | BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 | LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 | ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 | POSSIBILITY OF SUCH DAMAGE.
34 |
35 |
--------------------------------------------------------------------------------
/Vagrantfile:
--------------------------------------------------------------------------------
1 | # -*- mode: ruby -*-
2 | # vi: set ft=ruby :
3 |
4 | # All Vagrant configuration is done below. The "2" in Vagrant.configure
5 | # configures the configuration version (we support older styles for
6 | # backwards compatibility). Please don't change it unless you know what
7 | # you're doing.
8 | Vagrant.configure(2) do |config|
9 | # The most common configuration options are documented and commented below.
10 | # For a complete reference, please see the online documentation at
11 | # https://docs.vagrantup.com.
12 |
13 | # Every Vagrant development environment requires a box. You can search for
14 | # boxes at https://atlas.hashicorp.com/search.
15 | config.vm.box = "ubuntu/trusty64"
16 |
17 | # Disable automatic box update checking. If you disable this, then
18 | # boxes will only be checked for updates when the user runs
19 | # `vagrant box outdated`. This is not recommended.
20 | # config.vm.box_check_update = false
21 |
22 | # Create a forwarded port mapping which allows access to a specific port
23 | # within the machine from a port on the host machine. In the example below,
24 | # accessing "localhost:8080" will access port 80 on the guest machine.
25 | # config.vm.network "forwarded_port", guest: 80, host: 8080
26 |
27 | # Create a private network, which allows host-only access to the machine
28 | # using a specific IP.
29 | # config.vm.network "private_network", ip: "192.168.33.10"
30 |
31 | # Create a public network, which generally matched to bridged network.
32 | # Bridged networks make the machine appear as another physical device on
33 | # your network.
34 | # config.vm.network "public_network"
35 |
36 | # Share an additional folder to the guest VM. The first argument is
37 | # the path on the host to the actual folder. The second argument is
38 | # the path on the guest to mount the folder. And the optional third
39 | # argument is a set of non-required options.
40 | # config.vm.synced_folder "../data", "/vagrant_data"
41 |
42 | # Provider-specific configuration so you can fine-tune various
43 | # backing providers for Vagrant. These expose provider-specific options.
44 | # Example for VirtualBox:
45 | #
46 | # config.vm.provider "virtualbox" do |vb|
47 | # # Display the VirtualBox GUI when booting the machine
48 | # vb.gui = true
49 | #
50 | # # Customize the amount of memory on the VM:
51 | # vb.memory = "1024"
52 | # end
53 | #
54 | # View the documentation for the provider you are using for more
55 | # information on available options.
56 | config.vm.provider "virtualbox" do |vb|
57 | vb.memory = 2048
58 | vb.cpus = 4
59 | end
60 |
61 | # Define a Vagrant Push strategy for pushing to Atlas. Other push strategies
62 | # such as FTP and Heroku are also available. See the documentation at
63 | # https://docs.vagrantup.com/v2/push/atlas.html for more information.
64 | # config.push.define "atlas" do |push|
65 | # push.app = "YOUR_ATLAS_USERNAME/YOUR_APPLICATION_NAME"
66 | # end
67 |
68 | # Enable provisioning with a shell script. Additional provisioners such as
69 | # Puppet, Chef, Ansible, Salt, and Docker are also available. Please see the
70 | # documentation for more information about their specific syntax and use.
71 | # config.vm.provision "shell", inline: <<-SHELL
72 | # sudo apt-get update
73 | # sudo apt-get install -y apache2
74 | # SHELL
75 | config.vm.provision "ansible" do |ansible|
76 | ansible.playbook = "test/provision/vagrant.yml"
77 | end
78 | end
79 |
--------------------------------------------------------------------------------
/msg/Audio.msg:
--------------------------------------------------------------------------------
1 | Header header
2 | uint8[] audio_data
3 | int32 bits_per_sample
4 | int32 sample_rate
5 | int32 number_of_channels
6 | int32 number_of_frames
7 |
--------------------------------------------------------------------------------
/msg/Close.msg:
--------------------------------------------------------------------------------
1 | string session_id
2 | string peer_id
3 |
--------------------------------------------------------------------------------
/msg/Constraint.msg:
--------------------------------------------------------------------------------
1 | string key
2 | string value
3 |
--------------------------------------------------------------------------------
/msg/Data.msg:
--------------------------------------------------------------------------------
1 | string label
2 | string encoding
3 | uint8[] buffer
4 |
--------------------------------------------------------------------------------
/msg/DataChannel.msg:
--------------------------------------------------------------------------------
1 | string label
2 | int32 id
3 | bool reliable
4 | bool ordered
5 | string protocol
6 | int32 chunk_size
7 | string state
--------------------------------------------------------------------------------
/msg/ExampleCall.msg:
--------------------------------------------------------------------------------
1 | string id
2 | string peer_id
3 |
--------------------------------------------------------------------------------
/msg/IceCandidate.msg:
--------------------------------------------------------------------------------
1 | string sdp_mid
2 | int32 sdp_mline_index
3 | string candidate
4 |
--------------------------------------------------------------------------------
/msg/IceConnectionState.msg:
--------------------------------------------------------------------------------
1 | string kind
2 | string label
3 | string state
4 | bool publish
5 |
--------------------------------------------------------------------------------
/msg/IceServer.msg:
--------------------------------------------------------------------------------
1 | string uri
2 | string username
3 | string password
--------------------------------------------------------------------------------
/msg/MediaConstraints.msg:
--------------------------------------------------------------------------------
1 | ros_webrtc/Constraint[] mandatory
2 | ros_webrtc/Constraint[] optional
3 |
--------------------------------------------------------------------------------
/msg/PeerConnection.msg:
--------------------------------------------------------------------------------
1 | string session_id
2 | string peer_id
3 | string signaling_state
4 | string ice_connection_state
5 | string ice_gathering_state
6 | ros_webrtc/MediaConstraints sdp_constraints
7 | bool is_offerer
8 | ros_webrtc/Track[] local_tracks
9 | ros_webrtc/Track[] remote_tracks
10 | ros_webrtc/DataChannel[] data_channels
11 |
--------------------------------------------------------------------------------
/msg/PeerConnectionKey.msg:
--------------------------------------------------------------------------------
1 | string session_id
2 | string peer_id
3 |
--------------------------------------------------------------------------------
/msg/SessionDescription.msg:
--------------------------------------------------------------------------------
1 | string type
2 | string sdp
3 |
--------------------------------------------------------------------------------
/msg/SignalingState.msg:
--------------------------------------------------------------------------------
1 | string kind
2 | string label
3 | string state
4 | bool publish
5 |
--------------------------------------------------------------------------------
/msg/Source.msg:
--------------------------------------------------------------------------------
1 | string kind
2 | string label
3 | string state
4 | bool publish
5 | int32 rotation
6 |
7 |
--------------------------------------------------------------------------------
/msg/Stream.msg:
--------------------------------------------------------------------------------
1 | string kind
2 | string label
3 | string state
4 | bool publish
5 |
--------------------------------------------------------------------------------
/msg/Track.msg:
--------------------------------------------------------------------------------
1 | string kind
2 | string id
3 | string state
4 | bool enabled
5 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ros_webrtc
4 | 14.3.1
5 | Bring WebRTC to ROS
6 |
7 |
8 |
9 |
10 | dev+ros-webrtc
11 |
12 |
13 |
14 |
15 |
16 | BSD
17 |
18 |
19 |
20 |
21 | https://github.com/mayfieldrobotics/ros-webrtc -->
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 | catkin
42 |
43 | cv_bridge
44 | roscpp
45 | std_msgs
46 | libjsoncpp-dev
47 | bondcpp
48 | image_transport
49 | libjingle555cfe9-dev
50 |
51 | cv_bridge
52 | rosbridge_library
53 | roscpp
54 | std_msgs
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
--------------------------------------------------------------------------------
/ros_webrtc.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | cameras:
6 | webcam:
7 | label: webcam
8 | publish: yes
9 | # rotation: 90
10 | # constraints:
11 | # optional:
12 | # maxWidth: "1280"
13 | # minWidth: "1280"
14 | # maxHeight: "720"
15 | # minHeight: "720"
16 | peer_connection:
17 | constraints:
18 | optional:
19 | # googCpuOveruseDetection: "true"
20 | # googCpuUnderuseThreshold: "40"
21 | # googCpuOveruseThreshold: "60"
22 | googVeryHighBitrate: "true"
23 | DtlsSrtpKeyAgreement: "true"
24 | ice_servers:
25 | - uri: stun:stun.services.mozilla.com:3478
26 | - uri: stun:stun.l.google.com:19302
27 | trace:
28 | file: /tmp/ros_webrtc.trace
29 | filter: all
30 | queue_sizes:
31 | audio: 1000
32 | video: 1000
33 | data: 1000
34 | event: 1000
35 | flush_frequency: 60
36 | open_media_sources: false
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
--------------------------------------------------------------------------------
/scripts/ros_webrtc_example:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | """
3 | Example ROS node showing what a ROS WebRTC application might look like.
4 | """
5 | import pprint
6 | import socket
7 | import uuid
8 | import weakref
9 |
10 | import roslaunch.scriptapi
11 | import rospy
12 |
13 | from ros_webrtc import application as app
14 | from ros_webrtc import signaling as sig
15 | import ros_webrtc.msg
16 | import ros_webrtc.srv
17 | import rosgraph
18 |
19 |
20 | class SignalHandler(sig.SignalHandler):
21 |
22 | def __init__(self, app):
23 | self.app = weakref.proxy(app)
24 | super(SignalHandler, self).__init__()
25 |
26 | def _pc_for(self, channel, session):
27 | pc = self.app.pcs.get((session, channel))
28 | if not pc:
29 | raise sig.DropSignal('no pc')
30 | return pc
31 |
32 | # sig.SignalHandler
33 |
34 | def on_connect(self, channel, session, payload):
35 | pass
36 |
37 | def on_disconnect(self, channel, session, payload):
38 | pc = self._pc_for(channel, session)
39 | pc.delete()
40 |
41 | def on_call(self, channel, session, payload):
42 | self.app.create_pc(session, channel,
43 | sdp_constraints=ros_webrtc.msg.MediaConstraints(
44 | mandatory=[],
45 | optional=[],
46 | ),
47 | video_sources=['*'],
48 | audio_sources=['*'],
49 | )
50 | self.app.sig_cli.send('pickup', channel, session)
51 |
52 | def on_add_ice_candidate(self, channel, session, payload):
53 | pc = self._pc_for(channel, session)
54 | pc.add_ice_candidate(
55 | sdp_mid=payload['sdpMid'],
56 | sdp_mline_index=payload['sdpMLineIndex'],
57 | candidate=payload['candidate'],
58 | )
59 |
60 | def on_set_session_description(self, channel, session, payload):
61 | pc = self._pc_for(channel, session)
62 | pc.set_remote_description(
63 | type=payload['type'],
64 | sdp=payload['sdp'],
65 | )
66 |
67 | def on_hangup(self, channel, session, payload):
68 | pc = self._pc_for(channel, session)
69 | pc.delete()
70 |
71 |
72 | class Application(app.Application):
73 |
74 | def __init__(
75 | self,
76 | id_, signaling_url,
77 | launch,
78 | pc_timeout=None,
79 | ros_webrtc_namespace=None,
80 | rosbridge_timeout=5.0,
81 | rosbridge_output='screen',
82 | rosbridge_heartbeat_timeout=None):
83 | super(Application, self).__init__(id_, ros_webrtc_namespace, pc_timeout)
84 | self.launch = launch
85 | self.rosbridge_timeout = rosbridge_timeout
86 | self.rosbridge_output = rosbridge_output
87 | self.rosbridge_heartbeat_timeout = rosbridge_heartbeat_timeout
88 | self.sig_cli = sig.SignalClient(
89 | signaling_url + '/' + self.id,
90 | handler=SignalHandler(self)
91 | )
92 | self.sig_cli.connect()
93 | self.svrs.extend([
94 | rospy.Service(
95 | rosgraph.names.ns_join(rospy.get_name(), name),
96 | srv_cls,
97 | handler
98 | )
99 | for name, srv_cls, handler in [
100 | ('calls', ros_webrtc.srv.ExampleGetCalls, self.on_get_calls),
101 | ('call', ros_webrtc.srv.ExampleCallPeer, self.on_call_peer),
102 | ('hangup', ros_webrtc.srv.ExampleHangup, self.on_hangup),
103 | ]
104 | ])
105 |
106 | def on_get_calls(self, req):
107 | return ros_webrtc.srv.ExampleGetCallsResponse(
108 | calls=[
109 | ros_webrtc.msg.ExampleCall(id=pc.session_id, peer_id=pc.peer_id)
110 | for pc in self.pcs.values()
111 | ],
112 | )
113 |
114 | def on_call_peer(self, req):
115 | pc = self.create_pc(
116 | session_id=req.session_id or uuid.uuid4().hex,
117 | peer_id=req.peer_id,
118 | sdp_constraints=ros_webrtc.msg.MediaConstraints(
119 | mandatory=[],
120 | optional=[],
121 | ),
122 | video_sources=['*'],
123 | audio_sources=['*'],
124 | )
125 | self.sig_cli.send('call', pc.peer_id, pc.session_id)
126 | pc.create_data_channel(
127 | label='rosbridge',
128 | id=1,
129 | reliable=False,
130 | ordered=False,
131 | protocol='application/vnd.rosbridge.v1+json; chunksize=512',
132 | )
133 | if not pc.rosbridge(
134 | 'rosbridge',
135 | self.launch,
136 | timeout=self.rosbridge_timeout,
137 | output=self.rosbridge_output,
138 | heartbeat_timeout=self.rosbridge_heartbeat_timeout):
139 | pc.delete()
140 | return
141 | pc.create_offer()
142 | call = ros_webrtc.msg.ExampleCall(id=pc.session_id, peer_id=pc.peer_id)
143 | resp = ros_webrtc.srv.ExampleCallPeerResponse(call=call)
144 | return resp
145 |
146 | def on_hangup(self, req):
147 | pc = self.pcs.get((req.id, req.peer_id))
148 | if not pc:
149 | rospy.logwarn('no call w/ id="%s", peer_id="%s"', req.id, req.peer_id)
150 | return
151 | pc.delete()
152 | resp = ros_webrtc.srv.ExampleHangupResponse()
153 | return resp
154 |
155 | # Application
156 |
157 | def shutdown(self):
158 | self.sig_cli.close()
159 | super(Application, self).shutdown()
160 |
161 | def on_pc_delete(self, pc):
162 | if self.sig_cli.connection:
163 | self.sig_cli.send('hangup', pc.peer_id, pc.session_id)
164 |
165 | def on_pc_data_channel(self, pc, msg):
166 | if 'rosbridge' in msg.protocol:
167 | if not pc.rosbridge(
168 | msg.label,
169 | self.launch,
170 | timeout=self.rosbridge_timeout,
171 | output=self.rosbridge_output,
172 | heartbeat_timeout=self.rosbridge_heartbeat_timeout):
173 | return False
174 | return True
175 |
176 | def on_pc_ice_candidate(self, pc, msg):
177 | self.sig_cli.send('add_ice_candidate', pc.peer_id, pc.session_id, {
178 | 'sdpMid': msg.sdp_mid,
179 | 'sdpMLineIndex': msg.sdp_mline_index,
180 | 'candidate': msg.candidate,
181 | })
182 |
183 | def on_pc_set_session_description(self, pc, msg):
184 | self.sig_cli.send('set_session_description', pc.peer_id, pc.session_id, {
185 | 'type': msg.type,
186 | 'sdp': msg.sdp
187 | })
188 |
189 |
190 | def load_config():
191 | id_ = str(rospy.get_param('~id', uuid.uuid4().hex))
192 | if id_ == 'hostname':
193 | id_ = socket.gethostname()
194 |
195 | signaling_url = rospy.get_param('~url', None)
196 | if signaling_url is None:
197 | signaling_host = rospy.get_param('~host', '127.0.0.1')
198 | signaling_port = rospy.get_param('~port', 9000)
199 | signaling_url = 'ws://{0}:{1}'.format(signaling_host, signaling_port)
200 |
201 | return {
202 | 'id': id_,
203 | 'signaling_url': signaling_url,
204 | 'ros_webrtc_ns': rospy.get_param('~ros_webrtc_ns', None),
205 | 'peer_connection_timeout': rospy.get_param('~peer_connection_timeout', None),
206 | 'rosbridge_output': rospy.get_param('~rosbridge_output', 'screen'),
207 | 'rosbridge_timeout': float(rospy.get_param('~rosbridge_timeout', 5.0)),
208 | 'rosbridge_heartbeat_timeout': float(rospy.get_param('~rosbridge_heartbeat_timeout', 5.0)),
209 | }
210 |
211 |
212 | def main():
213 | a = None
214 | l = None
215 |
216 | def shutdown():
217 | if a:
218 | a.shutdown()
219 | if l:
220 | l.stop()
221 |
222 | rospy.init_node('example')
223 |
224 | c = load_config()
225 | rospy.loginfo('config\n%s', pprint.pformat(c))
226 |
227 | rospy.on_shutdown(shutdown)
228 |
229 | roslaunch.pmon._init_signal_handlers() # HACK: l.launch *not* called from main thread
230 | l = roslaunch.scriptapi.ROSLaunch()
231 | l.start()
232 |
233 | a = Application(
234 | c['id'],
235 | signaling_url=c['signaling_url'],
236 | launch=l,
237 | pc_timeout=c['peer_connection_timeout'],
238 | ros_webrtc_namespace=c['ros_webrtc_ns'],
239 | rosbridge_output=c['rosbridge_output'],
240 | rosbridge_timeout=c['rosbridge_timeout'],
241 | rosbridge_heartbeat_timeout=c['rosbridge_heartbeat_timeout'],
242 | )
243 |
244 | rospy.spin()
245 |
246 | if __name__ == '__main__':
247 | main()
248 |
--------------------------------------------------------------------------------
/scripts/ros_webrtc_rosbridge:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | """
3 | ROS node adapting a `RTCDataChannel` to ROS protocol. This is called a
4 | *rosbridge* and is done using the `rosbridge_library`.
5 |
6 | Typically spawn one of these nodes for **each** `RTCDataChannel` you want to
7 | convert to a bridge, like e.g.:
8 |
9 | .. code:: python
10 |
11 | from ros_webrtc.peer_connection import rosbridge_node
12 |
13 | node = rosbridge_node(
14 | '{my-label}',
15 | '{my-session-id}',
16 | '{my-peer-id}',
17 | output='screen',
18 | )
19 | launch = roslaunch.scriptapi.ROSLaunch()
20 | launch.start()
21 | launch.launch(node)
22 |
23 | where:
24 |
25 | - `{my-label}`
26 | - `{my-session-id}` and
27 | - `{my-peer-id}`
28 |
29 | identify **your** side of the `RTCDataChannel`.
30 |
31 | """
32 | import array
33 | import os
34 | import StringIO
35 | import struct
36 | import threading
37 | import time
38 |
39 | import bondpy.bondpy
40 | from ros_webrtc import join_ros_names
41 | import ros_webrtc.msg
42 | import ros_webrtc.srv
43 | import rosbridge_library.rosbridge_protocol
44 | import rospy
45 |
46 |
47 | class DataChannelBridge(object):
48 |
49 | @classmethod
50 | def generate_client_id(cls):
51 | return struct.unpack("!Q", os.urandom(8))[0]
52 |
53 | def __init__(
54 | self,
55 | label,
56 | session_id,
57 | peer_id,
58 | ros_webrtc_namespace=None,
59 | client_id=None,
60 | queue_size=1000,
61 | persistent_send=True):
62 | self.label = label
63 | self.session_id = session_id
64 | self.peer_id = peer_id
65 | self.subscriber = rospy.Subscriber(
66 | join_ros_names(
67 | ros_webrtc_namespace,
68 | 'session_{0}'.format(self.session_id),
69 | 'peer_{0}'.format(self.peer_id),
70 | 'data_{0}'.format(self.label),
71 | ),
72 | ros_webrtc.msg.Data,
73 | self._recv,
74 | )
75 | self.send = rospy.ServiceProxy(
76 | join_ros_names(ros_webrtc_namespace, 'send_data'),
77 | ros_webrtc.srv.SendData,
78 | persistent=persistent_send,
79 | )
80 | self.send_lock = threading.Lock()
81 | self.protocol = rosbridge_library.rosbridge_protocol.RosbridgeProtocol(
82 | client_id=(
83 | client_id
84 | if client_id is not None
85 | else self.generate_client_id()
86 | )
87 | )
88 | self.protocol.outgoing = self._send
89 | self.bond = bondpy.bondpy.Bond(
90 | topic='rosbridge_bond',
91 | id='_'.join([
92 | self.session_id, self.label, self.peer_id
93 | ]),
94 | on_broken=self._on_bond_broken,
95 | on_formed=self._on_bond_formed,
96 | )
97 |
98 | def __str__(self):
99 | return '{0}(label="{1}", session_id="{2}", peer_id="{3}", bond.id={4})'.format(
100 | type(self).__name__,
101 | self.label,
102 | self.session_id,
103 | self.peer_id,
104 | '"{0}"'.format(self.bond.id) if self.bond else None,
105 | )
106 |
107 | def wait_for_recv(self, timeout=5.0, poll_freq=1.0):
108 | rospy.loginfo(
109 | '%s wait_for_recv - timeout=%0.4f, poll_freq=%0.4f',
110 | self, timeout, poll_freq,
111 | )
112 | stared_at = time.time()
113 | expire_at = time.time() + timeout
114 | while self.subscriber and self.subscriber.get_num_connections() == 0:
115 | if time.time() >= expire_at:
116 | rospy.loginfo(
117 | '%s wait_for_recv - expired after %0.4f sec(s)',
118 | self, time.time() - stared_at
119 | )
120 | return False
121 | time.sleep(poll_freq)
122 | if not self.subscriber:
123 | rospy.loginfo(
124 | '%s wait_for_recv - shutdown after %0.4f sec(s)',
125 | self, time.time() - stared_at,
126 | )
127 | return False
128 | rospy.loginfo(
129 | '%s wait_for_recv - succeeded after %0.4f sec(s)',
130 | self, time.time() - stared_at,
131 | )
132 | return True
133 |
134 | def teardown(self):
135 | rospy.loginfo('%s teardown begin ...', self)
136 | if self.bond:
137 | rospy.loginfo('shutting down bind')
138 | if getattr(self.bond, 'sub', None):
139 | self.bond.shutdown()
140 | self.bond = None
141 | if self.protocol is not None:
142 | rospy.loginfo('finishing protocol')
143 | self.protocol.finish()
144 | self.protocol = None
145 | if self.subscriber is not None:
146 | rospy.loginfo('unregistering subscriber')
147 | self.subscriber.unregister()
148 | self.subscriber = None
149 | if self.send is not None:
150 | rospy.loginfo('closing send')
151 | self.send.close()
152 | self.send = None
153 | rospy.loginfo('%s teardown done', self)
154 |
155 | def _send(self, msg):
156 | rospy.logdebug('%s sending - size=%s', self, len(msg))
157 | data = ros_webrtc.msg.Data(
158 | label=self.label,
159 | encoding='utf-8',
160 | buffer=array.array('B', msg).tolist() or []
161 | )
162 | try:
163 | with self.send_lock:
164 | self.send(
165 | session_id=self.session_id,
166 | peer_id=self.peer_id,
167 | data=data
168 | )
169 | except rospy.ServiceException as ex:
170 | rospy.signal_shutdown(str(ex))
171 | raise
172 |
173 | def _recv(self, msg):
174 | rospy.logdebug(
175 | '%s recv - encoding=%s, buffer.size=%s',
176 | self, msg.encoding, len(msg.buffer)
177 | )
178 | message_string = StringIO.StringIO(bytearray(msg.buffer)).getvalue()
179 | self.protocol.incoming(message_string)
180 |
181 | def _on_bond_formed(self):
182 | rospy.loginfo('%s bond formed', self)
183 |
184 | def _on_bond_broken(self):
185 | rospy.loginfo('%s bond broken, shutting down ...', self)
186 | rospy.signal_shutdown('bond broken')
187 |
188 |
189 | def main():
190 | dcb = None
191 |
192 | def shutdown():
193 | if dcb:
194 | dcb.teardown()
195 | rospy.loginfo('deleting %s params', rospy.get_name())
196 | try:
197 | rospy.delete_param(rospy.get_name())
198 | except KeyError:
199 | rospy.logwarn('no params for %s', rospy.get_name())
200 | else:
201 | rospy.loginfo('deleted %s params', rospy.get_name())
202 |
203 | rospy.init_node('rosbridge')
204 |
205 | rospy.on_shutdown(shutdown)
206 |
207 | dcb = DataChannelBridge(
208 | label=str(rospy.get_param('~label')),
209 | session_id=str(rospy.get_param('~session_id')),
210 | peer_id=str(rospy.get_param('~peer_id')),
211 | queue_size=int(rospy.get_param('~queue_size', 1000)),
212 | persistent_send=bool(rospy.get_param('~persistent_send', True)),
213 | ros_webrtc_namespace=rospy.get_param('~ros_webrtc_ns', None),
214 | )
215 |
216 | wait_for_recv = rospy.get_param('~wait_for_recv', 5.0)
217 | if wait_for_recv:
218 | if not dcb.wait_for_recv(float(wait_for_recv)):
219 | raise RuntimeError(
220 | 'No publisher for {0} after {1} sec(s).'
221 | .format(dcb, wait_for_recv)
222 | )
223 |
224 | if rospy.has_param('heartbeat_timeout'):
225 | dcb.bond.heartbeat_timeout = float(rospy.has_param('heartbeat_timeout'))
226 |
227 | dcb.bond.start()
228 |
229 | rospy.spin()
230 |
231 |
232 | if __name__ == '__main__':
233 | main()
234 |
--------------------------------------------------------------------------------
/scripts/ros_webrtc_signaling:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | """
3 | *Signaling* refers to the mechanism used to negotiate sessions in WebRTC. You
4 | can use anything you like to do that but its typically done via an internet
5 | facing WebSocket service.
6 |
7 | This ROS node is a *test*/*example* WebSocket signaling server.
8 |
9 | Note that you will need `ws4py`to use it, e.g.:
10 |
11 | .. code: bash
12 |
13 | $ pip install ws4py
14 |
15 | """
16 | import collections
17 | import json
18 | import functools
19 | import urlparse
20 | import wsgiref.simple_server
21 | import wsgiref.util
22 |
23 | import rospy
24 |
25 | from ws4py.server.wsgirefserver import WSGIServer, WebSocketWSGIRequestHandler
26 | from ws4py.server.wsgiutils import WebSocketWSGIApplication
27 | from ws4py.websocket import WebSocket
28 |
29 |
30 | class Rooms(dict):
31 |
32 | def __init__(self):
33 | self.channels = collections.defaultdict(list)
34 |
35 | def join(self, room_id, peer):
36 | if room_id not in self:
37 | self[room_id] = Room(room_id, self.channels)
38 | self[room_id].join(peer)
39 | return self[room_id]
40 |
41 | def send(self, channel, payload):
42 | room_id = payload['session']
43 | self[room_id].send(channel, payload)
44 |
45 | def leave(self, room_id, peer):
46 | self[room_id].leave(peer)
47 | if self[room_id].empty:
48 | del self[room_id]
49 |
50 | def leave_all(self, peer):
51 | for room in self.values():
52 | if peer in room:
53 | room.leave(peer)
54 | if room.empty:
55 | self.pop(room.id)
56 |
57 |
58 | class Room(set):
59 |
60 | def __init__(self, id_, channels):
61 | self.id = id_
62 | self.channels = channels
63 |
64 | @property
65 | def empty(self):
66 | return len(self) == 0
67 |
68 | def join(self, peer):
69 | if peer in self:
70 | return
71 | self.add(peer)
72 | self.send(None, {
73 | 'channel': peer.channel,
74 | 'type': 'connect',
75 | })
76 |
77 | def send(self, channel, payload):
78 | payload['session'] = self.id
79 | data = json.dumps(payload, indent=2)
80 | if channel:
81 | peers = [
82 | peer for peer in self if peer.channel == channel
83 | ] or self.channels[channel]
84 | if not peers:
85 | rospy.loginfo(
86 | 'no peers w/ channel "%s", dropping\n%s',
87 | channel, data,
88 | )
89 | return 0
90 | else:
91 | peers = [
92 | peer for peer in self if payload['channel'] != peer.channel
93 | ]
94 | count = 0
95 | for peer in peers:
96 | peer.send(data)
97 | count += 1
98 | return count
99 |
100 | def leave(self, peer):
101 | if peer not in self:
102 | return
103 | self.remove(peer)
104 | self.send(None, {
105 | 'channel': peer.channel,
106 | 'type': 'disconnect',
107 | })
108 |
109 |
110 | class Peer(WebSocket):
111 |
112 | CHANNEL_ID_WSGI_HEADER = 'HTTP_X_CHANNEL'
113 |
114 | def __init__(self, *args, **kwargs):
115 | self.rooms = kwargs.pop('rooms')
116 | super(Peer, self).__init__(*args, **kwargs)
117 |
118 | @property
119 | def channel(self):
120 | return self.environ[self.CHANNEL_ID_WSGI_HEADER]
121 |
122 | # WebSocket
123 |
124 | def opened(self):
125 | if self.channel:
126 | self.rooms.channels[self.channel].append(self)
127 | if len(self.rooms.channels[self.channel]) == 1:
128 | rospy.loginfo('channel "%s" opened', self.channel)
129 | return super(Peer, self).opened()
130 |
131 | def received_message(self, message):
132 | data = str(message)
133 | try:
134 | payload = json.loads(data)
135 | except ValueError, ex:
136 | rospy.logwarn('dropping malformed msg - %s', ex)
137 | return
138 | if 'channel' not in payload:
139 | rospy.logwarn(
140 | 'dropping msg w/o "channel"\n%s', json.dumps(payload, indent=2)
141 | )
142 | return
143 | if 'session' not in payload:
144 | rospy.logwarn(
145 | 'dropping msg w/o "session"\n%s', json.dumps(payload, indent=2)
146 | )
147 | return
148 | channel = payload['channel']
149 | rospy.loginfo(
150 | 'channel "%s" -> "%s" -\n%s',
151 | self.channel, channel, json.dumps(payload, indent=2),
152 | )
153 | room = self.rooms.join(payload['session'], self)
154 | callback = payload.pop('callback', None)
155 | if callback is not None:
156 | payload['channel'] = callback
157 | else:
158 | payload['channel'] = self.channel
159 | room.send(channel, payload)
160 |
161 | def closed(self, code, reason=None):
162 | if self.channel:
163 | self.rooms.leave_all(self)
164 | if self in self.rooms.channels[self.channel]:
165 | self.rooms.channels[self.channel].remove(self)
166 | if not self.rooms.channels[self.channel]:
167 | rospy.loginfo('channel "%s" closed', self.channel)
168 | return super(Peer, self).closed(code, reason=reason)
169 |
170 |
171 | class PeerWSGIMiddleware(object):
172 |
173 | def __init__(self, app, password=None):
174 | self.app = app
175 | self.password = password
176 |
177 | def channel_id(self, environ):
178 | uri = wsgiref.util.request_uri(environ)
179 | url = urlparse.urlparse(uri)
180 | parts = url.path.split('/')
181 | if len(parts) != 2 or parts[0]:
182 | return
183 | return parts[1]
184 |
185 | def auth(self, environ, start_response):
186 | # TODO: basic auth
187 | return True
188 |
189 | def __call__(self, environ, start_response):
190 | environ[Peer.CHANNEL_ID_WSGI_HEADER] = self.channel_id(environ)
191 | if not self.auth(environ, start_response):
192 | return
193 | return self.app(environ, start_response)
194 |
195 |
196 | def main():
197 | rospy.init_node('signaling', disable_signals=True)
198 |
199 | rooms = Rooms()
200 |
201 | server = wsgiref.simple_server.make_server(
202 | host=rospy.get_param('~host', '127.0.0.1'),
203 | port=rospy.get_param('~port', 9000),
204 | server_class=WSGIServer,
205 | handler_class=WebSocketWSGIRequestHandler,
206 | app=PeerWSGIMiddleware(
207 | WebSocketWSGIApplication(
208 | handler_cls=functools.partial(
209 | Peer, heartbeat_freq=3.0, rooms=rooms,
210 | )
211 | ),
212 | password=rospy.get_param('~password', None))
213 | )
214 | server.initialize_websockets_manager()
215 |
216 | rospy.loginfo("serving %s:%d ...", *server.server_address)
217 | try:
218 | server.serve_forever()
219 | except KeyboardInterrupt:
220 | rospy.core.signal_shutdown('keyboard interrupt')
221 | finally:
222 | server.server_close()
223 |
224 |
225 | if __name__ == '__main__':
226 | main()
227 |
--------------------------------------------------------------------------------
/setup.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 | from distutils.core import setup
3 |
4 | from catkin_pkg.python_setup import generate_distutils_setup
5 |
6 |
7 | setup_args = generate_distutils_setup(
8 | packages=['ros_webrtc'],
9 | package_dir={'': 'src/py'},
10 | )
11 | setup(**setup_args)
12 |
--------------------------------------------------------------------------------
/src/cpp/config.cpp:
--------------------------------------------------------------------------------
1 | #include "config.h"
2 |
3 | #include
4 | #include
5 |
6 | #include "util.h"
7 |
8 |
9 | Config Config::get(ros::NodeHandle& nh) {
10 | Config instance;
11 |
12 | // cameras
13 | XmlRpc::XmlRpcValue cameras_xml;
14 | if (nh.getParam("cameras/", cameras_xml)) {
15 | for (XmlRpc::XmlRpcValue::iterator i = cameras_xml.begin(); i != cameras_xml.end(); i++) {
16 | VideoSource camera;
17 | if (_get(nh, ros::names::append("cameras/", (*i).first), camera)) {
18 | instance.cameras.push_back(camera);
19 | }
20 | }
21 | } else {
22 | ROS_INFO("missing 'cameras/' param");
23 | }
24 |
25 | // microphone
26 | _get(nh, "microphone", instance.microphone);
27 |
28 | // peer bond timeouts
29 | instance.pc_bond_connect_timeout = 10.0; // seconds
30 | if (nh.hasParam("peer_connection/connect_timeout")) {
31 | if (!nh.getParam("peer_connection/connect_timeout", instance.pc_bond_connect_timeout)) {
32 | ROS_WARN("'peer_connection/connect_timeout' param type not double");
33 | }
34 | }
35 | instance.pc_bond_heartbeat_timeout = 4.0; // seconds
36 | if (nh.hasParam("peer_connection/heartbeat_timeout")) {
37 | if (!nh.getParam("peer_connection/heartbeat_timeout", instance.pc_bond_heartbeat_timeout)) {
38 | ROS_WARN("'peer_connection/heartbeat_timeout' param type not double");
39 | }
40 | }
41 |
42 | // peer connection constraints
43 | _get(nh, ros::names::append("peer_connection", "constraints"), instance.pc_constraints);
44 |
45 | // ice_servers
46 | XmlRpc::XmlRpcValue ice_servers_xml;
47 | if (nh.getParam("ice_servers", ice_servers_xml)) {
48 | for (size_t i = 0; i != ice_servers_xml.size(); i++) {
49 | webrtc::PeerConnectionInterface::IceServer ice_server;
50 | if (_get(nh, ice_servers_xml[i], ice_server)) {
51 | instance.default_ice_servers.push_back(ice_server);
52 | }
53 | }
54 | } else {
55 | ROS_INFO("missing 'ice_servers/' param");
56 | }
57 |
58 | // flush_frequency
59 | instance.flush_frequency = 10 * 60; // 10 minutes
60 | if (nh.hasParam("flush_frequency")) {
61 | if (!nh.getParam("flush_frequency", instance.flush_frequency)) {
62 | ROS_WARN("'flush_frequency' param type not int");
63 | }
64 | }
65 |
66 | // reap_frequency
67 | instance.reap_frequency = 15; // 15 seconds
68 | if (nh.hasParam("reap_frequency")) {
69 | if (!nh.getParam("reap_frequency", instance.reap_frequency)) {
70 | ROS_WARN("'reap_frequency' param type not int");
71 | }
72 | }
73 |
74 | // trace_file
75 | instance.trace_file.clear(); // empty
76 | if (nh.hasParam("trace/file")) {
77 | if (!nh.getParam("trace/file", instance.trace_file)) {
78 | ROS_WARN("'trace/file' param type not string");
79 | }
80 | }
81 |
82 | // trace_mask
83 | instance.trace_mask = webrtc::TraceLevel::kTraceDefault;
84 | if (nh.hasParam("trace/filter")) {
85 | std::vector trace_filters;
86 | std::string trace_filter;
87 | if (nh.getParam("trace/filter", trace_filters)) {
88 | instance.trace_mask = 0;
89 | for (size_t i = 0; i != trace_filters.size(); i++) {
90 | std::string lc = trace_filters[i];
91 | std::transform(lc.begin(), lc.end(), lc.begin(), ::tolower);
92 | TraceLevels::const_iterator iter = _trace_levels.find(lc);
93 | if (iter == _trace_levels.end()) {
94 | ROS_WARN(
95 | "'trace_filter[%zu]' value '%s' invalid, using default ...",
96 | i, trace_filters[i].c_str()
97 | );
98 | instance.trace_mask = webrtc::TraceLevel::kTraceDefault;
99 | break;
100 | }
101 | instance.trace_mask |= (*iter).second;
102 | }
103 | } else if (nh.getParam("trace/filter", trace_filter)) {
104 | std::string lc = trace_filter;
105 | std::transform(lc.begin(), lc.end(), lc.begin(), ::tolower);
106 | TraceLevels::const_iterator iter = _trace_levels.find(lc);
107 | if (iter == _trace_levels.end()) {
108 | ROS_WARN(
109 | "'trace/filter' value '%s' invalid, using default ...",
110 | trace_filter.c_str()
111 | );
112 | instance.trace_mask = webrtc::TraceLevel::kTraceDefault;
113 | } else {
114 | instance.trace_mask |= (*iter).second;
115 | }
116 | } else {
117 | ROS_WARN("'trace/filter' should be string or string array");
118 | }
119 | }
120 |
121 | // queue_sizes
122 | instance.queue_sizes = QueueSizes(1000);
123 | if (nh.hasParam("queue_sizes")) {
124 | _get(nh, "queue_sizes", instance.queue_sizes);
125 | }
126 |
127 | // open media sources
128 | instance.open_media_sources = true;
129 | if (nh.hasParam("open_media_sources")) {
130 | if (!nh.getParam("open_media_sources", instance.open_media_sources)) {
131 | ROS_WARN("'open_media_sources' param type not boolean");
132 | }
133 | }
134 |
135 | return instance;
136 | }
137 |
138 | void Config::set() {
139 | throw std::runtime_error("Not implemented.");
140 | }
141 |
142 | bool Config::_get(ros::NodeHandle& nh, const std::string& root, VideoSource& value) {
143 | if (!nh.getParam(ros::names::append(root, "name"), value.name)) {
144 | return false;
145 | }
146 | if (value.name.find("name://") == 0) {
147 | value.name = value.name.substr(7);
148 | value.type = VideoSource::NameType;
149 | } else if (value.name.find("id://") == 0) {
150 | value.name = value.name.substr(5);
151 | value.type = VideoSource::IdType;
152 | } else if (value.name.find("ros://") == 0) {
153 | value.name = value.name.substr(6);
154 | value.type = VideoSource::ROSType;
155 | } else if (value.name.find("madmux://") == 0) {
156 | value.name = value.name.substr(9);
157 | value.type = VideoSource::MuxType;
158 | } else {
159 | value.type = VideoSource::NameType;
160 | }
161 | nh.getParam(ros::names::append(root, "label"), value.label);
162 | if (!_get(nh, ros::names::append(root, "constraints"), value.constraints)) {
163 | return false;
164 | }
165 | nh.getParam(ros::names::append(root, "publish"), value.publish);
166 | int rotation = 0;
167 | if (nh.getParam(ros::names::append(root, "rotation"), rotation)) {
168 | if (rotation != 0 && rotation != 90 && rotation != 180 && rotation != 270) {
169 | ROS_ERROR_STREAM(
170 | "'" << ros::names::append(root, "rotation") << "' = " <<
171 | rotation << " " <<
172 | "invalid, must be 0, 90, 180 or 270"
173 | );
174 | return false;
175 | }
176 | value.rotation = rotation;
177 | }
178 | return true;
179 | }
180 |
181 | bool Config::_get(ros::NodeHandle& nh, const std::string& root, AudioSource& value) {
182 | nh.getParam(ros::names::append(root, "label"), value.label);
183 | if (!_get(nh, ros::names::append(root, "constraints"), value.constraints)) {
184 | return false;
185 | }
186 | nh.getParam(ros::names::append(root, "publish"), value.publish);
187 | return true;
188 | }
189 |
190 | bool Config::_get(ros::NodeHandle& nh, const std::string& root, MediaConstraints& value) {
191 | typedef std::map Constraints;
192 | Constraints constraints;
193 | std::string key;
194 |
195 | key = ros::names::append(root, "mandatory");
196 | if (nh.getParam(key, constraints)) {
197 | for (Constraints::iterator i = constraints.begin(); i != constraints.end(); i++) {
198 | value.mandatory().push_back(MediaConstraints::Constraint((*i).first, (*i).second));
199 | }
200 | }
201 |
202 | key = ros::names::append(root, "optional");
203 | if (nh.getParam(key, constraints)) {
204 | for (Constraints::iterator i = constraints.begin(); i != constraints.end(); i++) {
205 | value.optional().push_back(MediaConstraints::Constraint((*i).first, (*i).second));
206 | }
207 | }
208 |
209 | return true;
210 | }
211 |
212 | bool Config::_get(ros::NodeHandle& nh, XmlRpc::XmlRpcValue& root, webrtc::PeerConnectionInterface::IceServer& value) {
213 | if (!root.hasMember("uri")) {
214 | return false;
215 | }
216 | value.uri = std::string(root["uri"]);
217 | if (root.hasMember("username"))
218 | value.username = std::string(root["username"]);
219 | else
220 | value.username.clear();
221 | if (root.hasMember("password"))
222 | value.password = std::string(root["password"]);
223 | else
224 | value.password.clear();
225 | return true;
226 | }
227 |
228 | bool Config::_get(ros::NodeHandle& nh, const std::string& root, QueueSizes& value) {
229 | int size;
230 | if (nh.getParam(ros::names::append(root, "audio"), size))
231 | value.audio = size;
232 | if (nh.getParam(ros::names::append(root, "video"), size))
233 | value.video = size;
234 | if (nh.getParam(ros::names::append(root, "data"), size))
235 | value.data = size;
236 | return true;
237 | }
238 |
239 | Config::TraceLevels Config::_trace_levels = {
240 | {"stateinfo", webrtc::TraceLevel::kTraceStateInfo},
241 | {"warning", webrtc::TraceLevel::kTraceWarning},
242 | {"error", webrtc::TraceLevel::kTraceError},
243 | {"critical", webrtc::TraceLevel::kTraceCritical},
244 | {"apicall", webrtc::TraceLevel::kTraceApiCall},
245 | {"default", webrtc::TraceLevel::kTraceDefault},
246 | {"modulecall", webrtc::TraceLevel::kTraceModuleCall},
247 | {"memory", webrtc::TraceLevel::kTraceMemory},
248 | {"timer", webrtc::TraceLevel::kTraceTimer},
249 | {"stream", webrtc::TraceLevel::kTraceStream},
250 | {"debug", webrtc::TraceLevel::kTraceDebug},
251 | {"info", webrtc::TraceLevel::kTraceInfo},
252 | {"terseinfo", webrtc::TraceLevel::kTraceTerseInfo},
253 | {"all", webrtc::TraceLevel::kTraceAll}
254 | };
255 |
--------------------------------------------------------------------------------
/src/cpp/config.h:
--------------------------------------------------------------------------------
1 | #ifndef ROS_WEBRTC_CONFIG_H_
2 | #define ROS_WEBRTC_CONFIG_H_
3 |
4 | #include
5 | #include
6 | #include
7 |
8 | #include "host.h"
9 | #include "media_constraints.h"
10 |
11 | /**
12 | * \brief Configuration settings read from ROS params.
13 | */
14 | class Config {
15 |
16 | public:
17 |
18 | /**
19 | * \brief Factory function used to load configuration settings from ROS params.
20 | * \return Instance representing loaded ROS params.
21 | *
22 | * The ROS params look something like:
23 | *
24 | * \code{.yaml}
25 |
26 | cameras:
27 | downward:
28 | # video device is ROS sensor_msgs/Image topic
29 | name: ros:///downward_looking_camera/image_raw
30 | label: downward
31 | upward:
32 | # video device is file-system path
33 | name: id:///dev/upward_looking_camera
34 | label: upward
35 | constraints:
36 | mandatory:
37 | maxWidth: "640"
38 | minWidth: "640"
39 | maxHeight: "480"
40 | minHeight: "480"
41 | wayward:
42 | # video device is system dependent name (e.g. Linux 2.6+ its `cat /sys/class/video4linux/video{#}/name`)
43 | name: HD Camera
44 | label: wayward
45 | peer_connection:
46 | connect_timeout: 10.0
47 | heartbeat_timeout: 4.0
48 | constraints:
49 | optional:
50 | DtlsSrtpKeyAgreement: "true"
51 | ice_servers:
52 | - uri: stun:stun.services.mozilla.com:3478
53 | - uri: stun:stun.l.google.com:19302
54 | trace:
55 | file: /tmp/ros_webrtc.trace
56 | filter: all
57 | queue_sizes:
58 | audio: 1000
59 | video: 1000
60 | data: 1000
61 | open_media_sources: true
62 |
63 | * \endcode
64 | */
65 | static Config get(ros::NodeHandle& nh);
66 |
67 | /**
68 | * \brief Persists configuration settings to ROS params.
69 | */
70 | void set();
71 |
72 | std::vector cameras; /*! Video sources. */
73 |
74 | AudioSource microphone; /*! Single audio source. */
75 |
76 | double pc_bond_connect_timeout; /*! Peer connection bond connect timeout, or 0 for no bonding. */
77 |
78 | double pc_bond_heartbeat_timeout; /*! Peer connection bond heartbeat timeout, or 0 for no bonding. */
79 |
80 | MediaConstraints pc_constraints; /*! Peer connection media constraints. */
81 |
82 | typedef webrtc::PeerConnectionInterface::IceServers IceServers;
83 |
84 | IceServers default_ice_servers; /*! Servers to use for ICE. */
85 |
86 | double flush_frequency; /*! Number of seconds between host/session flushes. */
87 |
88 | double reap_frequency; /*! Number of seconds between host/connection reaps. */
89 |
90 | std::string trace_file; /*! Write WebRTC traces to this file. */
91 |
92 | uint32_t trace_mask; /*! Filter WebRTC traces using this mask. */
93 |
94 | QueueSizes queue_sizes; /*! Sizes of audio, video and data publisher/subscriber queues. */
95 |
96 | bool open_media_sources; /*! Open media sources on start. */
97 |
98 | private:
99 |
100 | static bool _get(ros::NodeHandle& nh, const std::string& root, VideoSource& value);
101 |
102 | static bool _get(ros::NodeHandle& nh, const std::string& root, AudioSource& value);
103 |
104 | static bool _get(ros::NodeHandle& nh, const std::string& root, MediaConstraints& value);
105 |
106 | static bool _get(ros::NodeHandle& nh, XmlRpc::XmlRpcValue& root, webrtc::PeerConnectionInterface::IceServer& value);
107 |
108 | static bool _get(ros::NodeHandle& nh, const std::string& root, QueueSizes& value);
109 |
110 | typedef std::map TraceLevels;
111 |
112 | static TraceLevels _trace_levels;
113 |
114 | };
115 |
116 | #endif /* ROS_WEBRTC_CONFIG_H_ */
117 |
--------------------------------------------------------------------------------
/src/cpp/convert.cpp:
--------------------------------------------------------------------------------
1 | #include "convert.h"
2 |
3 | ros_webrtc::Track to_ros(const webrtc::MediaStreamTrackInterface* src) {
4 | ros_webrtc::Track dst;
5 | dst.kind = src->kind();
6 | dst.id = src->id();
7 | switch (src->state()) {
8 | case webrtc::MediaStreamTrackInterface::TrackState::kLive:
9 | dst.state = "live";
10 | break;
11 | case webrtc::MediaStreamTrackInterface::TrackState::kEnded:
12 | dst.state = "ended";
13 | break;
14 | }
15 | dst.enabled = src->enabled();
16 | return dst;
17 | }
18 |
19 | const char *to_string(webrtc::PeerConnectionInterface::SignalingState src) {
20 | switch (src) {
21 | case webrtc::PeerConnectionInterface::SignalingState::kStable:
22 | return "stable";
23 | case webrtc::PeerConnectionInterface::SignalingState::kHaveLocalOffer:
24 | return "have_local_offer";
25 | case webrtc::PeerConnectionInterface::SignalingState::kHaveLocalPrAnswer:
26 | return "have_local_pr_answer";
27 | case webrtc::PeerConnectionInterface::SignalingState::kHaveRemoteOffer:
28 | return "have_remote_offer";
29 | case webrtc::PeerConnectionInterface::SignalingState::kHaveRemotePrAnswer:
30 | return "have_remote_pr_answer";
31 | break;
32 | case webrtc::PeerConnectionInterface::SignalingState::kClosed:
33 | return "closed";
34 | };
35 | return "unknown";
36 | }
37 |
38 | const char *to_string(webrtc::PeerConnectionInterface::IceConnectionState src) {
39 | switch (src) {
40 | case webrtc::PeerConnectionInterface::IceConnectionState::kIceConnectionNew:
41 | return "new";
42 | case webrtc::PeerConnectionInterface::IceConnectionState::kIceConnectionChecking:
43 | return "checking";
44 | case webrtc::PeerConnectionInterface::IceConnectionState::kIceConnectionConnected:
45 | return "connected";
46 | case webrtc::PeerConnectionInterface::IceConnectionState::kIceConnectionCompleted:
47 | return "completed";
48 | case webrtc::PeerConnectionInterface::IceConnectionState::kIceConnectionFailed:
49 | return "failed";
50 | case webrtc::PeerConnectionInterface::IceConnectionState::kIceConnectionDisconnected:
51 | return "disconnected";
52 | case webrtc::PeerConnectionInterface::IceConnectionState::kIceConnectionClosed:
53 | return "closed";
54 | };
55 | return "unknown";
56 | }
57 |
58 | const char *to_string(webrtc::PeerConnectionInterface::IceGatheringState src) {
59 | switch (src) {
60 | case webrtc::PeerConnectionInterface::IceGatheringState::kIceGatheringNew:
61 | return "new";
62 | case webrtc::PeerConnectionInterface::IceGatheringState::kIceGatheringGathering:
63 | return "gathering";
64 | case webrtc::PeerConnectionInterface::IceGatheringState::kIceGatheringComplete:
65 | return "complete";
66 | }
67 | return "unknown";
68 | }
69 |
70 | const char *to_string(webrtc::DataChannelInterface::DataState src) {
71 | switch (src) {
72 | case webrtc::DataChannelInterface::DataState::kConnecting:
73 | return "connecting";
74 | case webrtc::DataChannelInterface::DataState::kOpen:
75 | return "open";
76 | case webrtc::DataChannelInterface::DataState::kClosing:
77 | return "closing";
78 | case webrtc::DataChannelInterface::DataState::kClosed:
79 | return "closed";
80 | }
81 | return "unknown";
82 | }
83 |
84 | const char *to_string(webrtc::MediaSourceInterface::SourceState src) {
85 | switch (src) {
86 | case webrtc::MediaSourceInterface::kInitializing:
87 | return "initializing";
88 | case webrtc::MediaSourceInterface::kLive:
89 | return "live";
90 | case webrtc::MediaSourceInterface::kEnded:
91 | return "ended";
92 | case webrtc::MediaSourceInterface::kMuted:
93 | return "muted";
94 | default:
95 | return "unknown";
96 | }
97 | }
98 |
--------------------------------------------------------------------------------
/src/cpp/convert.h:
--------------------------------------------------------------------------------
1 | #ifndef ROS_WEBRTC_CONVERT_H_
2 | #define ROS_WEBRTC_CONVERT_H_
3 |
4 | #include
5 | #include
6 |
7 | ros_webrtc::Track to_ros(const webrtc::MediaStreamTrackInterface *src);
8 |
9 | const char *to_string(webrtc::PeerConnectionInterface::SignalingState src);
10 |
11 | const char *to_string(webrtc::PeerConnectionInterface::IceConnectionState src);
12 |
13 | const char *to_string(webrtc::PeerConnectionInterface::IceGatheringState src);
14 |
15 | const char *to_string(webrtc::DataChannelInterface::DataState src);
16 |
17 | const char *to_string(webrtc::MediaSourceInterface::SourceState src);
18 |
19 | #endif /* ROS_WEBRTC_CONVERT_H_ */
20 |
--------------------------------------------------------------------------------
/src/cpp/data_channel.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | #include "data_channel.h"
4 | #include "util.h"
5 |
6 | // ChunkedDataTransfer
7 |
8 | struct ChunkedDataTransfer {
9 |
10 | ChunkedDataTransfer(
11 | const std::string& id,
12 | const webrtc::DataBuffer& data_buffer,
13 | size_t size
14 | );
15 |
16 | bool is_complete() const;
17 |
18 | size_t operator()(webrtc::DataChannelInterface* provider);
19 |
20 | const std::string id;
21 |
22 | const rtc::CopyOnWriteBuffer& data;
23 |
24 | const size_t size;
25 |
26 | const size_t total;
27 |
28 | size_t current;
29 |
30 | };
31 |
32 | ChunkedDataTransfer::ChunkedDataTransfer(
33 | const std::string& id,
34 | const webrtc::DataBuffer& data_buffer,
35 | size_t size) :
36 | id(id),
37 | data(data_buffer.data),
38 | size(size),
39 | current(0),
40 | total(static_cast(std::ceil((double)data.size() / (double)size))) {
41 | }
42 |
43 | bool ChunkedDataTransfer::is_complete() const {
44 | return current == total;
45 | }
46 |
47 | size_t ChunkedDataTransfer::operator()(webrtc::DataChannelInterface* provider) {
48 | size_t bytes = 0;
49 |
50 | Json::Value chunk;
51 | chunk["id"] = id;
52 | chunk["index"] = static_cast(current);
53 | chunk["total"] = static_cast(total);
54 | chunk["data"] = std::string(
55 | (const char *)(&data.data()[0] + current * size),
56 | std::min(size, data.size() - current * size)
57 | );
58 | std::string serialized = chunk.toStyledString();
59 | webrtc::DataBuffer data_buffer(serialized);
60 | provider->Send(data_buffer);
61 | bytes += data_buffer.size();
62 | current++;
63 |
64 | return bytes;
65 | }
66 |
67 | // DataChannel
68 |
69 | DataChannel::DataChannel(
70 | ros::NodeHandle& nh,
71 | const std::string& recv_topic,
72 | webrtc::DataChannelInterface *provider,
73 | const MediaType& media_type,
74 | size_t queue_size) :
75 | _provider(provider),
76 | _media_type(media_type) {
77 | if (is_chunked()) {
78 | _data_observer.reset(new ChunkedDataObserver(
79 | nh,
80 | recv_topic,
81 | queue_size,
82 | provider
83 | ));
84 | } else {
85 | _data_observer.reset(new UnchunkedDataObserver(
86 | nh,
87 | recv_topic,
88 | queue_size,
89 | provider
90 | ));
91 | }
92 | }
93 |
94 | bool DataChannel::is_chunked() const {
95 | return chunk_size() != 0;
96 | }
97 |
98 | size_t DataChannel::chunk_size() const {
99 | auto i = _media_type.params.find("chunksize");
100 | return i == _media_type.params.end() ? 0 : std::atoi((*i).second.c_str());
101 | }
102 |
103 | void DataChannel::send(const ros_webrtc::Data& msg) {
104 | webrtc::DataBuffer data_buffer(
105 | rtc::CopyOnWriteBuffer(&msg.buffer[0], msg.buffer.size()),
106 | msg.encoding == "binary"
107 | );
108 | send(data_buffer);
109 | }
110 |
111 | void DataChannel::send(webrtc::DataBuffer& data_buffer) {
112 | if (!is_chunked()) {
113 | _provider->Send(data_buffer);
114 | } else {
115 | ChunkedDataTransfer xfer(generate_id(), data_buffer, chunk_size());
116 | while (!xfer.is_complete()) {
117 | // TODO: rate limit?
118 | xfer(_provider);
119 | }
120 | }
121 | }
122 |
123 | DataChannel::operator ros_webrtc::DataChannel () const {
124 | ros_webrtc::DataChannel dst;
125 | dst.label = _provider->label();
126 | dst.id = _provider->id();
127 | dst.reliable = _provider->reliable();
128 | dst.ordered = _provider->ordered();
129 | dst.protocol = _provider->protocol();
130 | dst.chunk_size = chunk_size();
131 | dst.state = _provider->state();
132 | return dst;
133 | }
134 |
135 | size_t DataChannel::reap() {
136 | return _data_observer->reap();
137 | }
138 |
--------------------------------------------------------------------------------
/src/cpp/data_channel.h:
--------------------------------------------------------------------------------
1 | #ifndef ROS_WEBRTC_DATA_CHANNEL_H_
2 | #define ROS_WEBRTC_DATA_CHANNEL_H_
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 |
10 | #include "media_type.h"
11 | #include "renderer.h"
12 |
13 | class DataChannel {
14 |
15 | public:
16 |
17 | DataChannel(
18 | ros::NodeHandle &nh,
19 | const std::string& recv_topic,
20 | webrtc::DataChannelInterface *provider,
21 | const MediaType& media_type,
22 | size_t queue_size=1000);
23 |
24 | void send(const ros_webrtc::Data& msg);
25 |
26 | void send(webrtc::DataBuffer& data_buffer);
27 |
28 | bool is_chunked() const;
29 |
30 | size_t chunk_size() const;
31 |
32 | operator ros_webrtc::DataChannel () const;
33 |
34 | size_t reap();
35 |
36 | private:
37 |
38 | rtc::scoped_refptr _provider;
39 | MediaType _media_type;
40 | DataObserverPtr _data_observer;
41 |
42 | };
43 |
44 | typedef boost::shared_ptr DataChannelPtr;
45 |
46 | typedef boost::shared_ptr DataChannelConstPtr;
47 |
48 | #endif /* ROS_WEBRTC_DATA_CHANNEL_H_ */
49 |
--------------------------------------------------------------------------------
/src/cpp/geocam_cfg.h:
--------------------------------------------------------------------------------
1 | #define GEO_CAM_WIDTH 1920
2 | #define GEO_CAM_HEIGHT 1080
3 | #define GEO_CAM_SOCK "/var/run/madmux/ch3.sock"
4 |
--------------------------------------------------------------------------------
/src/cpp/host.h:
--------------------------------------------------------------------------------
1 | #ifndef ROS_WEBRTC_HOST_H_
2 | #define ROS_WEBRTC_HOST_H_
3 |
4 | #include
5 |
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 | #include
13 | #include
14 | #include
15 | #include
16 | #include
17 | #include
18 | #include
19 |
20 | #include "media_constraints.h"
21 | #include "peer_connection.h"
22 | #include "video_capture.h"
23 |
24 | /**
25 | * \brief Description of a local video source.
26 | */
27 | struct VideoSource {
28 |
29 | enum Type {
30 | NameType = 0,
31 | IdType,
32 | ROSType,
33 | MuxType,
34 | };
35 |
36 | VideoSource();
37 |
38 | VideoSource(
39 | Type type,
40 | const std::string& name,
41 | const std::string& label,
42 | const MediaConstraints& constraints,
43 | bool publish = false,
44 | int rotation = 0
45 | );
46 |
47 | Type type;
48 |
49 | std::string name;
50 |
51 | std::string label;
52 |
53 | MediaConstraints constraints;
54 |
55 | bool publish;
56 |
57 | int rotation;
58 |
59 | rtc::scoped_refptr interface;
60 |
61 | rtc::scoped_refptr capture_module;
62 |
63 | VideoRendererPtr renderer;
64 |
65 | };
66 |
67 | /**
68 | * \brief Description of a local audio source.
69 | */
70 | struct AudioSource {
71 |
72 | AudioSource();
73 |
74 | AudioSource(
75 | const std::string& label,
76 | const MediaConstraints& constraints,
77 | bool publish = false
78 | );
79 |
80 | std::string label;
81 |
82 | MediaConstraints constraints;
83 |
84 | bool publish;
85 |
86 | rtc::scoped_refptr interface;
87 |
88 | AudioSinkPtr sink;
89 |
90 | };
91 |
92 | /**
93 | * \brief Accesses local media and manages peer connections.
94 | */
95 | class Host {
96 |
97 | public:
98 |
99 | Host(
100 | ros::NodeHandle &nh,
101 | const std::vector& video_srcs,
102 | const AudioSource& audio_src,
103 | const MediaConstraints& pc_constraints,
104 | double pc_bond_connect_timeout,
105 | double pc_bond_heartbeat_timeout,
106 | const std::vector& default_ice_servers,
107 | const QueueSizes& queue_sizes);
108 |
109 | Host(const Host& other);
110 |
111 | ~Host();
112 |
113 | bool open(bool media=false);
114 |
115 | bool is_open() const;
116 |
117 | void close();
118 |
119 | PeerConnectionPtr create_peer_connection(
120 | const std::string& node_name,
121 | const std::string& session_id,
122 | const std::string& peer_id,
123 | const MediaConstraints& sdp_constraints,
124 | const std::vector& audio_sources,
125 | const std::vector& video_sources
126 | );
127 |
128 | bool delete_peer_connection(
129 | const std::string& session_id,
130 | const std::string& peer_id
131 | );
132 |
133 | struct FlushStats {
134 |
135 | size_t reaped_data_messages = 0;
136 |
137 | FlushStats& operator += (const PeerConnection::FlushStats & rhs);
138 |
139 | };
140 |
141 | FlushStats flush();
142 |
143 | struct ReapStats {
144 |
145 | size_t deleted_connections = 0;
146 |
147 | };
148 |
149 | ReapStats reap(double stale_threshold);
150 |
151 | private:
152 |
153 | class Service {
154 |
155 | public:
156 |
157 | Service(Host& instance);
158 |
159 | void advertise();
160 |
161 | void shutdown();
162 |
163 | bool add_ice_candidate(ros::ServiceEvent& event);
164 |
165 | bool create_data_channel(ros::ServiceEvent& event);
166 |
167 | bool create_offer(ros::ServiceEvent& event);
168 |
169 | bool create_peer_connection(ros::ServiceEvent& event);
170 |
171 | bool delete_peer_connection(ros::ServiceEvent& event);
172 |
173 | bool get_host(ros::ServiceEvent& event);
174 |
175 | bool get_peer_connection(ros::ServiceEvent& event);
176 |
177 | bool send_data(ros::ServiceEvent& event);
178 |
179 | bool set_ice_servers(
180 | ros::ServiceEvent& event);
182 |
183 | bool set_remote_description(ros::ServiceEvent& event);
184 |
185 | bool rotate_video_source(ros::ServiceEvent& event);
186 |
187 | private:
188 |
189 | Host &_instance;
190 |
191 | ros::V_ServiceServer _srvs;
192 |
193 | };
194 |
195 | class PeerConnectionObserver : public PeerConnection::Observer {
196 |
197 | public:
198 |
199 | PeerConnectionObserver(Host& instance, PeerConnectionPtr pc);
200 |
201 | ~PeerConnectionObserver();
202 |
203 | private:
204 |
205 | Host& _instance;
206 |
207 | PeerConnectionPtr _pc;
208 |
209 | // PeerConnection::Observer
210 |
211 | public:
212 |
213 | void on_connection_change(webrtc::PeerConnectionInterface::IceConnectionState state);
214 |
215 | void on_bond_broken();
216 |
217 | };
218 |
219 | struct PeerConnectionKey {
220 |
221 | bool operator < (const PeerConnectionKey& other) const {
222 | if (session_id != other.session_id)
223 | return session_id < other.session_id;
224 | return peer_id < other.peer_id;
225 | }
226 |
227 | std::string session_id;
228 |
229 | std::string peer_id;
230 |
231 | };
232 |
233 | class DeletePeerConnectionCallback : public ros::CallbackInterface {
234 |
235 | public:
236 |
237 | DeletePeerConnectionCallback(Host& instance, const PeerConnectionKey& key);
238 |
239 | private:
240 |
241 | Host& _instance;
242 |
243 | PeerConnectionKey _key;
244 |
245 | // ros::CallbackInterface
246 |
247 | public:
248 |
249 | virtual ros::CallbackInterface::CallResult call();
250 |
251 | };
252 |
253 | typedef std::map Sessions;
254 |
255 | bool _create_pc_factory();
256 |
257 | bool _open_media();
258 |
259 | bool _is_media_open() const;
260 |
261 | void _close_media();
262 |
263 | PeerConnectionPtr _find_peer_connection(const PeerConnectionKey& key);
264 |
265 | PeerConnectionConstPtr _find_peer_connection(const PeerConnectionKey& key) const;
266 |
267 | ros::NodeHandle _nh;
268 |
269 | AudioSource _audio_src;
270 |
271 | std::vector _video_srcs;
272 |
273 | VideoCaptureModuleRegistryPtr _video_capture_modules;
274 |
275 | MediaConstraints _pc_constraints;
276 |
277 | double _pc_bond_connect_timeout;
278 |
279 | double _pc_bond_heartbeat_timeout;
280 |
281 | std::vector
282 | _default_ice_servers;
283 |
284 | std::vector _ice_servers;
285 |
286 | QueueSizes _queue_sizes;
287 |
288 | std::unique_ptr _network_thd;
289 |
290 | std::unique_ptr _signaling_thd;
291 |
292 | std::unique_ptr _worker_thd;
293 |
294 | rtc::scoped_refptr _pc_factory;
295 |
296 | Sessions _pcs;
297 |
298 | Service _srv;
299 |
300 | bool _auto_close_media;
301 |
302 | };
303 |
304 | typedef boost::shared_ptr HostPtr;
305 |
306 | /**
307 | * \brief Helper used to create a Host.
308 | */
309 | struct HostFactory {
310 |
311 | Host operator()(ros::NodeHandle &nh);
312 |
313 | std::vector video_srcs;
314 |
315 | AudioSource audio_src;
316 |
317 | double pc_bond_connect_timeout;
318 |
319 | double pc_bond_heartbeat_timeout;
320 |
321 | MediaConstraints pc_constraints;
322 |
323 | std::vector default_ice_servers;
324 |
325 | QueueSizes queue_sizes;
326 | };
327 |
328 | #endif /* WEBRTC_HOST_H_ */
329 |
--------------------------------------------------------------------------------
/src/cpp/main.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | #include
4 | #include
5 | #include
6 |
7 | #include "config.h"
8 | #include "host.h"
9 |
10 | #include
11 | #include
12 | #include
13 |
14 |
15 | struct Flush {
16 |
17 | Flush(Host& host) : host(host) {}
18 |
19 | void operator()(const ros::TimerEvent& event) {
20 | if (!ros::isShuttingDown()) {
21 | auto stats = host.flush();
22 | if (stats.reaped_data_messages) {
23 | ROS_INFO(
24 | "flushed - reaped_data_messages=%zu",
25 | stats.reaped_data_messages
26 | );
27 | }
28 | }
29 | }
30 |
31 | Host &host;
32 |
33 | };
34 |
35 | struct Reap {
36 |
37 | Reap(Host& host, double stale_threhold=30)
38 | : host(host),
39 | stale_threhold(stale_threhold) {
40 | }
41 |
42 | void operator()(const ros::TimerEvent& event) {
43 | if (!ros::isShuttingDown()) {
44 | auto stats = host.reap(stale_threhold);
45 | if (stats.deleted_connections) {
46 | ROS_INFO(
47 | "reaped - deleted_connections=%zu",
48 | stats.deleted_connections
49 | );
50 | }
51 | }
52 | }
53 |
54 | Host &host;
55 | double stale_threhold;
56 |
57 | };
58 |
59 | struct MemMonitor {
60 |
61 | MemMonitor(void*) {}
62 |
63 | void operator()(const ros::TimerEvent& event) {
64 | if (!ros::isShuttingDown()) {
65 | // Check our OOM score to
66 | // see if we are running away with memory
67 | static FILE* proc_file;
68 | if(!proc_file) {
69 | char proc_path[128];
70 | int pidnum = (int)getpid();
71 | snprintf(proc_path,sizeof(proc_path)-1,
72 | "/proc/%d/oom_score",pidnum);
73 | proc_file = fopen(proc_path,"r");
74 | }
75 | rewind(proc_file);
76 | fflush(proc_file);
77 | int oom_score;
78 | fscanf(proc_file,"%d",&oom_score);
79 | if(oom_score > 400) {
80 | ROS_FATAL(
81 | "Memory went over limit (%d percent)",oom_score/10
82 | );
83 | abort();
84 | }
85 | }
86 | }
87 | };
88 |
89 | int main(int argc, char **argv) {
90 | ROS_INFO("initializing ros");
91 | ros::init(argc, argv, "host");
92 |
93 | ros::NodeHandle nh;
94 |
95 | ROS_INFO("loading config");
96 | Config config(Config::get(nh));
97 |
98 |
99 | if (!config.trace_file.empty()) {
100 | ROS_INFO(
101 | "setting webrtc trace file to %s w/ mask 0x%04x",
102 | config.trace_file.c_str(), config.trace_mask
103 | );
104 | webrtc::Trace::set_level_filter(config.trace_mask);
105 | webrtc::Trace::CreateTrace();
106 | webrtc::Trace::SetTraceFile(config.trace_file.c_str());
107 | }
108 |
109 | ROS_INFO("initializing ssl");
110 | if (!rtc::InitializeSSL()) {
111 | ROS_ERROR("ssl initialization failed");
112 | return 1;
113 | }
114 |
115 | struct rlimit corelimit = {0x70000000,0x70000000};
116 | if(setrlimit(RLIMIT_CORE,&corelimit) < 0) {
117 | ROS_ERROR("%s",strerror(errno));
118 | return 1;
119 | }
120 |
121 | ROS_INFO("creating host");
122 | HostFactory host_factory;
123 | host_factory.audio_src = config.microphone;
124 | for (size_t i = 0; i != config.cameras.size(); i++) {
125 | host_factory.video_srcs.push_back(config.cameras[i]);
126 | }
127 | for (size_t i = 0; i != config.default_ice_servers.size(); i++) {
128 | host_factory.default_ice_servers.push_back(
129 | config.default_ice_servers[i]);
130 | }
131 | host_factory.pc_constraints = config.pc_constraints;
132 | host_factory.pc_bond_connect_timeout = config.pc_bond_connect_timeout;
133 | host_factory.pc_bond_heartbeat_timeout = config.pc_bond_heartbeat_timeout;
134 | host_factory.queue_sizes = config.queue_sizes;
135 | Host host = host_factory(nh);
136 |
137 | ROS_INFO("opening host ... ");
138 | if (!host.open(config.open_media_sources)) {
139 | ROS_INFO("host open failed");
140 | return 2;
141 | }
142 | ROS_INFO("opened host");
143 |
144 | Flush flush(host);
145 | ros::Timer flush_timer = nh.createTimer(
146 | ros::Duration(config.flush_frequency), flush
147 | );
148 | if (config.flush_frequency != 0) {
149 | ROS_INFO("scheduling host flush every %0.1f sec(s) ... ", config.flush_frequency);
150 | flush_timer.start();
151 | }
152 |
153 | Reap reap(host);
154 | ros::Timer reap_timer = nh.createTimer(
155 | ros::Duration(config.reap_frequency), reap
156 | );
157 | if (config.reap_frequency != 0) {
158 | ROS_INFO("scheduling host reap every %0.1f sec(s) ... ", config.reap_frequency);
159 | reap_timer.start();
160 | }
161 |
162 | MemMonitor monitor(NULL);
163 | ros::Timer mem_timer = nh.createTimer(
164 | ros::Duration(0.1), monitor
165 | );
166 | mem_timer.start();
167 |
168 | ROS_INFO("start spinning");
169 | ros::spin();
170 | ROS_INFO("stop spinning");
171 |
172 | ROS_INFO("closing host ...");
173 | host.close();
174 | ROS_INFO("closed host");
175 |
176 | if (!config.trace_file.empty()) {
177 | ROS_INFO("resetting webrtc trace file");
178 | webrtc::Trace::SetTraceFile(NULL);
179 | webrtc::Trace::ReturnTrace();
180 | }
181 |
182 | return 0;
183 | }
184 |
--------------------------------------------------------------------------------
/src/cpp/media_constraints.cpp:
--------------------------------------------------------------------------------
1 | #include "media_constraints.h"
2 |
3 | MediaConstraints::~MediaConstraints() {
4 | }
5 |
6 | MediaConstraints::Constraints& MediaConstraints::mandatory() {
7 | return _mandatory;
8 | }
9 |
10 | const MediaConstraints::Constraints& MediaConstraints::mandatory() const {
11 | return _mandatory;
12 | }
13 |
14 | MediaConstraints::Constraints& MediaConstraints::optional() {
15 | return _optional;
16 | }
17 |
18 | const MediaConstraints::Constraints& MediaConstraints::optional() const {
19 | return _optional;
20 | }
21 |
22 | MediaConstraints::operator ros_webrtc::MediaConstraints () const {
23 | ros_webrtc::MediaConstraints dst;
24 | for (auto i = mandatory().begin(); i != mandatory().end(); i++) {
25 | ros_webrtc::Constraint constraint;
26 | constraint.key = (*i).key;
27 | constraint.value = (*i).value;
28 | dst.mandatory.push_back(constraint);
29 | }
30 | for (auto i = optional().begin(); i != optional().end(); i++) {
31 | ros_webrtc::Constraint constraint;
32 | constraint.key = (*i).key;
33 | constraint.value = (*i).value;
34 | dst.optional.push_back(constraint);
35 | }
36 | return dst;
37 | }
38 |
39 | const MediaConstraints::Constraints& MediaConstraints::GetMandatory() const {
40 | return _mandatory;
41 | }
42 |
43 | const MediaConstraints::Constraints& MediaConstraints::GetOptional() const {
44 | return _optional;
45 | }
46 |
--------------------------------------------------------------------------------
/src/cpp/media_constraints.h:
--------------------------------------------------------------------------------
1 | #ifndef ROS_WEBRTC_MEDIA_CONSTRAINTS_H_
2 | #define ROS_WEBRTC_MEDIA_CONSTRAINTS_H_
3 |
4 | #include
5 | #include
6 |
7 | /**
8 | * @class MediaConstraints
9 | */
10 | class MediaConstraints : public webrtc::MediaConstraintsInterface {
11 |
12 | public:
13 |
14 | virtual ~MediaConstraints();
15 |
16 | Constraints& mandatory();
17 |
18 | const Constraints& mandatory() const;
19 |
20 | Constraints& optional();
21 |
22 | const Constraints& optional() const;
23 |
24 | operator ros_webrtc::MediaConstraints () const;
25 |
26 | // webrtc::MediaConstraintsInterface
27 |
28 | public:
29 |
30 | virtual const Constraints& GetMandatory() const;
31 |
32 | virtual const Constraints& GetOptional() const;
33 |
34 | private:
35 |
36 | Constraints _mandatory;
37 |
38 | Constraints _optional;
39 |
40 | };
41 |
42 | #endif /* ROS_WEBRTC_MEDIA_CONSTRAINTS_H_ */
43 |
--------------------------------------------------------------------------------
/src/cpp/media_type.cpp:
--------------------------------------------------------------------------------
1 | #include "media_type.h"
2 |
3 | #include
4 |
5 | #include
6 |
7 | /**
8 | * A regex used to parse media types, which are used to describe data channel
9 | * protocols.
10 | */
11 | static const boost::regex media_type_re(
12 | "^"
13 | "(\\w+)"
14 | "/"
15 | "((vnd|prs|x)\\.)?"
16 | "([\\w\\.\\-]+)"
17 | "(\\+(\\w+))?"
18 | "(\\s*;((\\s*[\\w\\-_\\.]+?=(\"([^\"]+?)\"|([^\\s]+)))*))?"
19 | "$"
20 | );
21 |
22 | /**
23 | * A regex used to parse media type parameters.
24 | */
25 | static const boost::regex media_type_param_re(
26 | "([\\w\\-_\\.]+?)"
27 | "="
28 | "(\"([^\"]+?)\"|([^\\s]+))"
29 | );
30 |
31 | bool MediaType::matches(const std::string& value) {
32 | return boost::regex_match(value, media_type_re);
33 | }
34 |
35 | MediaType::MediaType() {
36 | }
37 |
38 | MediaType::MediaType(const std::string& value) {
39 | boost::smatch m;
40 | if (!boost::regex_match(value, m, media_type_re)) {
41 | std::stringstream ss;
42 | ss << "Malformed media type '" << value << "'.";
43 | throw std::invalid_argument(ss.str());
44 | }
45 | type = m[1];
46 | tree = m[3];
47 | sub_type = m[4];
48 | suffix = m[6];
49 | if (m[8].matched) {
50 | std::string match = m[8];
51 | boost::sregex_iterator m_i(match.begin(), match.end(), media_type_param_re);
52 | boost::sregex_iterator m_i_done;
53 | while (m_i != m_i_done) {
54 | if ((*m_i)[3].matched)
55 | params[(*m_i)[1]] = (*m_i)[3];
56 | else
57 | params[(*m_i)[1]] = (*m_i)[4];
58 | m_i++;
59 | }
60 | }
61 | }
62 |
63 | bool MediaType::has_tree() const {
64 | return !tree.empty();
65 | }
66 |
67 | bool MediaType::has_suffix() const {
68 | return !suffix.empty();
69 | }
70 |
--------------------------------------------------------------------------------
/src/cpp/media_type.h:
--------------------------------------------------------------------------------
1 | #ifndef ROS_WEBRTC_MEDIA_TYPE_H_
2 | #define ROS_WEBRTC_MEDIA_TYPE_H_
3 |
4 | #include