├── .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 5 | #include 6 | 7 | /** 8 | * \brief Represents media type components (type, tree, etc). 9 | * \link http://en.wikipedia.org/wiki/Internet_media_type#Naming 10 | */ 11 | struct MediaType { 12 | 13 | static bool matches(const std::string& value); 14 | 15 | MediaType(); 16 | 17 | /** 18 | * \brief Parses components from a string representation of a media type. 19 | * \param value Media type as a string. 20 | * \return Components parsed from value as a MediaType. 21 | */ 22 | MediaType(const std::string& value); 23 | 24 | bool has_tree() const; 25 | 26 | bool has_suffix() const; 27 | 28 | std::string type; 29 | 30 | std::string tree; 31 | 32 | std::string sub_type; 33 | 34 | std::string suffix; 35 | 36 | std::map params; 37 | 38 | }; 39 | 40 | #endif /* ROS_WEBRTC_MEDIA_TYPE_H_ */ 41 | -------------------------------------------------------------------------------- /src/cpp/peer_connection.h: -------------------------------------------------------------------------------- 1 | #ifndef ROS_WEBRTC_PEER_CONNECTION_H_ 2 | #define ROS_WEBRTC_PEER_CONNECTION_H_ 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | #include "data_channel.h" 20 | #include "media_constraints.h" 21 | #include "renderer.h" 22 | 23 | class Device; 24 | 25 | /** 26 | * \brief Categorized sizes of publisher/subscriber queues. 27 | */ 28 | struct QueueSizes { 29 | 30 | QueueSizes(uint32_t size = 0); 31 | 32 | QueueSizes(uint32_t video, uint32_t audio, uint32_t data, uint32_t event); 33 | 34 | uint32_t video; 35 | uint32_t audio; 36 | uint32_t data; 37 | uint32_t event; 38 | 39 | }; 40 | 41 | /** 42 | * \brief Represents a peer connection. 43 | */ 44 | class PeerConnection { 45 | 46 | public: 47 | 48 | /** 49 | * \brief Creates an initial session. 50 | * \param node_name Name of node that created this peer connection. 51 | * \param session_id String identifying the session. 52 | * \param peer_id String identifying the remote peer. 53 | * \param sdp_constraints Media constraints to apply for this peer connection. 54 | * \param default_queue_size Default size of publisher and subscriber queues. 55 | * \param connect_timeout Bond connect timeout in seconds or 0 for no bonding. 56 | * \param heartbeat_timeout Bond heartbeat timeout in seconds or 0 for no bonding. 57 | */ 58 | PeerConnection( 59 | const std::string& node_name, 60 | const std::string& session_id, 61 | const std::string& peer_id, 62 | const MediaConstraints& sdp_constraints, 63 | const QueueSizes& queue_sizes, 64 | double connect_timeout=10.0, 65 | double heartbeat_timeout=4.0); 66 | 67 | /** 68 | * \brief String identifying the session. 69 | * \return Session identifier. 70 | */ 71 | const std::string& session_id() const; 72 | 73 | /** 74 | * \brief String identifying the remote peer for this session. 75 | * \return Peer identifier. 76 | */ 77 | const std::string& peer_id() const; 78 | 79 | /** 80 | * \brief Whether we are currently connecting to peer. 81 | */ 82 | bool is_connecting() const; 83 | 84 | /** 85 | * \brief Whether we disconnected from peer. 86 | */ 87 | bool is_disconnected() const; 88 | 89 | /** 90 | * \brief Time in seconds since state of connection to peer changed. 91 | */ 92 | double last_connection_state_change() const; 93 | 94 | /** 95 | * \brief Prefix ROS topic name for topics associated with PeerConnection. 96 | * \return Prefixed ROS topic name. 97 | */ 98 | std::string topic(const std::string &name) const; 99 | 100 | /** 101 | * \brief Prefix ROS callback service name for topics associated with PeerConnection. 102 | * \return Prefixed ROS callback service name. 103 | */ 104 | std::string callback(const std::string &name) const; 105 | 106 | /** 107 | * \brief Video source for a PeerConnection to be added to local stream as a track. 108 | */ 109 | struct VideoSource { 110 | 111 | VideoSource( 112 | const std::string& label, 113 | webrtc::VideoTrackSourceInterface *interface, 114 | bool publish = false 115 | ); 116 | 117 | std::string label; 118 | 119 | bool publish; 120 | 121 | rtc::scoped_refptr interface; 122 | 123 | }; 124 | 125 | /** 126 | * \brief Audio source for a PeerConnection to be added to local stream as a track. 127 | */ 128 | struct AudioSource { 129 | 130 | AudioSource( 131 | const std::string& label, 132 | webrtc::AudioSourceInterface *interface, 133 | bool publish = false 134 | ); 135 | 136 | std::string label; 137 | 138 | rtc::scoped_refptr interface; 139 | 140 | bool publish; 141 | 142 | }; 143 | 144 | /** 145 | * \brief Callback interface used to observe PeerConnection life-cycle. 146 | */ 147 | class Observer { 148 | 149 | public: 150 | 151 | virtual ~Observer() {} 152 | 153 | virtual void on_connection_change(webrtc::PeerConnectionInterface::IceConnectionState state) = 0; 154 | 155 | virtual void on_bond_broken() = 0; 156 | 157 | }; 158 | 159 | typedef boost::shared_ptr ObserverPtr; 160 | 161 | /** 162 | * \brief Initiate connection to remote peer for this session. 163 | * \param pc_factory Factory used to create a peer connection. 164 | * \param pc_constraints Constraints to apply to the connection. 165 | * \param ice_servers Collection of servers to use for ICE (connection negotiation). 166 | * \param audio_srcs Local audio sources to share with peer as a stream tracks. 167 | * \param video_srcs Local video sources to share with peer as a stream tracks. 168 | * \param observer Optional observer to call on various PeerConnection life-cycle events (e.g. disconnect). 169 | * \return Whether initiation of peer connection succeeded. 170 | */ 171 | bool begin( 172 | webrtc::PeerConnectionFactoryInterface* pc_factory, 173 | const webrtc::MediaConstraintsInterface* pc_constraints, 174 | const webrtc::PeerConnectionInterface::IceServers& ice_servers, 175 | const std::vector &audio_srcs, 176 | const std::vector &video_srcs, 177 | ObserverPtr observer = ObserverPtr()); 178 | 179 | /** 180 | * \brief Teardown connection to remote peer, ending this session. 181 | */ 182 | void end(); 183 | 184 | webrtc::PeerConnectionInterface* peer_connection(); 185 | 186 | bool create_data_channel( 187 | std::string label, 188 | std::string protocol=std::string(), 189 | bool reliable=false, 190 | bool ordered=false, 191 | int id=-1); 192 | 193 | DataChannelPtr data_channel(const std::string& label); 194 | 195 | DataChannelConstPtr data_channel(const std::string& label) const; 196 | 197 | void add_ice_candidate(webrtc::IceCandidateInterface* candidate); 198 | 199 | void set_remote_session_description(webrtc::SessionDescriptionInterface* sdp); 200 | 201 | bool create_offer(); 202 | 203 | bool is_offerer() const; 204 | 205 | void create_answer(); 206 | 207 | operator ros_webrtc::PeerConnection () const; 208 | 209 | struct FlushStats { 210 | 211 | size_t reaped_data_messages; 212 | 213 | }; 214 | 215 | FlushStats flush(); 216 | 217 | private: 218 | 219 | class PeerConnectionObserver : public webrtc::PeerConnectionObserver { 220 | 221 | public: 222 | 223 | PeerConnectionObserver(PeerConnection &instance_); 224 | 225 | PeerConnection& instance; 226 | 227 | // webrtc::PeerConnectionObserver 228 | 229 | public: 230 | virtual void OnSignalingChange(webrtc::PeerConnectionInterface::SignalingState new_state); 231 | 232 | virtual void OnAddStream(rtc::scoped_refptr stream); 233 | 234 | virtual void OnRemoveStream(rtc::scoped_refptr stream); 235 | 236 | virtual void OnDataChannel(rtc::scoped_refptr data_channel); 237 | 238 | virtual void OnRenegotiationNeeded(); 239 | 240 | virtual void OnIceConnectionChange(webrtc::PeerConnectionInterface::IceConnectionState new_state); 241 | 242 | virtual void OnIceGatheringChange(webrtc::PeerConnectionInterface::IceGatheringState new_state); 243 | 244 | virtual void OnIceCandidate(const webrtc::IceCandidateInterface* candidate); 245 | 246 | virtual void OnIceCandidatesRemoved(const std::vector& candidates); 247 | 248 | virtual void OnIceConnectionReceivingChange(bool receiving); 249 | 250 | }; 251 | 252 | class CreateSessionDescriptionObserver : 253 | public rtc::RefCountedObject { 254 | 255 | public: 256 | 257 | CreateSessionDescriptionObserver(PeerConnection &instance_); 258 | 259 | virtual ~CreateSessionDescriptionObserver(); 260 | 261 | PeerConnection& instance; 262 | 263 | // webrtc::CreateSessionDescriptionObserver 264 | 265 | public: 266 | 267 | virtual void OnSuccess(webrtc::SessionDescriptionInterface* desc); 268 | 269 | virtual void OnFailure(const std::string& error); 270 | 271 | }; 272 | 273 | class SetSessionDescriptionObserver : 274 | public rtc::RefCountedObject { 275 | 276 | public: 277 | 278 | SetSessionDescriptionObserver(PeerConnection &instance_); 279 | 280 | virtual ~SetSessionDescriptionObserver(); 281 | 282 | PeerConnection& instance; 283 | 284 | // webrtc::SetSessionDescriptionObserver 285 | 286 | public: 287 | 288 | virtual void OnSuccess(); 289 | 290 | virtual void OnFailure(const std::string& error); 291 | 292 | }; 293 | 294 | typedef boost::shared_ptr IceCandidatePtr; 295 | 296 | class Events { 297 | 298 | public: 299 | 300 | Events(PeerConnection &pc); 301 | 302 | void shutdown(); 303 | 304 | ros::Publisher on_data_channel; 305 | ros::Publisher on_negotiation_needed; 306 | ros::Publisher on_ice_candidate; 307 | ros::Publisher on_ice_connection_state_change; 308 | ros::Publisher on_signaling_state_change; 309 | ros::Publisher on_add_stream; 310 | ros::Publisher on_remove_stream; 311 | 312 | ros::Publisher on_set_session_description; 313 | ros::Publisher on_close; 314 | 315 | }; 316 | 317 | class Callbacks { 318 | 319 | public: 320 | 321 | Callbacks(PeerConnection &pc); 322 | 323 | void shutdown(); 324 | 325 | ros::ServiceClient on_data_channel; 326 | ros::ServiceClient on_negotiation_needed; 327 | ros::ServiceClient on_ice_candidate; 328 | ros::ServiceClient on_ice_connection_state_change; 329 | ros::ServiceClient on_signaling_state_change; 330 | ros::ServiceClient on_add_stream; 331 | ros::ServiceClient on_remove_stream; 332 | 333 | ros::ServiceClient on_set_session_description; 334 | 335 | }; 336 | 337 | bool _open_peer_connection( 338 | webrtc::PeerConnectionFactoryInterface* pc_factory, 339 | const webrtc::MediaConstraintsInterface* pc_constraints, 340 | const webrtc::PeerConnectionInterface::IceServers& ice_servers); 341 | 342 | void _close_peer_connection(); 343 | 344 | bool _open_local_stream( 345 | webrtc::PeerConnectionFactoryInterface* pc_factory, 346 | const std::vector &audio_srcs, 347 | const std::vector &video_srcs); 348 | 349 | void _close_local_stream(); 350 | 351 | void _on_bond_formed(); 352 | 353 | void _on_bond_broken(); 354 | 355 | void _on_local_description(webrtc::SessionDescriptionInterface* desc); 356 | 357 | void _drain_remote_ice_candidates(); 358 | 359 | void _begin_event(); 360 | 361 | void _renegotiation_needed_event(); 362 | 363 | void _signaling_state_change_event(webrtc::PeerConnectionInterface::SignalingState new_state); 364 | 365 | void _ice_state_change_event(webrtc::PeerConnectionInterface::IceState new_state); 366 | 367 | void _ice_gathering_change_event(webrtc::PeerConnectionInterface::IceGatheringState new_state); 368 | 369 | void _ice_connection_change_event(webrtc::PeerConnectionInterface::IceConnectionState new_state); 370 | 371 | void _ice_complete_event(); 372 | 373 | void _add_stream_event(); 374 | 375 | void _remove_stream_event(); 376 | 377 | void _data_channel_event(); 378 | 379 | void _end_event(); 380 | 381 | ros::NodeHandle _nh; 382 | 383 | ros::Subscriber _s; 384 | 385 | std::string _nn; 386 | 387 | std::string _session_id; 388 | 389 | std::string _peer_id; 390 | 391 | double _ice_connection_changed_at; 392 | 393 | QueueSizes _queue_sizes; 394 | 395 | bond::Bond _bond; 396 | 397 | MediaConstraints _sdp_constraints; 398 | 399 | std::vector audio_sinks; 400 | 401 | std::vector video_renderers; 402 | 403 | rtc::scoped_refptr _local_stream; 404 | 405 | rtc::scoped_refptr _pc; 406 | 407 | PeerConnectionObserver _pco; 408 | 409 | ObserverPtr _observer; 410 | 411 | rtc::scoped_refptr _csdo; 412 | 413 | rtc::scoped_refptr _ssdo; 414 | 415 | bool _is_offerer; 416 | 417 | std::unique_ptr _local_desc; 418 | 419 | bool _queue_remote_ice_candidates; 420 | 421 | std::list _remote_ice_cadidates; 422 | 423 | std::map _dcs; 424 | 425 | typedef std::list AudioSinks; 426 | 427 | AudioSinks _audio_sinks; 428 | 429 | typedef std::list VideoRenderers; 430 | 431 | VideoRenderers _video_renderers; 432 | 433 | Events _events; 434 | 435 | Callbacks _callbacks; 436 | }; 437 | 438 | typedef boost::shared_ptr PeerConnectionPtr; 439 | 440 | typedef boost::shared_ptr PeerConnectionConstPtr; 441 | 442 | 443 | #endif /* ROS_WEBRTC_PEER_CONNECTION_H_ */ 444 | -------------------------------------------------------------------------------- /src/cpp/renderer.cpp: -------------------------------------------------------------------------------- 1 | #include "renderer.h" 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | 8 | // AudioSink 9 | 10 | AudioSink::AudioSink( 11 | ros::NodeHandle& nh, 12 | const std::string& topic, 13 | uint32_t queue_size, 14 | webrtc::AudioTrackInterface* audio_track) : 15 | _audio_track(audio_track), 16 | _rpub(nh.advertise(topic, queue_size)) { 17 | ROS_DEBUG_STREAM("registering audio renderer"); 18 | _audio_track->AddSink(this); 19 | } 20 | 21 | AudioSink::~AudioSink() { 22 | ROS_DEBUG_STREAM("unregistering audio renderer"); 23 | _audio_track->RemoveSink(this); 24 | _msg.header.stamp = ros::Time::now(); 25 | _msg.header.seq += 1; 26 | } 27 | 28 | webrtc::AudioTrackInterface* AudioSink::audio_track() { 29 | return _audio_track; 30 | } 31 | 32 | void AudioSink::OnData( 33 | const void* audio_data, 34 | int bits_per_sample, 35 | int sample_rate, 36 | size_t number_of_channels, 37 | size_t number_of_frames) { 38 | ROS_DEBUG_STREAM( 39 | "audio data -" 40 | << " bps : " << bits_per_sample 41 | <<" sample_rate: " << sample_rate 42 | << " number_of_channels: " << number_of_channels 43 | << " number_of_frames: " << number_of_frames 44 | ); 45 | } 46 | 47 | // VideoRenderer 48 | 49 | VideoRenderer::VideoRenderer( 50 | ros::NodeHandle nh, 51 | const std::string& topic, 52 | uint32_t queue_size, 53 | webrtc::VideoTrackInterface* video_track) : 54 | _video_track(video_track), 55 | _rpub(nh.advertise(topic, queue_size)) { 56 | ROS_INFO_STREAM("registering video renderer for '" << topic << "'"); 57 | // FIXME: configure video sink wants? 58 | _video_track->AddOrUpdateSink(this, rtc::VideoSinkWants()); 59 | _msg.encoding = sensor_msgs::image_encodings::BGR8; 60 | _msg.is_bigendian = false; 61 | } 62 | 63 | VideoRenderer::~VideoRenderer() { 64 | Close(); 65 | } 66 | 67 | webrtc::VideoTrackInterface* VideoRenderer::video_track() { 68 | return _video_track.get(); 69 | } 70 | 71 | void VideoRenderer::Close() { 72 | ROS_INFO_STREAM("unregistering video renderer for '" << _rpub.getTopic() << "'"); 73 | if (_video_track) { 74 | _video_track->RemoveSink(this); 75 | _video_track = NULL; 76 | } 77 | } 78 | 79 | void VideoRenderer::OnFrame(const cricket::VideoFrame& frame) { 80 | const cricket::VideoFrame *rf = frame.GetCopyWithRotationApplied(); 81 | if (_msg.height != rf->height() || _msg.width != rf->width()) { 82 | ROS_INFO_STREAM( 83 | "video size '" << _rpub.getTopic() << "'- " << 84 | "width=" << rf->width() << 85 | " height=" << rf->height() 86 | ); 87 | _msg.height = rf->height(); 88 | _msg.width = rf->width(); 89 | _msg.step = rf->width() * 3; 90 | _msg.data.resize(_msg.step * _msg.height); 91 | } 92 | _msg.header.stamp = ros::Time::now(); 93 | _msg.header.seq += 1; 94 | rf->ConvertToRgbBuffer( 95 | cricket::FOURCC_BGR3, 96 | &_msg.data[0], 97 | _msg.data.size(), 98 | _msg.step 99 | ); 100 | _rpub.publish(_msg); 101 | } 102 | 103 | // DataObserver 104 | 105 | DataObserver::DataObserver( 106 | ros::NodeHandle& nh, 107 | const std::string& topic, 108 | uint32_t queue_size, 109 | webrtc::DataChannelInterface* data_channel) : 110 | _dc(data_channel), 111 | _rpub(nh.advertise(topic, queue_size)) { 112 | ROS_INFO( 113 | "registering data renderer for '%s' to '%s'", 114 | _dc->label().c_str(), _rpub.getTopic().c_str() 115 | ); 116 | _dc->RegisterObserver(this); 117 | } 118 | 119 | DataObserver::~DataObserver() { 120 | ROS_INFO("unregistering data renderer for '%s'", _dc->label().c_str()); 121 | _dc->UnregisterObserver(); 122 | } 123 | 124 | void DataObserver::OnStateChange() { 125 | ROS_INFO( 126 | "data state change for '%s' to '%d'", 127 | _dc->label().c_str(), _dc->state() 128 | ); 129 | } 130 | 131 | // UnchunkedDataObserver 132 | 133 | UnchunkedDataObserver::UnchunkedDataObserver( 134 | ros::NodeHandle& nh, 135 | const std::string& topic, 136 | uint32_t queue_size, 137 | webrtc::DataChannelInterface* data_channel 138 | ) : DataObserver(nh, topic, queue_size, data_channel) { 139 | } 140 | 141 | size_t UnchunkedDataObserver::reap() { 142 | return 0; 143 | } 144 | 145 | void UnchunkedDataObserver::OnMessage(const webrtc::DataBuffer& buffer) { 146 | ROS_DEBUG( 147 | "data message for '%s' - binary=%s, size=%zu", 148 | _dc->label().c_str(), 149 | buffer.binary ? "true" : "false", 150 | buffer.data.size() 151 | ); 152 | ros_webrtc::Data msg; 153 | msg.label = _dc->label(); 154 | msg.encoding = buffer.binary ? "utf-8" : "binary"; 155 | msg.buffer.insert( 156 | msg.buffer.end(), 157 | buffer.data.cdata(), 158 | buffer.data.cdata() + buffer.data.size() 159 | ); 160 | _rpub.publish(msg); 161 | } 162 | 163 | // ChunkedDataObserver 164 | 165 | ChunkedDataObserver::ChunkedDataObserver( 166 | ros::NodeHandle& nh, 167 | const std::string& topic, 168 | uint32_t queue_size, 169 | webrtc::DataChannelInterface* data_channel 170 | ) : DataObserver(nh, topic, queue_size, data_channel) { 171 | } 172 | 173 | size_t ChunkedDataObserver::reap() { 174 | size_t count = 0; 175 | Messages::iterator i = _messages.begin(); 176 | while (i != _messages.end()) { 177 | if ((*i).second->is_expired()) { 178 | ROS_WARN_STREAM( 179 | "data message for '" << _dc->label() 180 | << "' w/" << " id " << (*i).second->id << " expired @" << (*i).second->expires_at 181 | << ", discarding ... " 182 | ); 183 | count++; 184 | _messages.erase(i++); // http://stackoverflow.com/a/596180 185 | } else { 186 | i++; 187 | } 188 | } 189 | return count; 190 | } 191 | 192 | void ChunkedDataObserver::OnMessage(const webrtc::DataBuffer& buffer) { 193 | ROS_DEBUG_STREAM( 194 | "chunked data message for '" << _dc->label() << "' - " 195 | << "binary=" << buffer.binary << ", " 196 | << "size=" << buffer.data.size() 197 | ); 198 | 199 | // deserialize chunk 200 | Json::Value chunk; 201 | Json::Reader reader; 202 | bool parsingSuccessful = reader.parse( 203 | (const char *)buffer.data.cdata(), 204 | (const char *)buffer.data.cdata() + buffer.data.size(), 205 | chunk 206 | ); 207 | if (!parsingSuccessful) { 208 | ROS_WARN_STREAM( 209 | "data message for '" << _dc->label() << "' malformed - " 210 | << reader.getFormattedErrorMessages() 211 | ); 212 | return; 213 | } 214 | 215 | // validate chunk 216 | // TODO: use json schema 217 | if (!chunk.isMember("id") || !chunk["id"].isString() || 218 | !chunk.isMember("total") || !chunk["total"].isUInt() || 219 | !chunk.isMember("index") || !chunk["index"].isUInt() || 220 | !chunk.isMember("data") || !chunk["data"].isString()) { 221 | ROS_WARN_STREAM( 222 | "data message for '" << _dc->label() << "' invalid" 223 | ); 224 | return; 225 | } 226 | 227 | // message for chunk 228 | bool created = false; 229 | MessagePtr message; 230 | Messages::iterator i = _messages.find(chunk["id"].asString()); 231 | if (i == _messages.end()) { 232 | message.reset(new Message( 233 | chunk["id"].asString(), 234 | chunk["total"].asUInt(), 235 | ros::Duration(10 * 60 /* 10 mins*/ ) 236 | )); 237 | _messages.insert(Messages::value_type(chunk["id"].asString(), message)); 238 | created = true; 239 | } else { 240 | message = (*i).second; 241 | } 242 | 243 | // add chunk to message and finalize if complete 244 | message->add_chunk(chunk["index"].asUInt(), chunk["data"].asString()); 245 | if (message->is_complete()) { 246 | _messages.erase(chunk["id"].asString()); 247 | ros_webrtc::Data msg; 248 | msg.label = _dc->label(); 249 | message->merge(msg); 250 | ROS_DEBUG_STREAM( 251 | "merged data message for '" << _dc->label() << "' - " 252 | << "encoding=" << msg.encoding << ", " 253 | << "size=" << msg.buffer.size() 254 | ); 255 | _rpub.publish(msg); 256 | } 257 | 258 | } 259 | 260 | // ChunkedDataObserver::Message 261 | 262 | ChunkedDataObserver::Message::Message( 263 | const std::string& id, 264 | size_t count, 265 | const ros::Duration& duration 266 | ) : id(id), count(count), expires_at(ros::Time::now() + duration) { 267 | } 268 | 269 | void ChunkedDataObserver::Message::add_chunk(size_t index, const std::string& data) { 270 | for (std::list::iterator i = chunks.begin(); i != chunks.end(); i++) { 271 | if (index < (*i).index) { 272 | chunks.insert(i, Chunk(index, data)); 273 | return; 274 | } 275 | if (index == (*i).index) { 276 | return; 277 | } 278 | } 279 | chunks.push_back(Chunk(index, data)); 280 | } 281 | 282 | void ChunkedDataObserver::Message::merge(ros_webrtc::Data &msg) { 283 | size_t length = 0; 284 | for (std::list::const_iterator i = chunks.begin(); i != chunks.end(); i++) { 285 | length += (*i).buffer.size(); 286 | } 287 | msg.encoding = "utf-8"; 288 | msg.buffer.reserve(length); 289 | for (std::list::const_iterator i = chunks.begin(); i != chunks.end(); i++) { 290 | msg.buffer.insert( 291 | msg.buffer.end(), 292 | &(*i).buffer[0], 293 | &(*i).buffer[0] + (*i).buffer.size() 294 | ); 295 | } 296 | } 297 | 298 | bool ChunkedDataObserver::Message::is_complete() const { 299 | return chunks.size() == count; 300 | } 301 | 302 | bool ChunkedDataObserver::Message::is_expired() const { 303 | return expires_at < ros::Time::now(); 304 | } 305 | 306 | // ChunkedDataObserver::Message::Chunk 307 | 308 | ChunkedDataObserver::Message::Chunk::Chunk( 309 | size_t index_, 310 | const std::string& buffer_ 311 | ) : index(index_) { 312 | buffer.insert(buffer.end(), &buffer_[0], &buffer_[0] + buffer_.size()); 313 | } 314 | -------------------------------------------------------------------------------- /src/cpp/renderer.h: -------------------------------------------------------------------------------- 1 | #ifndef ROS_WEBRTC_RENDERER_H_ 2 | #define ROS_WEBRTC_RENDERER_H_ 3 | 4 | #include 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | 16 | class AudioSink : public webrtc::AudioTrackSinkInterface { 17 | 18 | public: 19 | AudioSink( 20 | ros::NodeHandle& nh, 21 | const std::string& topic, 22 | uint32_t queue_size, 23 | webrtc::AudioTrackInterface* audio_track 24 | ); 25 | 26 | ~AudioSink(); 27 | 28 | webrtc::AudioTrackInterface* audio_track(); 29 | 30 | private: 31 | rtc::scoped_refptr _audio_track; 32 | 33 | ros_webrtc::Audio _msg; 34 | 35 | ros::Publisher _rpub; 36 | 37 | // webrtc::AudioTrackSinkInterface 38 | 39 | public: 40 | 41 | virtual void OnData( 42 | const void* audio_data, 43 | int bits_per_sample, 44 | int sample_rate, 45 | size_t number_of_channels, 46 | size_t number_of_frames 47 | ); 48 | 49 | }; 50 | 51 | typedef boost::shared_ptr AudioSinkPtr; 52 | 53 | class VideoRenderer : public rtc::VideoSinkInterface { 54 | 55 | public: 56 | 57 | VideoRenderer( 58 | ros::NodeHandle nh, 59 | const std::string& topic, 60 | uint32_t queue_size, 61 | webrtc::VideoTrackInterface* video_track 62 | ); 63 | 64 | ~VideoRenderer(); 65 | 66 | webrtc::VideoTrackInterface* video_track(); 67 | 68 | void Close(); 69 | 70 | private: 71 | 72 | rtc::scoped_refptr _video_track; 73 | 74 | ros::Publisher _rpub; 75 | 76 | sensor_msgs::Image _msg; 77 | 78 | // rtc::VideoSinkInterface 79 | 80 | public: 81 | 82 | virtual void OnFrame(const cricket::VideoFrame& frame); 83 | 84 | }; 85 | 86 | typedef boost::shared_ptr VideoRendererPtr; 87 | 88 | class DataObserver : public webrtc::DataChannelObserver { 89 | 90 | public: 91 | 92 | DataObserver( 93 | ros::NodeHandle& nh, 94 | const std::string& topic, 95 | uint32_t queue_size, 96 | webrtc::DataChannelInterface* data_channel 97 | ); 98 | 99 | virtual ~DataObserver(); 100 | 101 | virtual size_t reap() = 0; 102 | 103 | protected: 104 | 105 | rtc::scoped_refptr _dc; 106 | 107 | ros::Publisher _rpub; 108 | 109 | // webrtc::DataChannelObserver 110 | 111 | public: 112 | 113 | virtual void OnStateChange(); 114 | 115 | }; 116 | 117 | typedef boost::shared_ptr DataObserverPtr; 118 | 119 | typedef boost::shared_ptr DataObserverConstPtr; 120 | 121 | 122 | class UnchunkedDataObserver : public DataObserver { 123 | 124 | public: 125 | 126 | UnchunkedDataObserver( 127 | ros::NodeHandle& nh, 128 | const std::string& topic, 129 | uint32_t queue_size, 130 | webrtc::DataChannelInterface* data_channel 131 | ); 132 | 133 | // DataObserver 134 | 135 | public: 136 | 137 | virtual size_t reap(); 138 | 139 | // webrtc::DataChannelObserver 140 | 141 | public: 142 | 143 | virtual void OnMessage(const webrtc::DataBuffer& buffer); 144 | 145 | }; 146 | 147 | class ChunkedDataObserver : public DataObserver { 148 | 149 | public: 150 | 151 | ChunkedDataObserver( 152 | ros::NodeHandle& nh, 153 | const std::string& topic, 154 | uint32_t queue_size, 155 | webrtc::DataChannelInterface* data_channel 156 | ); 157 | 158 | private: 159 | 160 | struct Message { 161 | 162 | Message( 163 | const std::string& id, 164 | size_t count, 165 | const ros::Duration& duration 166 | ); 167 | 168 | void add_chunk(size_t index, const std::string& data); 169 | 170 | bool is_complete() const; 171 | 172 | bool is_expired() const; 173 | 174 | void merge(ros_webrtc::Data& msg); 175 | 176 | std::string id; 177 | 178 | size_t count; 179 | 180 | ros::Time expires_at; 181 | 182 | struct Chunk { 183 | 184 | Chunk(size_t index, const std::string &buffer); 185 | 186 | size_t index; 187 | 188 | std::vector buffer; 189 | 190 | }; 191 | 192 | std::list chunks; 193 | 194 | }; 195 | 196 | typedef boost::shared_ptr MessagePtr; 197 | 198 | typedef std::map Messages; 199 | 200 | Messages _messages; 201 | 202 | 203 | // DataObserver 204 | 205 | public: 206 | 207 | virtual size_t reap(); 208 | 209 | // webrtc::DataChannelObserver 210 | 211 | public: 212 | 213 | virtual void OnMessage(const webrtc::DataBuffer& buffer); 214 | 215 | }; 216 | 217 | #endif /* ROS_WEBRTC_RENDERER_H_ */ 218 | -------------------------------------------------------------------------------- /src/cpp/util.cpp: -------------------------------------------------------------------------------- 1 | #include "util.h" 2 | 3 | #include 4 | 5 | #include 6 | #include 7 | #include 8 | #include 9 | 10 | std::string normalize_name(const std::string& name) { 11 | std::string normalized; 12 | normalized.reserve(name.size()); 13 | size_t i = 0; 14 | if (isalpha(name[i])) { 15 | normalized += name[i]; 16 | } 17 | i++; 18 | for(; i != name.size(); i++) { 19 | if (isalnum(name[i]) || 20 | name[i] == '_' || 21 | name[i] == '/' || 22 | name[i] == '~') { 23 | normalized += name[i]; 24 | } 25 | } 26 | return normalized; 27 | } 28 | 29 | std::string join_names(std::initializer_list parts) { 30 | std::string path = ""; 31 | if (parts.size() != 0) { 32 | auto i = parts.begin(); 33 | path = normalize_name(*i); 34 | i += 1; 35 | for(; i != parts.end(); i += 1) { 36 | path = ros::names::append(path, normalize_name(*i)); 37 | } 38 | } 39 | return path; 40 | } 41 | 42 | std::string generate_id() { 43 | boost::uuids::uuid uuid = boost::uuids::random_generator()(); 44 | return boost::lexical_cast(uuid); 45 | } 46 | -------------------------------------------------------------------------------- /src/cpp/util.h: -------------------------------------------------------------------------------- 1 | #ifndef ROS_WEBRTC_UTIL_H_ 2 | #define ROS_WEBRTC_UTIL_H_ 3 | 4 | #include 5 | #include 6 | 7 | /** 8 | * \brief Normalizes to a ROS name. 9 | * \param name Candidate to normalize. 10 | * \return ROS name. 11 | */ 12 | std::string normalize_name(const std::string& name); 13 | 14 | /** 15 | * \brief Normalizes and joins to from a ROS name. 16 | * \param parts List of parts that form the name. 17 | * \return The ROS name. 18 | */ 19 | std::string join_names(std::initializer_list parts); 20 | 21 | /** 22 | * \brief Generates a unique id. 23 | * \return The unique id as a string. 24 | */ 25 | std::string generate_id(); 26 | 27 | #endif /* ROS_WEBRTC_UTIL_H_ */ 28 | -------------------------------------------------------------------------------- /src/cpp/video_capture.h: -------------------------------------------------------------------------------- 1 | #ifndef ROS_WEBRTC_VIDEO_CAPTURE_H_ 2 | #define ROS_WEBRTC_VIDEO_CAPTURE_H_ 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | 19 | #ifdef USE_MADMUX 20 | #include 21 | #include "geocam_cfg.h" 22 | #endif 23 | 24 | /** 25 | * \brief Maps cricket::VideoCapturer to their associated cricket::VideoCaptureModule. 26 | */ 27 | class VideoCaptureModuleRegistry { 28 | 29 | public: 30 | 31 | void add(cricket::VideoCapturer *capturer, webrtc::VideoCaptureModule *module); 32 | 33 | void add(const std::string& id, webrtc::VideoCaptureModule *module); 34 | 35 | bool remove(cricket::VideoCapturer *capturer); 36 | 37 | bool remove(const std::string& id); 38 | 39 | void remove_all(); 40 | 41 | webrtc::VideoCaptureModule* find(cricket::VideoCapturer *capturer) const; 42 | 43 | webrtc::VideoCaptureModule* find(const std::string& id) const; 44 | 45 | std::vector ids() const; 46 | 47 | private: 48 | 49 | typedef rtc::scoped_refptr module_type; 50 | 51 | std::map_modules; 52 | 53 | }; 54 | 55 | typedef std::shared_ptr VideoCaptureModuleRegistryPtr; 56 | 57 | #ifdef USE_MADMUX 58 | 59 | /** 60 | * \brief Allows capturing frames from GEO semi cameras 61 | * 62 | * They use their own API (mxuvc) to get camera frames. 63 | */ 64 | class GeoVideoCaptureModule : public webrtc::videocapturemodule::VideoCaptureImpl { 65 | 66 | public: 67 | 68 | GeoVideoCaptureModule(int32_t id); 69 | 70 | virtual ~GeoVideoCaptureModule(); 71 | 72 | /** 73 | * \brief Initialize mxuvc 74 | * 75 | * \param socket /var/run/madmux/chX.sock 76 | * 77 | * \returns 0 on success, non-0 otherwise. 78 | */ 79 | int32_t init(const char* socket); 80 | 81 | private: 82 | 83 | static void _madmux_video_cb(uint8_t* buffer, uint32_t size, void* user_data); 84 | void _video_cb(uint8_t* buffer, uint32_t size); 85 | 86 | webrtc::VideoCaptureCapability _capability; 87 | 88 | webrtc::CriticalSectionWrapper* _capture_cs; 89 | 90 | bool _capturing; 91 | 92 | struct mdx_stream* _stream; 93 | 94 | // webrtc::videocapturemodule::VideoCaptureImpl 95 | 96 | public: 97 | 98 | static rtc::scoped_refptr Create(const int32_t id, 99 | const char* device); 100 | 101 | static DeviceInfo* CreateDeviceInfo(const int32_t id); 102 | 103 | virtual int32_t StartCapture(const webrtc::VideoCaptureCapability& capability); 104 | 105 | virtual int32_t StopCapture(); 106 | 107 | virtual bool CaptureStarted(); 108 | 109 | virtual int32_t CaptureSettings(webrtc::VideoCaptureCapability& settings); 110 | 111 | }; 112 | 113 | /** 114 | * \brief cricket::GeoVideoDeviceCapturerFactory specialization for GEO Semi 115 | */ 116 | class GeoVideoDeviceCapturerFactory : public cricket::WebRtcVideoDeviceCapturerFactory { 117 | 118 | public: 119 | 120 | GeoVideoDeviceCapturerFactory(VideoCaptureModuleRegistryPtr module_reg); 121 | 122 | private: 123 | 124 | VideoCaptureModuleRegistryPtr _module_reg; 125 | 126 | // cricket::WebRtcVideoDeviceCapturerFactory 127 | 128 | public: 129 | 130 | virtual cricket::VideoCapturer* Create(const cricket::Device& device); 131 | 132 | }; 133 | 134 | #endif // USE_MADMUX 135 | 136 | /** 137 | * \brief Represents a ROS topics as a WebRTC video capture device. 138 | */ 139 | class ROSVideoCaptureModule : public webrtc::videocapturemodule::VideoCaptureImpl { 140 | 141 | public: 142 | 143 | ROSVideoCaptureModule(int32_t id); 144 | 145 | virtual ~ROSVideoCaptureModule(); 146 | 147 | /** 148 | * \brief Subscribes to an image ROS topic. 149 | * 150 | * \param deviceUniqueIdUTF8 ROS topic name. 151 | * \returns 0 on success, non-0 otherwise. 152 | */ 153 | int32_t init(const char* deviceUniqueIdUTF8); 154 | 155 | private: 156 | 157 | class CaptureThread : public rtc::Thread { 158 | 159 | public: 160 | CaptureThread (ROSVideoCaptureModule &parent); 161 | 162 | ~CaptureThread(); 163 | 164 | private: 165 | 166 | ROSVideoCaptureModule &_parent; 167 | 168 | // rtc::Thread 169 | 170 | public: 171 | 172 | virtual void Run(); 173 | 174 | }; 175 | 176 | void _image_callback(const sensor_msgs::ImageConstPtr& msg); 177 | 178 | webrtc::VideoCaptureCapability _capability; 179 | 180 | webrtc::CriticalSectionWrapper* _capture_cs; 181 | 182 | bool _capturing; 183 | 184 | ros::Subscriber _subscriber; 185 | 186 | ros::NodeHandle _nh; 187 | 188 | ros::CallbackQueue _image_q; 189 | 190 | CaptureThread* _capture_thd; 191 | 192 | // webrtc::videocapturemodule::VideoCaptureImpl 193 | 194 | public: 195 | 196 | static rtc::scoped_refptr Create(const int32_t id, const char* deviceUniqueIdUTF8); 197 | 198 | static DeviceInfo* CreateDeviceInfo(const int32_t id); 199 | 200 | virtual int32_t StartCapture(const webrtc::VideoCaptureCapability& capability); 201 | 202 | virtual int32_t StopCapture(); 203 | 204 | virtual bool CaptureStarted(); 205 | 206 | virtual int32_t CaptureSettings(webrtc::VideoCaptureCapability& settings); 207 | 208 | }; 209 | 210 | struct WebRTCVideoCaptureDeviceInfo { 211 | 212 | static void scan(std::vector &infos); 213 | 214 | struct find_by_name { 215 | 216 | bool operator() (const WebRTCVideoCaptureDeviceInfo & o) { 217 | return o.name == name; 218 | } 219 | 220 | std::string name; 221 | 222 | }; 223 | 224 | struct find_by_file_id { 225 | 226 | bool operator() (const WebRTCVideoCaptureDeviceInfo& o) { 227 | return o.file_id == file_id; 228 | } 229 | 230 | std::string file_id; 231 | 232 | }; 233 | 234 | std::string name; 235 | std::string file_id; 236 | std::string unique_id; 237 | std::string product_id; 238 | 239 | }; 240 | /** 241 | * \brief Collection of ROS topics to adapt as WebRTC video capture devices. 242 | */ 243 | class ROSVideoCaptureTopics { 244 | 245 | public: 246 | 247 | /// Query master for all ROS topics that can be adapted. 248 | static ROSVideoCaptureTopics scan(); 249 | 250 | ROSVideoCaptureTopics(); 251 | 252 | ROSVideoCaptureTopics(const std::vector &values); 253 | 254 | const ros::master::TopicInfo& get(size_t i) const { return _values[i]; } 255 | 256 | size_t size() const { return _values.size(); } 257 | 258 | void add(const std::string& name); 259 | 260 | int find(const std::string& name) const; 261 | 262 | private: 263 | 264 | std::vector _values; 265 | 266 | }; 267 | 268 | typedef std::shared_ptr ROSVideoCaptureTopicsPtr; 269 | 270 | typedef std::shared_ptr ROSVideoCaptureTopicsConstPtr; 271 | 272 | 273 | /** 274 | * \brief Represents available ROS topics as video capture devices to WebRTC. 275 | */ 276 | class ROSVideoCaptureDeviceInfo : public webrtc::videocapturemodule::DeviceInfoImpl { 277 | 278 | public: 279 | 280 | ROSVideoCaptureDeviceInfo(const int32_t id); 281 | 282 | virtual ~ROSVideoCaptureDeviceInfo(); 283 | 284 | bool init(ROSVideoCaptureTopicsConstPtr topics); 285 | 286 | private: 287 | 288 | struct topic_name_less_than { 289 | 290 | inline bool operator() (const ros::master::TopicInfo& a, const ros::master::TopicInfo& b) { 291 | return (a.name < b.name); 292 | } 293 | 294 | }; 295 | 296 | ROSVideoCaptureTopicsConstPtr _topics; 297 | 298 | // webrtc::VideoCaptureModule::DeviceInfo 299 | 300 | public: 301 | 302 | virtual uint32_t NumberOfDevices(); 303 | 304 | virtual int32_t GetDeviceName( 305 | uint32_t deviceNumber, 306 | char* deviceNameUTF8, 307 | uint32_t deviceNameLength, 308 | char* deviceUniqueIdUTF8, 309 | uint32_t deviceUniqueIdUTF8Length, 310 | char* productUniqueIdUTF8=0, 311 | uint32_t productUniqueIdUTF8Length=0 312 | ); 313 | 314 | virtual int32_t CreateCapabilityMap(const char* deviceUniqueIdUTF8); 315 | 316 | virtual int32_t DisplayCaptureSettingsDialogBox( 317 | const char* deviceUniqueIdUTF8, 318 | const char* dialogTitleUTF8, 319 | void* parentWindow, 320 | uint32_t positionX, 321 | uint32_t positionY 322 | ); 323 | 324 | int32_t Init(); 325 | 326 | }; 327 | 328 | /** 329 | * \brief cricket::WebRtcVideoDeviceCapturerFactory specialization for ROS and tracking webrtc::VideoCaptureModule. 330 | */ 331 | class ROSVideoDeviceCapturerFactory : public cricket::WebRtcVideoDeviceCapturerFactory { 332 | 333 | public: 334 | 335 | ROSVideoDeviceCapturerFactory( 336 | VideoCaptureModuleRegistryPtr module_reg, 337 | ROSVideoCaptureTopicsConstPtr topics); 338 | 339 | private: 340 | 341 | ROSVideoCaptureTopicsConstPtr _topics; 342 | VideoCaptureModuleRegistryPtr _module_reg; 343 | 344 | // cricket::WebRtcVideoDeviceCapturerFactory 345 | 346 | public: 347 | 348 | virtual cricket::VideoCapturer* Create(const cricket::Device& device); 349 | 350 | }; 351 | 352 | /** 353 | * \brief cricket::WebRtcVideoDeviceCapturerFactory specialization for tracking webrtc::VideoCaptureModule. 354 | */ 355 | class WebRTCVideoDeviceCapturerFactory : public cricket::WebRtcVideoDeviceCapturerFactory { 356 | 357 | public: 358 | 359 | WebRTCVideoDeviceCapturerFactory(VideoCaptureModuleRegistryPtr module_reg); 360 | 361 | private: 362 | 363 | VideoCaptureModuleRegistryPtr _module_reg; 364 | 365 | // cricket::WebRtcVideoDeviceCapturerFactory 366 | 367 | public: 368 | 369 | virtual cricket::VideoCapturer* Create(const cricket::Device& device); 370 | 371 | }; 372 | 373 | #endif /* ROS_WEBRTC_VIDEO_CAPTURE_H_ */ 374 | -------------------------------------------------------------------------------- /src/py/ros_webrtc/__init__.py: -------------------------------------------------------------------------------- 1 | import re 2 | 3 | import rosgraph 4 | 5 | 6 | def normalize_ros_name(name): 7 | return re.sub(r'[^\w_\/]', '', name) 8 | 9 | 10 | def join_ros_names(*names): 11 | return reduce( 12 | rosgraph.names.ns_join, 13 | map(normalize_ros_name, (n for n in names if n)) 14 | ) 15 | -------------------------------------------------------------------------------- /src/py/ros_webrtc/application.py: -------------------------------------------------------------------------------- 1 | """ 2 | """ 3 | import functools 4 | import weakref 5 | 6 | import rospy 7 | 8 | import ros_webrtc.srv 9 | 10 | from ros_webrtc import join_ros_names 11 | from ros_webrtc.msg import IceServer 12 | from ros_webrtc.peer_connection import ( 13 | RTCPeerConnection, 14 | RTCPeerConnectionCallbacks, 15 | ) 16 | 17 | 18 | class ApplicationRTCPeerConnectionCallbacks(RTCPeerConnectionCallbacks): 19 | 20 | def __init__(self, app, pc): 21 | self.app = weakref.proxy(app) 22 | super(ApplicationRTCPeerConnectionCallbacks, self).__init__(pc) 23 | 24 | def on_data_channel(self, req): 25 | if not self.app.on_pc_data_channel(self.pc, req.data_channel): 26 | return 27 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_data_channel(req) 28 | 29 | def on_ice_candidate(self, req): 30 | self.app.on_pc_ice_candidate(self.pc, req.candidate) 31 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_ice_candidate(req) 32 | 33 | def on_ice_candidate_state_change(self, req): 34 | self.app.on_pc_ice_candidate_state_change(self.pc, req) 35 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_ice_candidate_state_change(req) 36 | 37 | def on_signaling_state_change(self, req): 38 | self.app.on_pc_signaling_state_change(self.pc, req) 39 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_signaling_state_change(req) 40 | 41 | def on_negotiation_needed(self, req): 42 | self.app.on_pc_negotiation_needed(self.pc, req) 43 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_negotiation_needed(req) 44 | 45 | def on_add_stream(self, req): 46 | self.app.on_pc_add_stream(self.pc, req.stream) 47 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_add_stream(req) 48 | 49 | def on_remove_stream(self, req): 50 | self.app.on_pc_remove_stream(self.pc, req.stream) 51 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_remove_stream(req) 52 | 53 | def on_set_session_description(self, req): 54 | self.app.on_pc_set_session_description(self.pc, req) 55 | return super(ApplicationRTCPeerConnectionCallbacks, self).on_set_session_description(req) 56 | 57 | 58 | class ApplicationRTCPeerConnection(RTCPeerConnection): 59 | 60 | def __init__( 61 | self, 62 | app, 63 | session_id, 64 | peer_id, 65 | bond_connect_timeout=None, 66 | bond_heartbeat_timeout=None, 67 | **kwargs): 68 | super(ApplicationRTCPeerConnection, self).__init__( 69 | session_id, peer_id, **kwargs 70 | ) 71 | self.app = weakref.proxy(app) 72 | if bond_connect_timeout != 0 and bond_heartbeat_timeout != 0: 73 | self.pc_bond = self.bond( 74 | on_broken=self.on_pc_bond_broken, 75 | on_formed=self.on_pc_bond_formed, 76 | ) 77 | if bond_connect_timeout is not None: 78 | self.pc_bond.connect_timeout = bond_connect_timeout 79 | if bond_heartbeat_timeout is not None: 80 | self.pc_bond.heartbeat_timeout = bond_heartbeat_timeout 81 | else: 82 | rospy.loginfo('%s bonding disabled', self) 83 | self.pc_bond = None 84 | self.rosbridges = [] 85 | self.deleting = False 86 | self.callbacks = ApplicationRTCPeerConnectionCallbacks(app, self) 87 | self.app.pcs[(self.session_id, self.peer_id)] = self 88 | if self.pc_bond: 89 | self.pc_bond.start() 90 | 91 | def delete(self): 92 | rospy.loginfo('%s deleting', self) 93 | if self.app is None: 94 | return 95 | self.app, app = None, self.app 96 | try: 97 | app.on_pc_delete(self) 98 | finally: 99 | try: 100 | if self.pc_bond: 101 | self.pc_bond.shutdown() 102 | self.pc_bond = None 103 | while self.rosbridges: 104 | rosbridge = self.rosbridges.pop() 105 | rosbridge.stop() 106 | if self.callbacks: 107 | self.callbacks.shutdown() 108 | try: 109 | self.close() 110 | except rospy.ServiceException, ex: 111 | rospy.loginfo('%s close cmd failed - %s', self, ex) 112 | finally: 113 | app.pcs.pop((self.session_id, self.peer_id), None) 114 | self.deleting = False 115 | 116 | def on_pc_bond_broken(self): 117 | rospy.loginfo('%s bond broken, deleting pc ...', self) 118 | self.delete() 119 | 120 | def on_pc_bond_formed(self): 121 | rospy.loginfo('%s bond formed', self) 122 | 123 | def on_rosbridge_bond_broken(self, label): 124 | rospy.loginfo('%s rosbridge "%s" bond broken, deleting pc ...', self, label) 125 | self.delete() 126 | 127 | def on_rosbridge_bond_formed(self, label): 128 | rospy.loginfo('%s rosbridge "%s" bond formed', self, label) 129 | 130 | # RTCPeerConnection 131 | 132 | def rosbridge(self, data_channel_label, launch, timeout=5.0, **kwargs): 133 | rosbridge = super(ApplicationRTCPeerConnection, self).rosbridge( 134 | data_channel_label, 135 | launch, 136 | on_broken=functools.partial( 137 | self.on_rosbridge_bond_broken, data_channel_label 138 | ), 139 | on_formed=functools.partial( 140 | self.on_rosbridge_bond_formed, data_channel_label 141 | ), 142 | timeout=timeout, 143 | **kwargs 144 | ) 145 | self.rosbridges.append(rosbridge) 146 | return rosbridge 147 | 148 | 149 | class Application(object): 150 | 151 | def __init__(self, 152 | id_, 153 | ros_webrtc_namespace=None, 154 | pc_connect_timeout=None, 155 | pc_heartbeat_timeout=None): 156 | self.id = id_ 157 | self.pcs = {} 158 | self.svrs = [] 159 | self.ros_webrtc_namespace = ros_webrtc_namespace 160 | self.pc_connect_timeout = pc_connect_timeout 161 | self.pc_heartbeat_timeout = pc_heartbeat_timeout 162 | self.ice_server_svc = rospy.ServiceProxy( 163 | join_ros_names(self.ros_webrtc_namespace, 'set_ice_servers'), 164 | ros_webrtc.srv.SetIceServers 165 | ) 166 | 167 | def shutdown(self): 168 | for pc in self.pcs.values(): 169 | pc.delete() 170 | for srv in self.svrs: 171 | srv.shutdown() 172 | 173 | def set_ice_servers(self, ice_servers): 174 | valid_servers = [] 175 | for server in ice_servers: 176 | if 'uri' not in server: 177 | continue 178 | 179 | if 'stun' in server['uri'] or \ 180 | ('username' in server and 'password' in server): 181 | valid_servers.append( 182 | IceServer(uri=server['uri'], 183 | username=server.get('username', ''), 184 | password=server.get('password', '')) 185 | ) 186 | 187 | if not valid_servers: 188 | rospy.logerr("No properly formatted ice servers found in {}". 189 | format(ice_servers)) 190 | return 191 | 192 | rospy.loginfo("Setting ice servers: {}".format(valid_servers)) 193 | return self.ice_server_svc(valid_servers) 194 | 195 | def create_pc(self, session_id, peer_id, **kwargs): 196 | key = (session_id, peer_id) 197 | pc = self.pcs.pop(key, None) 198 | if pc: 199 | rospy.loginfo('pc %s already exists, deleting ... ', pc) 200 | pc.delete() 201 | if self.ros_webrtc_namespace: 202 | kwargs['namespace'] = self.ros_webrtc_namespace 203 | pc = ApplicationRTCPeerConnection( 204 | self, 205 | session_id, 206 | peer_id, 207 | bond_connect_timeout=self.pc_connect_timeout, 208 | bond_heartbeat_timeout=self.pc_heartbeat_timeout, 209 | **kwargs 210 | ) 211 | rospy.loginfo('created pc %s', pc) 212 | return pc 213 | 214 | def get_pc(self, session_id, peer_id): 215 | key = (session_id, peer_id) 216 | return self.pcs.get(key) 217 | 218 | def delete_pc(self, session_id, peer_id): 219 | key = (session_id, peer_id) 220 | pc = self.pcs.pop(key, None) 221 | if pc: 222 | pc.delete() 223 | 224 | def on_pc_delete(self, pc): 225 | pass 226 | 227 | def on_pc_data_channel(self, pc, msg): 228 | pass 229 | 230 | def on_pc_negotiation_needed(self, pc, msg): 231 | pass 232 | 233 | def on_pc_ice_candidate(self, pc, msg): 234 | pass 235 | 236 | def on_pc_ice_candidate_state_change(self, pc, msg): 237 | pass 238 | 239 | def on_pc_signaling_state_change(self, pc, msg): 240 | pass 241 | 242 | def on_pc_add_stream(self, pc, msg): 243 | pass 244 | 245 | def on_pc_set_session_description(self, pc, msg): 246 | pass 247 | -------------------------------------------------------------------------------- /src/py/ros_webrtc/peer_connection.py: -------------------------------------------------------------------------------- 1 | """ 2 | """ 3 | import time 4 | 5 | import bondpy.bondpy 6 | import roslaunch 7 | import rospy 8 | import std_msgs.msg 9 | 10 | from ros_webrtc import join_ros_names, normalize_ros_name 11 | import ros_webrtc.msg 12 | import ros_webrtc.srv 13 | 14 | 15 | class ROSBridge(object): 16 | 17 | @classmethod 18 | def _node(cls, 19 | pc, 20 | data_channel_label, 21 | wait_for_recv=None, 22 | **kwargs): 23 | args = [ 24 | '_session_id:={0}'.format(pc.session_id), 25 | '_label:={0}'.format(data_channel_label), 26 | '_peer_id:={0}'.format(pc.peer_id), 27 | ] 28 | if pc.namespace: 29 | args.append('_ros_webrtc_ns:={0}'.format(pc.namespace)) 30 | if wait_for_recv is not None: 31 | args.append('_wait_for_recv:={0}'.format(wait_for_recv)) 32 | node = roslaunch.core.Node( 33 | 'ros_webrtc', 34 | 'ros_webrtc_rosbridge', 35 | namespace=rospy.get_namespace(), 36 | name='rosbridge_{0}_{1}_{2}'.format(*map(normalize_ros_name, [ 37 | pc.session_id, data_channel_label, pc.peer_id 38 | ])), 39 | args=' '.join(args), 40 | **kwargs 41 | ) 42 | return node 43 | 44 | @classmethod 45 | def _bond(cls, 46 | pc, 47 | data_channel_label, 48 | **kwargs): 49 | return bondpy.bondpy.Bond( 50 | topic='rosbridge_bond', 51 | id='_'.join([pc.session_id, data_channel_label, pc.peer_id]), 52 | **kwargs 53 | ) 54 | 55 | def __init__(self, 56 | pc, 57 | data_channel_label, 58 | connect_timeout=None, 59 | heartbeat_timeout=None, 60 | on_broken=None, 61 | on_formed=None, 62 | **kwargs): 63 | self.node = self._node( 64 | pc=pc, 65 | data_channel_label=data_channel_label, 66 | **kwargs 67 | ) 68 | self.process = None 69 | self.bond = self._bond( 70 | pc=pc, 71 | data_channel_label=data_channel_label, 72 | on_broken=on_broken, 73 | on_formed=on_formed, 74 | ) 75 | if connect_timeout is not None: 76 | self.bond.connect_timeout = connect_timeout 77 | if heartbeat_timeout is not None: 78 | self.bond.heartbeat_timeout = heartbeat_timeout 79 | 80 | def __del__(self): 81 | self.stop() 82 | 83 | def start(self, launch, timeout=None): 84 | try: 85 | self.process = launch.launch(self.node) 86 | self.bond.start() 87 | if timeout: 88 | if not self.bond.wait_until_formed(rospy.Duration.from_sec(timeout)): 89 | raise RuntimeError( 90 | 'Bond "{0}" timed out after {1} sec(s).' 91 | .format(self.bond.topic, timeout) 92 | ) 93 | except Exception: 94 | self.stop() 95 | raise 96 | 97 | def stop(self): 98 | if self.process: 99 | if self.process.is_alive(): 100 | self.process.stop() 101 | self.process = None 102 | if self.bond: 103 | self.bond.shutdown() 104 | self.bond = None 105 | 106 | 107 | class RTCPeerConnection(object): 108 | 109 | def __init__( 110 | self, 111 | session_id, 112 | peer_id, 113 | namespace=None, 114 | wait_for_service=None, 115 | **kwargs): 116 | self.session_id = session_id 117 | self.peer_id = peer_id 118 | self.namespace = namespace or rospy.get_namespace() 119 | self.cmds = dict([ 120 | (name, rospy.ServiceProxy(join_ros_names(self.namespace, name), srv)) 121 | for name, srv in [ 122 | ('create_peer_connection', ros_webrtc.srv.CreatePeerConnection), 123 | ('delete_peer_connection', ros_webrtc.srv.DeletePeerConnection), 124 | ('add_ice_candidate', ros_webrtc.srv.AddIceCandidate), 125 | ('create_offer', ros_webrtc.srv.CreateOffer), 126 | ('create_data_channel', ros_webrtc.srv.CreateDataChannel), 127 | ('set_remote_description', ros_webrtc.srv.SetRemoteDescription), 128 | ] 129 | ]) 130 | self._cmd( 131 | 'create_peer_connection', 132 | wait_for_service=wait_for_service, 133 | **kwargs 134 | ) 135 | 136 | def __str__(self): 137 | return '{0}(session_id="{1}", peer_id="{2}")'.format( 138 | type(self).__name__, self.session_id, self.peer_id, 139 | ) 140 | 141 | def create_offer(self, **kwargs): 142 | return self._cmd('create_offer', **kwargs) 143 | 144 | def create_data_channel(self, **kwargs): 145 | return self._cmd('create_data_channel', **kwargs) 146 | 147 | def set_remote_description(self, **kwargs): 148 | return self._cmd( 149 | 'set_remote_description', 150 | session_description=ros_webrtc.msg.SessionDescription(**kwargs), 151 | ) 152 | 153 | def add_ice_candidate(self, **kwargs): 154 | return self._cmd('add_ice_candidate', **kwargs) 155 | 156 | def close(self): 157 | return self._cmd('delete_peer_connection') 158 | 159 | def bond(self, **kwargs): 160 | return bond( 161 | self.session_id, 162 | self.peer_id, 163 | namespace=self.namespace, 164 | **kwargs 165 | ) 166 | 167 | def rosbridge( 168 | self, 169 | data_channel_label, 170 | launch, 171 | timeout=None, 172 | **kwargs): 173 | rospy.loginfo( 174 | 'adapting %s datachannel "%s" to rosbridge', 175 | self, data_channel_label 176 | ) 177 | rosbridge = ROSBridge( 178 | pc=self, 179 | data_channel_label=data_channel_label, 180 | **kwargs 181 | ) 182 | rosbridge.start(launch, timeout=timeout) 183 | return rosbridge 184 | 185 | def _cmd(self, type_, wait_for_service=None, **kwargs): 186 | kwargs.update({ 187 | 'session_id': self.session_id, 188 | 'peer_id': self.peer_id, 189 | }) 190 | svc = self.cmds[type_] 191 | if wait_for_service: 192 | svc.wait_for_service(wait_for_service) 193 | return svc(**kwargs) 194 | 195 | 196 | class RTCPeerConnectionCallbacks(object): 197 | 198 | def __init__(self, pc): 199 | 200 | def _fqn(name): 201 | return join_ros_names( 202 | rospy.get_name(), 203 | 'session_{0}'.format(pc.session_id), 204 | 'peer_{0}'.format(pc.peer_id), 205 | name, 206 | ) 207 | 208 | self.pc = pc 209 | self.srvs = dict( 210 | (name, rospy.Service(_fqn(name), srv_cls, handler)) 211 | for name, srv_cls, handler in [ 212 | ('on_add_stream', ros_webrtc.srv.OnAddStream, self.on_add_stream), 213 | ('on_data_channel', ros_webrtc.srv.OnDataChannel, self.on_data_channel), 214 | ('on_ice_candidate', ros_webrtc.srv.OnIceCandidate, self.on_ice_candidate), 215 | ('on_ice_connection_state_change', ros_webrtc.srv.OnIceConnectionStateChange, self.on_ice_connection_state_change), 216 | ('on_negotiation_needed', ros_webrtc.srv.OnNegotiationNeeded, self.on_negotiation_needed), 217 | ('on_remove_stream', ros_webrtc.srv.OnRemoveStream, self.on_remove_stream), 218 | ('on_set_session_description', ros_webrtc.srv.OnSetSessionDescription, self.on_set_session_description), 219 | ('on_signaling_state_change', ros_webrtc.srv.OnSignalingStateChange, self.on_signaling_state_change), 220 | ] 221 | ) 222 | 223 | def shutdown(self): 224 | for srv in self.srvs.values(): 225 | srv.shutdown() 226 | 227 | def on_add_stream(self, req): 228 | resp = ros_webrtc.srv.OnAddStreamResponse() 229 | return resp 230 | 231 | def on_data_channel(self, req): 232 | resp = ros_webrtc.srv.OnDataChannelResponse() 233 | return resp 234 | 235 | def on_ice_candidate(self, req): 236 | resp = ros_webrtc.srv.OnIceCandidateResponse() 237 | return resp 238 | 239 | def on_ice_connection_state_change(self, req): 240 | resp = ros_webrtc.srv.OnIceConnectionStateChangeResponse() 241 | return resp 242 | 243 | def on_negotiation_needed(self, req): 244 | resp = ros_webrtc.srv.OnNegotiationNeededResponse() 245 | return resp 246 | 247 | def on_remove_stream(self, req): 248 | resp = ros_webrtc.srv.OnRemoveStreamResponseResponse() 249 | return resp 250 | 251 | def on_set_session_description(self, req): 252 | resp = ros_webrtc.srv.OnSetSessionDescriptionResponse() 253 | return resp 254 | 255 | def on_signaling_state_change(self, req): 256 | resp = ros_webrtc.srv.OnSignalingStateChangeResponse() 257 | return resp 258 | 259 | 260 | class RTCPeerConnectionEvents(object): 261 | 262 | def __init__(self, pc): 263 | self.pc = pc 264 | self.subscribers = [ 265 | rospy.Subscriber( 266 | join_ros_names( 267 | pc.namespace, 268 | 'session_{0}'.format(pc.session_id), 269 | 'peer_{0}'.format(pc.peer_id), 270 | topic, 271 | ), 272 | data_cls, 273 | handler 274 | ) 275 | for topic, data_cls, handler in [ 276 | ('data_channel', ros_webrtc.msg.DataChannel, self.on_data_channel), 277 | ('negotiation_needed', std_msgs.msg.Empty, self.on_negotiation_needed), 278 | ('ice_candidate', ros_webrtc.msg.IceCandidate, self.on_ice_candidate), 279 | ('ice_candidate_state_change', ros_webrtc.msg.IceCandidateState, self.on_ice_candidate_state_change), 280 | ('signaling_state_change', ros_webrtc.msg.SignalingState, self.on_signaling_state_change), 281 | ('add_stream', ros_webrtc.msg.Stream, self.on_add_stream), 282 | ('remove_stream', ros_webrtc.msg.Stream, self.on_remove_stream), 283 | ('set_session_description', ros_webrtc.msg.SessionDescription, self.on_set_session_description), 284 | ('close', std_msgs.msg.Empty, self.on_close), 285 | ] 286 | ] 287 | 288 | def wait_for_recv(self, timeout=5.0, poll_freq=1.0): 289 | rospy.loginfo( 290 | '%s wait_for_recv - timeout=%0.4f, poll_freq=%0.4f', 291 | self, timeout, poll_freq, 292 | ) 293 | stared_at = time.time() 294 | expire_at = time.time() + timeout 295 | subscribers = self.subscribers[:] 296 | while subscribers: 297 | if subscribers[0].get_num_connections() != 0: 298 | subscribers.pop(0) 299 | elif time.time() >= expire_at: 300 | rospy.loginfo( 301 | '%s wait_for_recv - expired after %0.4f sec(s)', 302 | self, time.time() - stared_at 303 | ) 304 | return False 305 | else: 306 | time.sleep(poll_freq) 307 | rospy.loginfo( 308 | '%s wait_for_recv - succeeded after %0.4f sec(s)', 309 | self, time.time() - stared_at, 310 | ) 311 | return True 312 | 313 | def unregister(self): 314 | for s in self.subscribers: 315 | s.unregister() 316 | 317 | def on_data_channel(self, req): 318 | pass 319 | 320 | def on_negotiation_needed(self, req): 321 | pass 322 | 323 | def on_ice_candidate(self, req): 324 | pass 325 | 326 | def on_ice_candidate_state_change(self, req): 327 | pass 328 | 329 | def on_signaling_state_change(self, req): 330 | pass 331 | 332 | def on_add_stream(self, req): 333 | pass 334 | 335 | def on_remove_stream(self, req): 336 | pass 337 | 338 | def on_set_session_description(self, req): 339 | pass 340 | 341 | def on_close(self, req): 342 | pass 343 | 344 | 345 | def bond(session_id, peer_id, namespace=None, **kwargs): 346 | return bondpy.bondpy.Bond( 347 | topic=join_ros_names(namespace, 'peer_connection_bond'), 348 | id='_'.join([session_id, peer_id]), 349 | **kwargs 350 | ) 351 | -------------------------------------------------------------------------------- /src/py/ros_webrtc/signaling.py: -------------------------------------------------------------------------------- 1 | """ 2 | """ 3 | import json 4 | 5 | import rospy 6 | 7 | from ws4py.client.threadedclient import WebSocketClient 8 | 9 | 10 | class SignalClient(WebSocketClient): 11 | 12 | def __init__(self, *args, **kwargs): 13 | self.handler = kwargs.pop('handler') 14 | super(SignalClient, self).__init__(*args, **kwargs) 15 | self._map = { 16 | 'connect': self.handler.on_connect, 17 | 'disconnect': self.handler.on_disconnect, 18 | 'call': self.handler.on_call, 19 | 'pickup': self.handler.on_pickup, 20 | 'add_ice_candidate': self.handler.on_add_ice_candidate, 21 | 'set_session_description': self.handler.on_set_session_description, 22 | 'hangup': self.handler.on_hangup, 23 | } 24 | 25 | # WebSocketClient 26 | 27 | def send(self, type_, channel, session, payload=None): 28 | msg = { 29 | 'channel': channel, 30 | 'session': session, 31 | 'type': type_, 32 | 'payload': payload, 33 | } 34 | text = json.dumps(msg, indent=4) 35 | rospy.logdebug('sending signal\n%s', text) 36 | return super(SignalClient, self).send(text, binary=False) 37 | 38 | def received_message(self, message): 39 | msg = json.loads(str(message)) 40 | channel, session, type_, payload = ( 41 | msg['channel'], 42 | msg['session'], 43 | msg['type'], 44 | msg.get('payload'), 45 | ) 46 | rospy.logdebug( 47 | 'received signal - channel="%s", session="%s", type="%s" payload=\n%s', 48 | channel, session, type_, json.dumps(payload, indent=4) 49 | ) 50 | try: 51 | handler = self._map.get(type_) 52 | if handler is None: 53 | rospy.logwarn('signal type "%s" not supported', type_) 54 | return 55 | try: 56 | handler(channel, session, payload) 57 | except DropSignal, ex: 58 | rospy.loginfo( 59 | 'dropping signal - channel="%s", session="%s", type="%s" - %s', 60 | channel, session, type_, ex, 61 | ) 62 | except Exception, ex: 63 | rospy.logerr(ex) 64 | 65 | 66 | class DropSignal(Exception): 67 | 68 | pass 69 | 70 | 71 | class SignalHandler(object): 72 | 73 | def on_connect(self, channel, session, payload): 74 | pass 75 | 76 | def on_disconnect(self, channel, session, payload): 77 | pass 78 | 79 | def on_call(self, channel, session, payload): 80 | pass 81 | 82 | def on_pickup(self, channel, session, payload): 83 | pass 84 | 85 | def on_add_ice_candidate(self, channel, session, payload): 86 | pass 87 | 88 | def on_set_session_description(self, channel, session, payload): 89 | pass 90 | 91 | def on_hangup(self, channel, session, payload): 92 | pass 93 | -------------------------------------------------------------------------------- /srv/AddIceCandidate.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | string sdp_mid 4 | int32 sdp_mline_index 5 | string candidate 6 | --- 7 | -------------------------------------------------------------------------------- /srv/CreateDataChannel.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | string label 4 | int32 id 5 | bool reliable 6 | bool ordered 7 | string protocol 8 | --- 9 | -------------------------------------------------------------------------------- /srv/CreateOffer.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | --- 4 | -------------------------------------------------------------------------------- /srv/CreatePeerConnection.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | ros_webrtc/MediaConstraints sdp_constraints 4 | string[] video_sources 5 | string[] audio_sources 6 | --- 7 | -------------------------------------------------------------------------------- /srv/DeletePeerConnection.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | --- 4 | -------------------------------------------------------------------------------- /srv/ExampleCallPeer.srv: -------------------------------------------------------------------------------- 1 | string peer_id 2 | string session_id 3 | --- 4 | ros_webrtc/ExampleCall call 5 | -------------------------------------------------------------------------------- /srv/ExampleGetCalls.srv: -------------------------------------------------------------------------------- 1 | --- 2 | ros_webrtc/ExampleCall[] calls 3 | -------------------------------------------------------------------------------- /srv/ExampleHangup.srv: -------------------------------------------------------------------------------- 1 | string id 2 | string peer_id 3 | --- 4 | -------------------------------------------------------------------------------- /srv/GetHost.srv: -------------------------------------------------------------------------------- 1 | --- 2 | ros_webrtc/MediaConstraints sdp_constraints 3 | ros_webrtc/Source[] audio_sources 4 | ros_webrtc/Source[] video_sources 5 | ros_webrtc/PeerConnectionKey[] peer_connections 6 | -------------------------------------------------------------------------------- /srv/GetPeerConnection.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | --- 4 | ros_webrtc/PeerConnection peer_connection 5 | -------------------------------------------------------------------------------- /srv/OnAddStream.srv: -------------------------------------------------------------------------------- 1 | ros_webrtc/Stream stream 2 | --- 3 | -------------------------------------------------------------------------------- /srv/OnDataChannel.srv: -------------------------------------------------------------------------------- 1 | ros_webrtc/DataChannel data_channel 2 | --- 3 | -------------------------------------------------------------------------------- /srv/OnIceCandidate.srv: -------------------------------------------------------------------------------- 1 | ros_webrtc/IceCandidate candidate 2 | --- 3 | -------------------------------------------------------------------------------- /srv/OnIceConnectionStateChange.srv: -------------------------------------------------------------------------------- 1 | --- 2 | -------------------------------------------------------------------------------- /srv/OnNegotiationNeeded.srv: -------------------------------------------------------------------------------- 1 | --- 2 | -------------------------------------------------------------------------------- /srv/OnRemoveStream.srv: -------------------------------------------------------------------------------- 1 | ros_webrtc/Stream stream 2 | --- 3 | -------------------------------------------------------------------------------- /srv/OnSetSessionDescription.srv: -------------------------------------------------------------------------------- 1 | string type 2 | string sdp 3 | --- 4 | -------------------------------------------------------------------------------- /srv/OnSignalingStateChange.srv: -------------------------------------------------------------------------------- 1 | --- 2 | -------------------------------------------------------------------------------- /srv/RotateVideoSource.srv: -------------------------------------------------------------------------------- 1 | string label 2 | int32 rotation 3 | --- 4 | -------------------------------------------------------------------------------- /srv/SendData.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | ros_webrtc/Data data 4 | --- 5 | -------------------------------------------------------------------------------- /srv/SetIceServers.srv: -------------------------------------------------------------------------------- 1 | IceServer[] ice_servers 2 | --- 3 | -------------------------------------------------------------------------------- /srv/SetRemoteDescription.srv: -------------------------------------------------------------------------------- 1 | string session_id 2 | string peer_id 3 | ros_webrtc/SessionDescription session_description 4 | --- 5 | -------------------------------------------------------------------------------- /test/fixtures/bags/.gitignore: -------------------------------------------------------------------------------- 1 | * 2 | !.gitignore 3 | -------------------------------------------------------------------------------- /test/fixtures/params/cameras.yaml: -------------------------------------------------------------------------------- 1 | downward: 2 | name: ros:///downward_looking_camera/image_raw 3 | label: downward 4 | publish: true 5 | constraints: 6 | optional: 7 | maxWidth: "640" 8 | minWidth: "640" 9 | maxHeight: "480" 10 | minHeight: "480" 11 | upward: 12 | name: ros:///upward_looking_camera/image_raw 13 | label: upward 14 | publish: true 15 | constraints: 16 | optional: 17 | maxWidth: "640" 18 | minWidth: "640" 19 | maxHeight: "480" 20 | minHeight: "480" 21 | -------------------------------------------------------------------------------- /test/fixtures/params/ice_servers.yaml: -------------------------------------------------------------------------------- 1 | - uri: stun:stun.services.mozilla.com:3478 2 | - uri: stun:stun.l.google.com:19302 3 | -------------------------------------------------------------------------------- /test/fixtures/params/peer_connection.yaml: -------------------------------------------------------------------------------- 1 | constraints: 2 | optional: 3 | DtlsSrtpKeyAgreement: "true" 4 | -------------------------------------------------------------------------------- /test/fixtures/site/.gitignore: -------------------------------------------------------------------------------- 1 | bower_components 2 | dist 3 | npm_modules 4 | -------------------------------------------------------------------------------- /test/fixtures/site/bower.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "ros-webrtc", 3 | "version": "0.1.0", 4 | "dependencies": { 5 | "adapterjs": "^0.13.2", 6 | "bootstrap": "^3.3.6", 7 | "livereload-js": "^2.2.1", 8 | "screenfull": "^3.0.0", 9 | "font-awesome": "fontawesome#^4.5.0", 10 | "backbone": "^1.3.3", 11 | "js-url": "^2.3.0", 12 | "uuid-js": "^0.7.5", 13 | "meatyjs": "^0.1.0", 14 | "roslib": "https://github.com/aisch/roslibjs.git#created-rtc-data-channel" 15 | }, 16 | "analytics": false 17 | } 18 | -------------------------------------------------------------------------------- /test/fixtures/site/gruntfile.js: -------------------------------------------------------------------------------- 1 | module.exports = function (grunt) { 2 | 3 | grunt.loadNpmTasks('grunt-contrib-connect'); 4 | grunt.loadNpmTasks('grunt-contrib-clean'); 5 | grunt.loadNpmTasks('grunt-contrib-copy'); 6 | grunt.loadNpmTasks('grunt-contrib-jshint'); 7 | grunt.loadNpmTasks('grunt-contrib-watch'); 8 | 9 | grunt.config.init({ 10 | pkg: grunt.file.readJSON('package.json'), 11 | 12 | clean: ['dist'], 13 | 14 | connect: { 15 | server: { 16 | options: { 17 | hostname: '*', 18 | port: 8080, 19 | debug: false, 20 | base: 'dist' 21 | } 22 | } 23 | }, 24 | 25 | copy: { 26 | src: { 27 | files: [{ 28 | cwd: 'src/', 29 | src: ['*.css'], 30 | dest: 'dist/css/', 31 | expand: true 32 | }, { 33 | cwd: 'src/', 34 | src: ['*.js'], 35 | dest: 'dist/js/', 36 | expand: true 37 | }, { 38 | cwd: 'src/', 39 | src: ['*.html'], 40 | dest: 'dist/', 41 | expand: true 42 | }] 43 | }, 44 | vendor: { 45 | files: [{ 46 | src: 'bower_components/adapterjs/publish/adapter.debug.js', 47 | dest: 'dist/js/adapter.js' 48 | }, { 49 | src: 'bower_components/jquery/jquery.js', 50 | dest: 'dist/js/jquery.js' 51 | }, { 52 | src: 'bower_components/livereload-js/dist/livereload.js', 53 | dest: 'dist/livereload.js' 54 | }, { 55 | src: 'bower_components/bootstrap/dist/js/bootstrap.js', 56 | dest: 'dist/js/bootstrap.js' 57 | }, { 58 | cwd: 'bower_components/bootstrap/dist/css/', 59 | src: ['bootstrap.css*'], 60 | dest: 'dist/css/', 61 | expand: true 62 | }, { 63 | cwd: 'bower_components/font-awesome/css/', 64 | src: ['*'], 65 | dest: 'dist/css', 66 | expand: true 67 | }, { 68 | cwd: 'bower_components/font-awesome/fonts/', 69 | src: ['*'], 70 | dest: 'dist/fonts', 71 | expand: true 72 | }, { 73 | src: 'bower_components/screenfull/dist/screenfull.js', 74 | dest: 'dist/js/screenfull.js' 75 | }, { 76 | src: 'bower_components/jquery/dist/jquery.js', 77 | dest: 'dist/js/jquery.js' 78 | }, { 79 | src: 'bower_components/backbone/backbone.js', 80 | dest: 'dist/js/backbone.js' 81 | }, { 82 | src: 'bower_components/underscore/underscore.js', 83 | dest: 'dist/js/underscore.js' 84 | }, { 85 | src: 'bower_components/uuid-js/lib/uuid.js', 86 | dest: 'dist/js/uuid.js' 87 | }, { 88 | src: 'bower_components/meatyjs/dist/meaty.js', 89 | dest: 'dist/js/meaty.js' 90 | }, { 91 | src: 'bower_components/roslib/build/roslib.js', 92 | dest: 'dist/js/roslib.js' 93 | }, { 94 | src: 'bower_components/eventemitter2/lib/eventemitter2.js', 95 | dest: 'dist/js/eventemitter2.js' 96 | }, { 97 | src: 'bower_components/screenfull/dist/screenfull.js', 98 | dest: 'dist/js/screenfull.js' 99 | }] 100 | } 101 | }, 102 | 103 | jshint: { 104 | grunt: [ 105 | 'gruntfile.js' 106 | ], 107 | src: [ 108 | 'gruntfile.js', 109 | 'src/*.js' 110 | ], 111 | options: { 112 | debug: true 113 | } 114 | }, 115 | 116 | watch: { 117 | grunt: { 118 | files: 'Gruntfile.js' 119 | }, 120 | src: { 121 | options: { 122 | livereload: true 123 | }, 124 | files: [ 125 | 'bower_components/**', 126 | 'src/**' 127 | ], 128 | tasks: ['build'] 129 | } 130 | } 131 | 132 | }); 133 | 134 | grunt.registerTask('build', ['jshint', 'copy:vendor', 'copy:src']); 135 | grunt.registerTask('dev', ['clean', 'build', 'connect', 'watch']); 136 | grunt.registerTask('default', ['build']); 137 | }; 138 | -------------------------------------------------------------------------------- /test/fixtures/site/package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "ros-webrtc", 3 | "version": "0.1.0", 4 | "devDependencies": { 5 | "eslint-config-google": "^0.4.0", 6 | "grunt": "^1.0.1", 7 | "grunt-contrib-clean": "^1.0.0", 8 | "grunt-contrib-connect": "^1.0.1", 9 | "grunt-contrib-copy": "^1.0.0", 10 | "grunt-contrib-jshint": "^1.0.0", 11 | "grunt-contrib-watch": "^1.0.0" 12 | } 13 | } 14 | -------------------------------------------------------------------------------- /test/fixtures/site/src/demo.css: -------------------------------------------------------------------------------- 1 | body { 2 | font: 20px sans-serif; 3 | margin: 0; 4 | } 5 | 6 | /* player */ 7 | 8 | #player { 9 | position: relative; 10 | text-align: center; 11 | background-color: black; 12 | } 13 | 14 | #player video { 15 | } 16 | 17 | /* msg */ 18 | 19 | #msg-send { 20 | background-color: orange; 21 | border-top: 1px dashed grey; 22 | } 23 | 24 | #msg-send i { 25 | float: left; 26 | position: relative; 27 | z-index: 2; 28 | } 29 | 30 | #msg-send input { 31 | width: 100%; 32 | margin-left: 5px; 33 | padding-left: 5px; 34 | padding-top: 2px; 35 | padding-bottom: 2px; 36 | height: 40px; 37 | border-bottom: none; 38 | border-top: none; 39 | } 40 | 41 | #msg-send input:focus { 42 | outline: none; 43 | } 44 | 45 | #msg-send span { 46 | display: block; 47 | overflow: hidden; 48 | } 49 | 50 | #msg-recv-header { 51 | background-color: orange; 52 | border-top: 1px dashed grey; 53 | } 54 | 55 | #msg-recv-header i { 56 | float: left; 57 | position: relative; 58 | z-index: 2; 59 | } 60 | 61 | #msg-recv-header button { 62 | font: 20px sans-serif; 63 | margin-right: 1px; 64 | margin-top: 1px; 65 | } 66 | 67 | #msg-recv-log { 68 | overflow: auto; 69 | } 70 | 71 | #msg-recv-log ol { 72 | list-style-type: none; 73 | padding-left: 0; 74 | counter-reset: msg-recv-no; 75 | border-bottom: 1px dashed grey; 76 | } 77 | 78 | #msg-recv-log ol li { 79 | position: relative; 80 | margin-left: 50px; 81 | padding-left: 10px; 82 | } 83 | 84 | @keyframes msg-recv-log-glow { 85 | 0% { 86 | color: rgb(150, 150, 150); 87 | } 88 | 89 | 50% { 90 | color: rgb(255, 255, 255); 91 | } 92 | 93 | 100% { 94 | color: rgb(150, 150, 150); 95 | } 96 | } 97 | 98 | #msg-recv-log ol li::before { 99 | animation-duration: 1s; 100 | animation-name: msg-recv-log-glow; 101 | counter-increment: msg-recv-no; 102 | content: counter(msg-recv-no); 103 | text-align: right; 104 | position: absolute; 105 | left: -52px; 106 | width: 50px; 107 | -webkit-user-select: none; 108 | -moz-user-select: none; 109 | user-select: none; 110 | margin-right: 5px; 111 | font-size: 80%; 112 | background-color: rgb(50, 50, 50); 113 | color: rgb(150, 150, 150); 114 | font-weight: bold; 115 | padding: 3px 8px; 116 | border-right: 2px solid grey; 117 | } 118 | 119 | .msg-flash { 120 | position: absolute; 121 | margin-left: 10px; 122 | margin-top: 10px; 123 | height: 20px; 124 | width: 20px; 125 | background-color: white; 126 | z-index: 1; 127 | opacity: 0.2; 128 | } 129 | 130 | /* settings */ 131 | 132 | #settings-toggle { 133 | transition: all 0.5s ease; 134 | color: #fff; 135 | opacity: 0.5; 136 | position: absolute; 137 | background-color: black; 138 | top: 0px; 139 | right: 0px; 140 | } 141 | 142 | #settings-toggle:hover { 143 | opacity: 0.9; 144 | } 145 | 146 | #settings-defaults { 147 | float: left; 148 | } 149 | -------------------------------------------------------------------------------- /test/fixtures/site/src/demo.js: -------------------------------------------------------------------------------- 1 | var Settings = Backbone.Model.extend({ 2 | 3 | defaults: { 4 | signaling_server: { 5 | url: 'ws://127.0.0.1:9000' 6 | }, 7 | ice_servers: [{ 8 | url: navigator.mozGetUserMedia ? 'stun:stun.services.mozilla.com' : 9 | navigator.webkitGetUserMedia ? 'stun:stun.l.google.com:19302' : 10 | 'stun:23.21.150.121' 11 | }], 12 | }, 13 | 14 | initialize: function (attributes, options) { 15 | options = options || {}; 16 | _.defaults(options , { 17 | storage: window.localStorage 18 | }); 19 | this.storage = options.storage; 20 | }, 21 | 22 | fetch: function () { 23 | _.each(_.keys(this.attributes), function (key) { 24 | if (this.storage.getItem(key) !== null) { 25 | this.set(key, JSON.parse(this.storage.getItem(key))); 26 | } else if (key in this.defaults){ 27 | this.set(key, this.defaults[key]); 28 | } else { 29 | this.unset(key); 30 | } 31 | }, this); 32 | }, 33 | 34 | reset: function () { 35 | _.each( 36 | this.defaults, 37 | function (value, key) { this.set(key, value); }, 38 | this 39 | ); 40 | }, 41 | 42 | save: function () { 43 | _.each( 44 | this.attributes, 45 | function (v, k) { 46 | this.storage.setItem(k, v === null ? null : JSON.stringify(v)); 47 | }, 48 | this 49 | ); 50 | } 51 | 52 | }); 53 | 54 | var SettingsDialog = Backbone.View.extend({ 55 | 56 | initialize: function (options) { 57 | var that = this; 58 | 59 | options = options || {}; 60 | this.settings = options.settings; 61 | 62 | this.$el.find('#settings-toggle').on('click', function () { 63 | that.toggle(); 64 | }); 65 | 66 | this.$el.find('#settings-defaults').on('click', function () { 67 | that.settings.reset(); 68 | that.load(); 69 | }); 70 | 71 | this.$el.find('#settings-save').on('click', $.proxy(function () { 72 | this.save(); 73 | this.$el.find('#settings').modal('hide'); 74 | (options.location || window.location).reload(); 75 | }, this)); 76 | 77 | this.$el.find('#settings').on('shown.bs.modal', function () { 78 | that.$el.keyup(function (e) { 79 | if (e.which == 13) { 80 | that.$el.find('#settings-save').click(); 81 | } 82 | }); 83 | }); 84 | this.$el.find('#settings').on('hidden.bs.modal', function () { 85 | that.$el.off('keyup'); 86 | }); 87 | }, 88 | 89 | load: function () { 90 | this.$el.find('#settings-signaling-server-url').val(this.settings.get('signaling_server').url); 91 | }, 92 | 93 | save: function () { 94 | this.settings.set('signaling_server', { 95 | url: this.$el.find('#settings-signaling-server-url').val() 96 | }); 97 | this.settings.save(); 98 | }, 99 | 100 | toggle: function () { 101 | this.settings.fetch(); 102 | this.load(); 103 | this.$el.find('#settings').modal('toggle'); 104 | } 105 | 106 | }); 107 | 108 | var Router = Backbone.Router.extend({ 109 | 110 | routes: { 111 | ':my_id/call/:peer_id': 'call', 112 | ':my_id/wait': 'wait', 113 | ':my_id': 'default', 114 | '': 'root' 115 | }, 116 | 117 | call: function (my_id, peer_id) { 118 | if (signaling) { 119 | window.location.reload(); 120 | return; 121 | } 122 | callPeer(my_id, peer_id); 123 | }, 124 | 125 | wait: function (my_id) { 126 | if (signaling) { 127 | window.location.reload(); 128 | return; 129 | } 130 | waitForCall(my_id); 131 | }, 132 | 133 | default: function (my_id) { 134 | this.navigate(my_id + '/wait', {trigger: true}); 135 | }, 136 | 137 | root: function () { 138 | var my_id = UUIDjs.create().toString().replace(/-/g, ''); 139 | this.navigate(my_id + '/wait', {trigger: true}); 140 | } 141 | 142 | }); 143 | 144 | RemotePlayer = Backbone.View.extend({ 145 | 146 | initialize: function() { 147 | this.listenTo(this.model, 'change:stream', this.render); 148 | }, 149 | 150 | render: function() { 151 | var stream = this.model.get('stream'); 152 | attachMediaStream(this.$el.find('video').get(0), stream); 153 | }, 154 | 155 | toggleFullscreen: function () { 156 | screenfull.toggle(this.$el.find('video').get(0)); 157 | } 158 | 159 | }); 160 | 161 | SendMessage = Backbone.View.extend({ 162 | 163 | defaults: { 164 | flash_duration: 200 165 | }, 166 | 167 | initialize: function (options) { 168 | var that = this; 169 | 170 | this.options = _.defaults(options, this.defaults); 171 | 172 | this.$el.find('input').keyup(function (e) { 173 | switch (e.which) { 174 | case 13: // enter 175 | that.model.publish({data: this.value}); 176 | this.value = ''; 177 | that.flash(); 178 | break; 179 | 180 | case 27: // esc 181 | this.value = ''; 182 | if (document.activeElement != $('body').get(0)) { 183 | document.activeElement.blur(); 184 | } 185 | break; 186 | } 187 | }); 188 | }, 189 | 190 | flash: function () { 191 | var that = this, 192 | el = this.$el.find('.msg-flash'); 193 | 194 | if (el.is(':animated')) 195 | return; 196 | el.animate({opacity: 1.0}, this.options.flash_duration, function () { 197 | el.animate({opacity: 0.2}, that.options.flash_duration); 198 | }); 199 | }, 200 | 201 | }); 202 | 203 | ReceiveMessages = Backbone.View.extend({ 204 | 205 | defaults: { 206 | flash_duration: 200, 207 | scroll_speed: 0, 208 | }, 209 | 210 | initialize: function (options) { 211 | var that = this; 212 | 213 | this.options = _.defaults(options, this.defaults); 214 | 215 | // model 216 | 217 | this.model.subscribe(function (message) { 218 | that.$el.find('#msg-recv-log ol').append( 219 | '
  • ' + (message.data || ' ') + '
  • ' 220 | ); 221 | if (that.isScrollActive()) { 222 | that.scroll(that.options.scroll_speed); 223 | } 224 | that.flash(); 225 | }); 226 | 227 | // clear 228 | 229 | this.$el.find('#msg-recv-clear').click(function () { 230 | that.$el.find('#msg-recv-log ol li').remove(); 231 | }); 232 | 233 | // resize 234 | 235 | $(window).resize(function () { 236 | that.resize(); 237 | }); 238 | $('#player video').resize(function () { 239 | that.resize(); 240 | }); 241 | this.resize(); 242 | 243 | // scroll 244 | 245 | this.$el.find('#msg-recv-scroll').click(function () { 246 | if (!that.isScrollActive()) { 247 | that.scroll(that.options.scroll_speed); 248 | } 249 | }); 250 | if (this.isScrollActive()) { 251 | this.scroll(this.options.scroll_speed); 252 | } 253 | }, 254 | 255 | resize: function () { 256 | var height = ($(window).height() - $('#msg-recv-log').position().top) + "px"; 257 | $('#msg-recv-log').css('height', height); 258 | }, 259 | 260 | flash: function () { 261 | var that = this, 262 | el = this.$el.find('.msg-flash'); 263 | 264 | if (el.is(':animated')) 265 | return; 266 | el.animate({opacity: 1.0}, this.options.flash_duration, function () { 267 | el.animate({opacity: 0.2}, that.options.flash_duration); 268 | }); 269 | }, 270 | 271 | isScrollActive: function () { 272 | return this.$el.find('#msg-recv-scroll').hasClass('active'); 273 | }, 274 | 275 | scroll: function (duration) { 276 | var log = this.$el.find('#msg-recv-log'); 277 | duration = _.isUndefined(duration) ? 0 : duration; 278 | log.animate({ scrollTop: log[0].scrollHeight}, duration); 279 | } 280 | 281 | }); 282 | 283 | // state 284 | 285 | var signaling = null, 286 | call = null, 287 | remote_player = null, 288 | ros = null, 289 | chatter_topic = null, 290 | send_msg = null, 291 | recv_msgs = null; 292 | 293 | function initialize(dc) { 294 | ros = new ROSLIB.Ros(); 295 | 296 | ros.transportLibrary = call.pc; 297 | ros.transportOptions = { 298 | reliable: false, 299 | ordered: false, 300 | protocol: 'application/vnd.rosbridge.v1+json; chunksize=512' 301 | }; 302 | ros.connect(dc); 303 | call.adaptROSClient(ros); 304 | 305 | chatter_topic = new ROSLIB.Topic({ 306 | ros: ros, 307 | name: '/ros_webrtc/chatter', 308 | messageType: 'std_msgs/String' 309 | }); 310 | 311 | send_msg = new SendMessage({ 312 | el: $('#msg-send').get(0), 313 | model: chatter_topic 314 | }); 315 | 316 | recv_msgs = new ReceiveMessages({ 317 | el: $('#msg-recv').get(0), 318 | model: chatter_topic 319 | }); 320 | } 321 | 322 | function waitForCall(my_id) { 323 | signaling = new ros_webrtc.Signaling({ 324 | server: settings.get('signaling_server').url, 325 | id: my_id 326 | }); 327 | 328 | signaling.once('call', function (signaling, session_id, peer_id) { 329 | if (call) { 330 | console.loginfo('busy, ignoring call "' + session_id + '" from "' + peer_id + '"'); 331 | return; 332 | } 333 | call = new ros_webrtc.Call({ 334 | id: session_id, 335 | peer_id: peer_id, 336 | signaling: signaling 337 | }); 338 | remote_player = new RemotePlayer({ 339 | el: $('#player'), 340 | model: call 341 | }); 342 | call.on('datachannel', function (data_channel) { 343 | initialize(data_channel); 344 | }); 345 | call.pickup(); 346 | }); 347 | } 348 | 349 | function callPeer(my_id, peer_id) { 350 | signaling = new ros_webrtc.Signaling({ 351 | server: settings.get('signaling_server').url, 352 | id: my_id 353 | }); 354 | 355 | signaling.once('connected', function () { 356 | call = new ros_webrtc.Call({ 357 | // id: UUIDjs.create().toString().replace(/-/g, ''), 358 | id: UUIDjs.create().toString().replace(/-/g, ''), 359 | peer_id: peer_id, 360 | signaling: signaling 361 | }); 362 | remote_player = new RemotePlayer({ 363 | el: $('#player'), 364 | model: call 365 | }); 366 | initialize('rosbridge'); 367 | call.dial(); 368 | }); 369 | } 370 | 371 | // global 372 | 373 | var settings = new Settings(); 374 | 375 | settings.fetch(); 376 | 377 | var settings_dialog = new SettingsDialog({ 378 | el: $('body').get(0), 379 | settings: settings 380 | }); 381 | 382 | $(window).on('beforeunload', function() { 383 | if (call) { 384 | call.hangup(); 385 | } 386 | }); 387 | 388 | $(document).keyup(function (event) { 389 | var targets = [$('body').get(0) ]; 390 | if (!_.any (targets, function (el) { return event.target ==el; })) 391 | return; 392 | switch (event.which) { 393 | case 32: // space 394 | send_msg.$el.find('input').focus(); 395 | break; 396 | 397 | case 115: // s 398 | case 83: // S 399 | settings_dialog.toggle(); 400 | break; 401 | 402 | case 102: // f 403 | case 70: // F 404 | if (remote_player) 405 | remote_player.toggleFullscreen(); 406 | break; 407 | } 408 | }); 409 | 410 | var router = new Router(); 411 | 412 | Backbone.history.start({ root: window.location.pathname }); 413 | -------------------------------------------------------------------------------- /test/fixtures/site/src/index.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | ROS WebRTC 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 |
    36 | 37 |
    38 | 39 | 40 |
    41 | 42 |
    43 |
    44 | 45 | 46 |
    47 | 48 |
    49 |
    50 |
    51 | 52 | 53 | 54 |
    55 | 56 |
    57 |
      58 |
    59 |
    60 |
    61 | 62 |
    63 | 64 | 65 | 66 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | -------------------------------------------------------------------------------- /test/integration/.coveragerc: -------------------------------------------------------------------------------- 1 | [run] 2 | parallel=true 3 | include=*/src/py/ros_webrtc/* 4 | -------------------------------------------------------------------------------- /test/integration/host-test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /test/integration/host_test.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | import collections 3 | import time 4 | import unittest 5 | 6 | import rospy 7 | import rostest 8 | 9 | import sensor_msgs.msg 10 | 11 | import ros_webrtc.srv 12 | 13 | from ros_coverage import ros_coverage 14 | 15 | 16 | PKG = 'ros_webrtc' 17 | NAME = 'host_test' 18 | 19 | 20 | class TestHost(unittest.TestCase): 21 | 22 | def _video_topic(self, label): 23 | return 'local/{label}'.format(label=label) 24 | 25 | def _audio_topic(self, label): 26 | return 'local/{label}'.format(label=label) 27 | 28 | def _service(self, name): 29 | return '{0}'.format(name) 30 | 31 | def test_video(self): 32 | 33 | def callback(image, topic): 34 | frames[topic] += 1 35 | 36 | frames = collections.Counter(); 37 | 38 | topics = [ 39 | self._video_topic('downward'), 40 | self._video_topic('upward'), 41 | ] 42 | 43 | subscribers = [ 44 | rospy.Subscriber(topic, sensor_msgs.msg.Image, callback, topic) 45 | for topic in topics 46 | ] 47 | 48 | min_frames, expires_at = 3, time.time() + 60 49 | 50 | while (not rospy.core.is_shutdown() and 51 | not all(min_frames <= frames[topic] for topic in topics) and 52 | time.time() < expires_at): 53 | rospy.sleep(2.0) 54 | 55 | for topic in topics: 56 | self.assertGreaterEqual(frames[topic], min_frames) 57 | 58 | def test_conf(self): 59 | srv = rospy.ServiceProxy(self._service('get_host'), ros_webrtc.srv.GetHost) 60 | srv.wait_for_service(5.0) 61 | resp = srv() 62 | self.assertEqual(len(resp.sdp_constraints.optional), 1) 63 | self.assertTrue(resp.sdp_constraints.optional[0].key == 'DtlsSrtpKeyAgreement') 64 | self.assertTrue(resp.sdp_constraints.optional[0].value) 65 | self.assertEqual(len(resp.sdp_constraints.mandatory), 0) 66 | self.assertEqual(len(resp.video_sources), 2) 67 | self.assertEqual(len(resp.audio_sources), 1) 68 | self.assertEqual(resp.peer_connections, []) 69 | 70 | 71 | def main(): 72 | rospy.init_node(NAME) 73 | with ros_coverage(): 74 | rostest.rosrun(PKG, NAME, TestHost) 75 | 76 | 77 | if __name__ == '__main__': 78 | main() 79 | -------------------------------------------------------------------------------- /test/integration/peer-connection-test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /test/integration/ros_coverage.py: -------------------------------------------------------------------------------- 1 | import contextlib 2 | import os 3 | import shutil 4 | import sys 5 | 6 | import rostest 7 | 8 | 9 | @contextlib.contextmanager 10 | def ros_coverage(): 11 | """ 12 | https://github.com/ros/ros_comm/issues/558 13 | """ 14 | coverage_mode = '--cov' in sys.argv 15 | if coverage_mode: 16 | sys.argv.remove('--cov') 17 | src = os.path.join(os.path.dirname(os.path.abspath(__file__)), '.coveragerc') 18 | dst = os.path.join(os.getcwd(), '.coveragerc') 19 | if not os.path.exists(dst): 20 | shutil.copyfile(src, dst) 21 | rostest._start_coverage(['ros_webrtc']) 22 | try: 23 | yield 24 | finally: 25 | if coverage_mode: 26 | rostest._stop_coverage(['ros_webrtc']) 27 | -------------------------------------------------------------------------------- /test/integration/site-call-test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /test/integration/site-wait-test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /test/provision/ansible.cfg: -------------------------------------------------------------------------------- 1 | [defaults] 2 | roles_path = ./roles 3 | -------------------------------------------------------------------------------- /test/provision/dev.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - hosts: all 4 | vars: 5 | chromedriver_version: '2.20' 6 | 7 | ros_webrtc_src_dir: "{{ playbook_dir }}/../../" 8 | 9 | webrtc_version: 555cfe9 10 | webrtc_install_bin: yes 11 | webrtc_install_dev: yes 12 | webrtc_install_dbg: yes 13 | webrtc_install_src: no 14 | 15 | roles: 16 | - {role: chrome, become: yes} 17 | - {role: chrome-driver, become: yes} 18 | - nodejs 19 | - {role: webrtc, become: yes} 20 | - {role: ros, become: yes} 21 | - ros-webrtc 22 | -------------------------------------------------------------------------------- /test/provision/inventories/local: -------------------------------------------------------------------------------- 1 | localhost ansible_connection=local 2 | -------------------------------------------------------------------------------- /test/provision/requirements.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - src: laggyluke.nodejs 4 | version: v0.4.0 5 | name: nodejs 6 | 7 | - src: jalessio.ROS 8 | name: ros 9 | 10 | - src: https://github.com/cmprescott/ansible-role-chrome 11 | version: 0ddd8ad7c6f27c729537de0ab388194a4be22c3b 12 | name: chrome 13 | 14 | - src: https://github.com/DrTom/ansible-role-chromedriver.git 15 | name: chrome-driver 16 | -------------------------------------------------------------------------------- /test/provision/roles/.gitignore: -------------------------------------------------------------------------------- 1 | /chrome/ 2 | /chrome-driver/ 3 | /nodejs/ 4 | /ros/ 5 | -------------------------------------------------------------------------------- /test/provision/roles/base/defaults/main.yml: -------------------------------------------------------------------------------- 1 | --- 2 | -------------------------------------------------------------------------------- /test/provision/roles/base/files/etc/profile.d/bash_aliases.sh: -------------------------------------------------------------------------------- 1 | alias ..="cd .." 2 | alias ...="cd ../.." 3 | alias ....="cd ../../.." 4 | alias .....="cd ../../../.." 5 | -------------------------------------------------------------------------------- /test/provision/roles/base/files/etc/profile.d/bashrc.sh: -------------------------------------------------------------------------------- 1 | shopt -s globstar 2 | -------------------------------------------------------------------------------- /test/provision/roles/base/files/etc/resolvconf/resolv.conf.d/base: -------------------------------------------------------------------------------- 1 | nameserver 8.8.8.8 2 | nameserver 8.8.4.4 3 | -------------------------------------------------------------------------------- /test/provision/roles/base/files/etc/rosdep/ros_webrtc.yaml: -------------------------------------------------------------------------------- 1 | libjingle555cfe9-dev: 2 | ubuntu: [libjingle555cfe9-dev] 3 | -------------------------------------------------------------------------------- /test/provision/roles/base/files/etc/rosdep/sources.list.d/30-ros_webrtc.list: -------------------------------------------------------------------------------- 1 | yaml file:///etc/ros/rosdep/ros_webrtc.yaml 2 | -------------------------------------------------------------------------------- /test/provision/roles/base/tasks/deps.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - name: update apt cache 4 | apt: update_cache=yes cache_valid_time=3600 5 | become: yes 6 | tags: [tools] 7 | 8 | - name: install tools via apt 9 | apt: name={{ item }} state=present 10 | with_items: 11 | - vim 12 | - htop 13 | - tmux 14 | - build-essential 15 | - git 16 | - wget 17 | - zip 18 | - curl 19 | - pkg-config 20 | - iftop 21 | - python2.7-dev 22 | - lcov 23 | - libssl-dev 24 | tags: [tools] 25 | become: yes 26 | 27 | - name: use vim as editor 28 | alternatives: name=editor path=/usr/bin/vim.basic 29 | tags: [tools] 30 | become: yes 31 | 32 | - name: install pip 33 | shell: "curl https://bootstrap.pypa.io/get-pip.py | python" 34 | args: 35 | creates: /usr/local/bin/pip 36 | become: yes 37 | 38 | - name: install python modules needed for SSL SNI 39 | pip: name={{ item }} state=latest 40 | with_items: 41 | - urllib3 42 | - pyopenssl 43 | - ndg-httpsclient 44 | - pyasn1 45 | tags: [tools] 46 | become: yes 47 | -------------------------------------------------------------------------------- /test/provision/roles/base/tasks/main.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - include: network.yml 4 | tags: [base, network] 5 | 6 | - include: swap.yml 7 | tags: [base, swap] 8 | 9 | - include: deps.yml 10 | tags: [base, deps] 11 | 12 | - include: users.yml 13 | tags: [base, users] 14 | -------------------------------------------------------------------------------- /test/provision/roles/base/tasks/network.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - name: copy resolvconf 4 | copy: 5 | src: etc/resolvconf/resolv.conf.d/base 6 | dest: /etc/resolvconf/resolv.conf.d/base 7 | owner: root 8 | group: root 9 | mode: 0644 10 | tags: [dns] 11 | register: resolvconf 12 | become: yes 13 | 14 | - name: update resolvconf 15 | command: /sbin/resolvconf -u 16 | become: yes 17 | when: resolvconf|changed 18 | -------------------------------------------------------------------------------- /test/provision/roles/base/tasks/swap.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - name: create swap 4 | command: dd if=/dev/zero of=/swap bs=1M count=1024 5 | when: ansible_swaptotal_mb < 1 6 | become: yes 7 | 8 | - name: make swap 9 | command: mkswap /swap 10 | when: ansible_swaptotal_mb < 1 11 | become: yes 12 | 13 | - name: fstab swap 14 | action: lineinfile dest=/etc/fstab regexp="/swap" line="/swap none swap sw 0 0" state=present 15 | when: ansible_swaptotal_mb < 1 16 | become: yes 17 | 18 | - name: turn on swap 19 | command: swapon -a 20 | when: ansible_swaptotal_mb < 1 21 | become: yes 22 | 23 | - name: enable swapiness 24 | sysctl: name=vm.swappiness value="1" 25 | become: yes 26 | -------------------------------------------------------------------------------- /test/provision/roles/base/tasks/users.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - name: bashrc 4 | copy: 5 | src: etc/profile.d/bashrc.sh 6 | dest: /etc/profile.d/bashrc.sh 7 | owner: root 8 | group: root 9 | mode: 0755 10 | become: yes 11 | 12 | - name: bash aliases 13 | copy: 14 | src: etc/profile.d/bash_aliases.sh 15 | dest: /etc/profile.d/bash_aliases.sh 16 | owner: root 17 | group: root 18 | mode: 0755 19 | become: yes 20 | -------------------------------------------------------------------------------- /test/provision/roles/ros-webrtc/defaults/main.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | ros_webrtc_workspace_dir: ~/tmp/ros-webrtc-ws 4 | #ros_webrtc_src_dir: ~/code/ros-webrtc 5 | 6 | ros_webrtc_build_type: Debug 7 | ros_webrtc_coverage: "ON" 8 | -------------------------------------------------------------------------------- /test/provision/roles/ros-webrtc/files/etc/ros/rosdep/ros_webrtc.yaml: -------------------------------------------------------------------------------- 1 | libjingle555cfe9-dev: 2 | ubuntu: [libjingle555cfe9-dev] 3 | -------------------------------------------------------------------------------- /test/provision/roles/ros-webrtc/files/etc/ros/rosdep/sources.list.d/30-ros_webrtc.list: -------------------------------------------------------------------------------- 1 | yaml file:///etc/ros/rosdep/ros_webrtc.yaml 2 | -------------------------------------------------------------------------------- /test/provision/roles/ros-webrtc/tasks/deps.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - name: install apt packages 4 | apt: name={{ item }} state=present 5 | with_items: 6 | - xvfb 7 | - python-numpy 8 | - python-opencv 9 | become: yes 10 | 11 | - name: install python packages 12 | pip: name={{ item }} 13 | with_items: 14 | - ipython 15 | - ipdb 16 | # http://stackoverflow.com/a/29202163 17 | - requests[security] 18 | - ws4py 19 | - xvfbwrapper 20 | - nose 21 | - selenium 22 | - coverage 23 | become: yes 24 | 25 | - name: install global npm dependencies 26 | npm: name={{ item }} global=yes 27 | with_items: 28 | - bower 29 | - grunt-cli 30 | become: yes 31 | 32 | - name: init ros deps 33 | shell: rosdep init 34 | args: 35 | creates: /etc/ros/rosdep/sources.list.d/20-default.list 36 | become: yes 37 | 38 | - name: add rosdep names 39 | copy: > 40 | src=etc/ros/rosdep/sources.list.d/30-ros_webrtc.list 41 | dest=/etc/ros/rosdep/sources.list.d/30-ros_webrtc.list 42 | mode=0644 43 | become: yes 44 | 45 | - name: add rosdep source 46 | copy: > 47 | src=etc/ros/rosdep/ros_webrtc.yaml 48 | dest=/etc/ros/rosdep/ros_webrtc.yaml 49 | mode=0644 50 | become: yes 51 | 52 | - name: update ros deps 53 | shell: rosdep update 54 | -------------------------------------------------------------------------------- /test/provision/roles/ros-webrtc/tasks/main.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - include: deps.yml 4 | tags: [ros-webrtc, ros-webrtc-deps] 5 | 6 | - include: workspace.yml 7 | tags: [ros-webrtc, ros-webrtc-workspace] 8 | 9 | - include: test-site.yml 10 | tags: [ros-webrtc, ros-webrtc-test-site] 11 | -------------------------------------------------------------------------------- /test/provision/roles/ros-webrtc/tasks/test-site.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - name: install test site npm deps 4 | shell: npm install 5 | args: 6 | executable: /bin/bash 7 | chdir: "{{ ros_webrtc_src_dir }}/test/fixtures/site" 8 | 9 | - name: install test site bower deps 10 | shell: bower install 11 | args: 12 | executable: /bin/bash 13 | chdir: "{{ ros_webrtc_src_dir }}/test/fixtures/site" 14 | 15 | - name: build test site 16 | shell: grunt clean build 17 | args: 18 | executable: /bin/bash 19 | chdir: "{{ ros_webrtc_src_dir }}/test/fixtures/site" 20 | -------------------------------------------------------------------------------- /test/provision/roles/ros-webrtc/tasks/workspace.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - name: create catkin workspace dirs 4 | file: path="{{ item }}" state=directory recurse=yes mode=0755 5 | with_items: 6 | - "{{ ros_webrtc_workspace_dir }}/src" 7 | 8 | - name: init catkin workspace 9 | shell: "source /opt/ros/{{ ros_release }}/setup.bash && catkin_init_workspace" 10 | args: 11 | executable: /bin/bash 12 | chdir: "{{ ros_webrtc_workspace_dir }}/src" 13 | creates: "{{ ros_webrtc_workspace_dir }}/src/CMakeLists.txt" 14 | 15 | - name: init catkin workspace 16 | shell: "source /opt/ros/{{ ros_release }}/setup.bash && catkin_make" 17 | args: 18 | executable: /bin/bash 19 | chdir: "{{ ros_webrtc_workspace_dir }}" 20 | creates: "{{ ros_webrtc_workspace_dir }}/devel/setup.bash" 21 | 22 | - name: symlink src 23 | file: src="{{ ros_webrtc_src_dir }}" dest="{{ ros_webrtc_workspace_dir }}/src/ros_webrtc" state=link 24 | 25 | - name: install ros deps 26 | shell: "rosdep install -y --from-paths {{ ros_webrtc_workspace_dir }}/src --ignore-src --rosdistro={{ ros_release }}" 27 | 28 | - name: build workspace 29 | shell: "source {{ ros_webrtc_workspace_dir }}/devel/setup.bash && catkin_make -DCMAKE_BUILD_TYPE={{ ros_webrtc_build_type }} -DCOVERAGE={{ ros_webrtc_coverage }}" 30 | args: 31 | executable: /bin/bash 32 | chdir: "{{ ros_webrtc_workspace_dir }}" 33 | -------------------------------------------------------------------------------- /test/provision/roles/webrtc/defaults/main.yml: -------------------------------------------------------------------------------- 1 | --- 2 | jingle_apt_repo: "http://apt-tm8ji0.c2x.io" 3 | jingle_apt_key: "http://apt-tm8ji0.c2x.io/D613DCD5.asc" 4 | -------------------------------------------------------------------------------- /test/provision/roles/webrtc/tasks/main.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | # setup repo for debs from 3rd parties 4 | - apt_key: 5 | url: "{{ jingle_apt_key }}" 6 | state: present 7 | 8 | - name: add 3rd party deb repo 9 | apt_repository: 10 | repo: "deb {{ jingle_apt_repo }} trusty unstable" 11 | state: present 12 | 13 | - name: install tools via apt 14 | apt: name={{ item }} state=present 15 | with_items: 16 | - libjsoncpp0 17 | - libjsoncpp-dev 18 | - libjingle555cfe9 19 | - libjingle555cfe9-dev 20 | tags: [tools] 21 | -------------------------------------------------------------------------------- /test/provision/travis.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - hosts: all 4 | tasks: 5 | 6 | - name: install tools via apt 7 | apt: name={{ item }} state=present 8 | with_items: 9 | - lcov 10 | - libssl-dev 11 | tags: [tools] 12 | become: yes 13 | 14 | - name: install tools via pip 15 | pip: name={{ item }} state=present 16 | with_items: 17 | - coverage 18 | - urllib3 19 | - pyopenssl 20 | - ndg-httpsclient 21 | - pyasn1 22 | tags: [tools] 23 | become: yes 24 | 25 | - hosts: all 26 | vars: 27 | chromedriver_version: '2.25' 28 | 29 | ros_webrtc_src_dir: "{{ lookup('env', 'TRAVIS_CI_PATH') }}" 30 | ros_webrtc_workspace_dir: "{{ lookup('env', 'TRAVIS_WS_PATH') }}" 31 | 32 | webrtc_version: 555cfe9 33 | webrtc_install_bin: yes 34 | webrtc_install_dev: yes 35 | webrtc_install_dbg: yes 36 | webrtc_install_src: no 37 | 38 | roles: 39 | - {role: chrome, become: yes} 40 | - {role: chrome-driver, become: yes} 41 | - {role: nodejs, become: yes} 42 | - {role: webrtc, become: yes} 43 | - {role: ros, become: yes} 44 | - ros-webrtc 45 | -------------------------------------------------------------------------------- /test/provision/vagrant.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | - hosts: all 4 | vars: 5 | chromedriver_version: '2.20' 6 | 7 | ros_webrtc_src_dir: /vagrant 8 | 9 | webrtc_version: 555cfe9 10 | webrtc_install_bin: yes 11 | webrtc_install_dev: yes 12 | webrtc_install_dbg: yes 13 | webrtc_install_src: no 14 | roles: 15 | - base 16 | - {role: chrome, become: yes} 17 | - {role: chrome-driver, become: yes} 18 | - nodejs 19 | - {role: webrtc, become: yes} 20 | - {role: ros, become: yes} 21 | - ros-webrtc 22 | -------------------------------------------------------------------------------- /test/unit/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | int main(int argc, char **argv){ 4 | testing::InitGoogleTest(&argc, argv); 5 | return RUN_ALL_TESTS(); 6 | } 7 | -------------------------------------------------------------------------------- /test/unit/test_media_constraints.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include "cpp/media_constraints.h" 4 | 5 | 6 | TEST(TestSuite, testMediaConstraints) { 7 | MediaConstraints mc; 8 | 9 | // defaults to empty 10 | ASSERT_EQ(0, mc.mandatory().size()); 11 | ASSERT_EQ(0, mc.GetMandatory().size()); 12 | ASSERT_EQ(0, mc.optional().size()); 13 | ASSERT_EQ(0, mc.GetOptional().size()); 14 | 15 | // add mandatory 16 | mc.mandatory().push_back(MediaConstraints::Constraint(MediaConstraints::kMaxWidth, "1024")); 17 | mc.mandatory().push_back(MediaConstraints::Constraint(MediaConstraints::kMinWidth, "320")); 18 | ASSERT_EQ(2, mc.mandatory().size()); 19 | ASSERT_EQ(2, mc.GetMandatory().size()); 20 | ASSERT_EQ(0, mc.optional().size()); 21 | ASSERT_EQ(0, mc.GetOptional().size()); 22 | 23 | // add optional 24 | mc.optional().push_back(MediaConstraints::Constraint(MediaConstraints::kEchoCancellation, "true")); 25 | ASSERT_EQ(2, mc.mandatory().size()); 26 | ASSERT_EQ(2, mc.GetMandatory().size()); 27 | ASSERT_EQ(1, mc.optional().size()); 28 | ASSERT_EQ(1, mc.GetOptional().size()); 29 | 30 | // duplicate optional 31 | mc.optional().push_back(MediaConstraints::Constraint(MediaConstraints::kEchoCancellation, "false")); 32 | ASSERT_EQ(2, mc.mandatory().size()); 33 | ASSERT_EQ(2, mc.GetMandatory().size()); 34 | ASSERT_EQ(2, mc.optional().size()); 35 | ASSERT_EQ(2, mc.GetOptional().size()); 36 | 37 | std::string value; 38 | ASSERT_TRUE(mc.optional().FindFirst(MediaConstraints::kEchoCancellation, &value)); 39 | ASSERT_EQ("true", value); 40 | } 41 | 42 | -------------------------------------------------------------------------------- /test/unit/test_media_type.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include "cpp/media_type.h" 4 | 5 | 6 | TEST(TestSuite, testMediaType) { 7 | MediaType mt; 8 | 9 | mt = MediaType("application/json"); 10 | ASSERT_EQ("application", mt.type); 11 | ASSERT_FALSE(mt.has_tree()); 12 | ASSERT_EQ("json", mt.sub_type); 13 | ASSERT_FALSE(mt.has_suffix()); 14 | ASSERT_EQ(0, mt.params.size()); 15 | 16 | mt = MediaType("application/vnd.mayfield.msg.v1+json"); 17 | ASSERT_EQ("application", mt.type); 18 | ASSERT_TRUE(mt.has_tree()); 19 | ASSERT_EQ("vnd", mt.tree); 20 | ASSERT_EQ("mayfield.msg.v1", mt.sub_type); 21 | ASSERT_EQ("json", mt.suffix); 22 | ASSERT_EQ(0, mt.params.size()); 23 | 24 | mt = MediaType("application/vnd.mayfield.msg-chunk-v1+json; chunksize=128"); 25 | ASSERT_EQ("application", mt.type); 26 | ASSERT_TRUE(mt.has_tree()); 27 | ASSERT_EQ("vnd", mt.tree); 28 | ASSERT_EQ("mayfield.msg-chunk-v1", mt.sub_type); 29 | ASSERT_EQ("json", mt.suffix); 30 | ASSERT_EQ(1, mt.params.size()); 31 | ASSERT_EQ("128", mt.params["chunksize"]); 32 | 33 | mt = MediaType("application/vnd.mayfield.msg-chunk-v1+json; chunksize=\"256\""); 34 | ASSERT_EQ("application", mt.type); 35 | ASSERT_TRUE(mt.has_tree()); 36 | ASSERT_EQ("vnd", mt.tree); 37 | ASSERT_EQ("mayfield.msg-chunk-v1", mt.sub_type); 38 | ASSERT_EQ("json", mt.suffix); 39 | ASSERT_EQ(1, mt.params.size()); 40 | ASSERT_EQ("256", mt.params["chunksize"]); 41 | 42 | mt = MediaType("application/vnd.mayfield-msg-chunk.v1+json; chunksize=32"); 43 | ASSERT_EQ("application", mt.type); 44 | ASSERT_TRUE(mt.has_tree()); 45 | ASSERT_EQ("vnd", mt.tree); 46 | ASSERT_EQ("mayfield-msg-chunk.v1", mt.sub_type); 47 | ASSERT_EQ("json", mt.suffix); 48 | ASSERT_EQ(1, mt.params.size()); 49 | ASSERT_EQ("32", mt.params["chunksize"]); 50 | } 51 | --------------------------------------------------------------------------------