├── .angular-cli.json ├── .editorconfig ├── .gitignore ├── LICENSE ├── README.md ├── Vagrantfile ├── package-lock.json ├── package.json ├── ros_test_project ├── CMakeLists.txt ├── launch │ └── main.launch ├── package.xml └── scripts │ ├── node_geometry_msgs.py │ ├── node_sensor_msgs.py │ ├── node_std_msgs.py │ └── node_std_srvs.py ├── src ├── app │ ├── app-routing.module.ts │ ├── app.component.html │ ├── app.component.ts │ ├── app.d.ts │ ├── app.module.ts │ ├── dashboard │ │ ├── dashboard.component.css │ │ ├── dashboard.component.html │ │ └── dashboard.component.ts │ ├── humanize.pipe.spec.ts │ ├── humanize.pipe.ts │ ├── parameter │ │ ├── parameter.component.css │ │ ├── parameter.component.html │ │ └── parameter.component.ts │ ├── service │ │ ├── service.component.css │ │ ├── service.component.html │ │ └── service.component.ts │ ├── settings │ │ ├── setting.ts │ │ ├── settings.component.css │ │ ├── settings.component.html │ │ └── settings.component.ts │ ├── topic │ │ ├── topic.component.css │ │ ├── topic.component.html │ │ └── topic.component.ts │ └── type │ │ ├── type.component.css │ │ ├── type.component.html │ │ ├── type.component.spec.ts │ │ └── type.component.ts ├── assets │ ├── ros-logo.svg │ ├── ros.svg │ └── screenshot.png ├── environments │ ├── environment.prod.ts │ └── environment.ts ├── index.html ├── main.ts ├── polyfills.ts ├── styles.css ├── tsconfig.app.json ├── tsconfig.spec.json └── typings.d.ts ├── tsconfig.json └── tslint.json /.angular-cli.json: -------------------------------------------------------------------------------- 1 | { 2 | "$schema": "./node_modules/@angular/cli/lib/config/schema.json", 3 | "project": { 4 | "name": "ros-control-center" 5 | }, 6 | "apps": [ 7 | { 8 | "baseHref": "/ros-control-center/", 9 | "root": "src", 10 | "outDir": "dist", 11 | "assets": [ 12 | "assets", 13 | "favicon.ico" 14 | ], 15 | "index": "index.html", 16 | "main": "main.ts", 17 | "polyfills": "polyfills.ts", 18 | "test": "test.ts", 19 | "tsconfig": "tsconfig.app.json", 20 | "testTsconfig": "tsconfig.spec.json", 21 | "prefix": "app", 22 | "styles": [ 23 | "styles.css" 24 | ], 25 | "scripts": [], 26 | "environmentSource": "environments/environment.ts", 27 | "environments": { 28 | "dev": "environments/environment.ts", 29 | "prod": "environments/environment.prod.ts" 30 | } 31 | } 32 | ], 33 | "e2e": { 34 | "protractor": { 35 | "config": "./protractor.conf.js" 36 | } 37 | }, 38 | "lint": [ 39 | { 40 | "project": "src/tsconfig.app.json" 41 | }, 42 | { 43 | "project": "src/tsconfig.spec.json" 44 | }, 45 | { 46 | "project": "e2e/tsconfig.e2e.json" 47 | } 48 | ], 49 | "test": { 50 | "karma": { 51 | "config": "./karma.conf.js" 52 | } 53 | }, 54 | "defaults": { 55 | "styleExt": "css", 56 | "component": {} 57 | } 58 | } 59 | -------------------------------------------------------------------------------- /.editorconfig: -------------------------------------------------------------------------------- 1 | # Editor configuration, see http://editorconfig.org 2 | root = true 3 | 4 | [*] 5 | charset = utf-8 6 | indent_style = space 7 | indent_size = 2 8 | insert_final_newline = true 9 | trim_trailing_whitespace = true 10 | 11 | [*.md] 12 | max_line_length = off 13 | trim_trailing_whitespace = false 14 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # See http://help.github.com/ignore-files/ for more about ignoring files. 2 | 3 | # compiled output 4 | /dist 5 | /tmp 6 | /out-tsc 7 | 8 | # dependencies 9 | /node_modules 10 | 11 | # IDEs and editors 12 | /.idea 13 | .project 14 | .classpath 15 | .c9/ 16 | .settings/ 17 | *.sublime-workspace 18 | 19 | # IDE - VSCode 20 | .vscode/* 21 | !.vscode/settings.json 22 | !.vscode/tasks.json 23 | !.vscode/launch.json 24 | !.vscode/extensions.json 25 | 26 | # misc 27 | /.sass-cache 28 | /connect.lock 29 | /coverage 30 | /libpeerconnection.log 31 | npm-debug.log 32 | testem.log 33 | /typings 34 | 35 | # e2e 36 | /e2e/*.js 37 | /e2e/*.map 38 | 39 | # System Files 40 | .DS_Store 41 | Thumbs.db 42 | 43 | # Vagrant 44 | .vagrant 45 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | Copyright (c) 2016, Lars Berscheid 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 5 | 6 | 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 7 | 8 | 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 9 | 10 | 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 11 | 12 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 13 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ROS Control Center 2 | 3 | This control center is a universal tool for controlling robots running ROS. It runs in the browser using a websocket connection and `roslibjs` from [RobotWebTools](http://robotwebtools.org). 4 | 5 | [![screenshot](https://raw.githubusercontent.com/pantor/ros-control-center/master/src/assets/screenshot.png)](http://pantor.github.io/ros-control-center) 6 | 7 | In general, ROS Control Center offers an easy way to 8 | - show nodes, topics and service names. 9 | - subscribe and publish messages. 10 | - call services. 11 | - show and change parameters. 12 | 13 | Further features like a console (rosout by default) output, a battery status view, a camera stream view or an advanced mode for better usability are implemented. [Check it out!](http://pantor.github.io/ros-control-center) 14 | 15 | 16 | ## Installation 17 | 18 | On your ROS robot, the `rosbridge_suite` from [Robot Web Tools](http://robotwebtools.org) needs to run. So to use the control center with your existing project, call `roslaunch rosbridge_server rosbridge_websocket.launch` to launch the websocket server. The control center runs on any computer (in particular without ROS...) in the same network. Open the ROS Control Center at [https://pantor.github.io/ros-control-center](http://pantor.github.io/ros-control-center). In the settings tab, you need to enter the IP address and port of your robot. Open the `Control` tab and reload. 19 | 20 | 21 | ## Features 22 | 23 | You can have multiple saved settings for quick changes and several robots. 24 | 25 | ROS Control Center supports images and camera streams via the `web_video_server` package. If camera and camera info messages are published according to the `web_video_server` standards, the stream is shown with the settings. 26 | 27 | For your own custom message and service types, you can download this repository and start a server via `http-server` in the console. Then, navigate to `index.html` in a browser. You can add individual `html` templates into the `app/topics/` or `app/services/` folder. The path of your file must correspond to the ROS service or message type name. See the included ROS common messages and standard services as an examples. In your html file, you can write `AngularJS` code for additional customizing and formatting. 28 | 29 | The right sidebar shows a logger output (`rosout` by default). On the left, group names are shown. ROS topics, 30 | services and parameters can be grouped together for a better overview. This works as follows: 31 | - Every topic, service or parameter name should correspond to `/group-name/element-name` like a URL. Global parameters should have no group name and are shown below the group list on the left side. 32 | - Every element name should start with a capital letter, as they are shown in the normal view mode. All elements (including the lowercase-names from system services, topics and parameters) can be shown by enabling the `advanced` view mode. 33 | 34 | In the right bottom corner, a battery status bar can be shown; the battery topic can be adapted in the settings tab. 35 | 36 | 37 | ## Contributing 38 | 39 | For development, [Node.js](https://nodejs.org/en/) needs to be installed. Via `npm install` it will automatically download all development dependencies (from `package.json`). Type `npm start` in the terminal for a live development server. With `vagrant ssh` and `roslaunch ros_test_project main.launch`, you can start a test project in a virtual ubuntu machine. 40 | 41 | ROS Control Center depends on: 42 | - [Angular](https://www.angular.io/) as the general JavaScript and routing framework. 43 | - [Bootstrap](https://getbootstrap.com/) for design. 44 | - [roslib.js](https://github.com/RobotWebTools/roslibjs) for ROS connection. 45 | 46 | Contributions are always welcome! 47 | 48 | 49 | ## License 50 | 51 | ROS Control Center is released with a BSD license. For full terms and conditions, see the [LICENSE](https://github.com/pantor/ros-control-center/blob/master/LICENSE) file. 52 | 53 | 54 | ## Contributors 55 | 56 | See [here](https://github.com/pantor/ros-control-center/graphs/contributors) for a full list of contributors. 57 | -------------------------------------------------------------------------------- /Vagrantfile: -------------------------------------------------------------------------------- 1 | # -*- mode: ruby -*- 2 | # vi: set ft=ruby : 3 | 4 | Vagrant.configure(2) do |config| 5 | config.vm.box = "nicolov/xenial-ros" 6 | config.vm.network "forwarded_port", guest: 9090, host: 9090 7 | config.vm.synced_folder "ros_test_project", "/home/vagrant/catkin_ws/src/ros_test_project" 8 | 9 | config.vm.provision "shell", inline: <<-SHELL 10 | sudo apt-get install ros-kinetic-rosbridge-server 11 | SHELL 12 | end 13 | -------------------------------------------------------------------------------- /package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "ros-control-center", 3 | "version": "0.8.0", 4 | "description": "A universal web-based control center for ROS robots.", 5 | "repository": { 6 | "type": "git", 7 | "url": "git+https://github.com/pantor/ros-control-center.git" 8 | }, 9 | "author": "Lars Berscheid", 10 | "license": "BSD-3-Clause", 11 | "bugs": { 12 | "url": "https://github.com/pantor/ros-control-center/issues" 13 | }, 14 | "scripts": { 15 | "ng": "ng", 16 | "start": "ng serve --base-href=", 17 | "build": "ng build", 18 | "test": "ng test", 19 | "lint": "ng lint", 20 | "e2e": "ng e2e" 21 | }, 22 | "dependencies": { 23 | "@angular/animations": "^5.2.2", 24 | "@angular/common": "^5.2.2", 25 | "@angular/compiler": "^5.2.2", 26 | "@angular/compiler-cli": "^5.2.2", 27 | "@angular/core": "^5.2.2", 28 | "@angular/forms": "^5.2.2", 29 | "@angular/http": "^5.2.2", 30 | "@angular/platform-browser": "^5.2.2", 31 | "@angular/platform-browser-dynamic": "^5.2.2", 32 | "@angular/router": "^5.2.2", 33 | "bootstrap": "^4.0.0", 34 | "core-js": "^2.5.3", 35 | "roslib": "^0.20.0", 36 | "rxjs": "^5.5.6", 37 | "zone.js": "^0.8.20" 38 | }, 39 | "devDependencies": { 40 | "@angular/cli": "^1.6.6", 41 | "@angular/language-service": "^5.2.2", 42 | "@types/jasmine": "^2.8.6", 43 | "@types/node": "^8.5.9", 44 | "codelyzer": "~4.0.2", 45 | "jasmine-core": "^2.9.1", 46 | "jasmine-spec-reporter": "^4.2.1", 47 | "karma": "^2.0.0", 48 | "karma-chrome-launcher": "~2.2.0", 49 | "karma-cli": "~1.0.1", 50 | "karma-coverage-istanbul-reporter": "^1.4.1", 51 | "karma-jasmine": "^1.1.1", 52 | "karma-jasmine-html-reporter": "^0.2.2", 53 | "protractor": "~5.2.2", 54 | "ts-node": "~4.1.0", 55 | "tslint": "~5.8.0", 56 | "typescript": "~2.4.2" 57 | } 58 | } 59 | -------------------------------------------------------------------------------- /ros_test_project/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(ros_test_project) 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 | rospy 9 | std_msgs 10 | ) 11 | 12 | ## System dependencies are found with CMake's conventions 13 | # find_package(Boost REQUIRED COMPONENTS system) 14 | 15 | 16 | ## Uncomment this if the package has a setup.py. This macro ensures 17 | ## modules and global scripts declared therein get installed 18 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html 19 | # catkin_python_setup() 20 | 21 | ################################################ 22 | ## Declare ROS messages, services and actions ## 23 | ################################################ 24 | 25 | ## To declare and build messages, services or actions from within this 26 | ## package, follow these steps: 27 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in 28 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). 29 | ## * In the file package.xml: 30 | ## * add a build_depend tag for "message_generation" 31 | ## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET 32 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in 33 | ## but can be declared for certainty nonetheless: 34 | ## * add a run_depend tag for "message_runtime" 35 | ## * In this file (CMakeLists.txt): 36 | ## * add "message_generation" and every package in MSG_DEP_SET to 37 | ## find_package(catkin REQUIRED COMPONENTS ...) 38 | ## * add "message_runtime" and every package in MSG_DEP_SET to 39 | ## catkin_package(CATKIN_DEPENDS ...) 40 | ## * uncomment the add_*_files sections below as needed 41 | ## and list every .msg/.srv/.action file to be processed 42 | ## * uncomment the generate_messages entry below 43 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) 44 | 45 | ## Generate messages in the 'msg' folder 46 | # add_message_files( 47 | # FILES 48 | # Message1.msg 49 | # Message2.msg 50 | # ) 51 | 52 | ## Generate services in the 'srv' folder 53 | # add_service_files( 54 | # FILES 55 | # Service1.srv 56 | # Service2.srv 57 | # ) 58 | 59 | ## Generate actions in the 'action' folder 60 | # add_action_files( 61 | # FILES 62 | # Action1.action 63 | # Action2.action 64 | # ) 65 | 66 | ## Generate added messages and services with any dependencies listed here 67 | # generate_messages( 68 | # DEPENDENCIES 69 | # std_msgs 70 | # ) 71 | 72 | ################################################ 73 | ## Declare ROS dynamic reconfigure parameters ## 74 | ################################################ 75 | 76 | ## To declare and build dynamic reconfigure parameters within this 77 | ## package, follow these steps: 78 | ## * In the file package.xml: 79 | ## * add a build_depend and a run_depend tag for "dynamic_reconfigure" 80 | ## * In this file (CMakeLists.txt): 81 | ## * add "dynamic_reconfigure" to 82 | ## find_package(catkin REQUIRED COMPONENTS ...) 83 | ## * uncomment the "generate_dynamic_reconfigure_options" section below 84 | ## and list every .cfg file to be processed 85 | 86 | ## Generate dynamic reconfigure parameters in the 'cfg' folder 87 | # generate_dynamic_reconfigure_options( 88 | # cfg/DynReconf1.cfg 89 | # cfg/DynReconf2.cfg 90 | # ) 91 | 92 | ################################### 93 | ## catkin specific configuration ## 94 | ################################### 95 | ## The catkin_package macro generates cmake config files for your package 96 | ## Declare things to be passed to dependent projects 97 | ## INCLUDE_DIRS: uncomment this if you package contains header files 98 | ## LIBRARIES: libraries you create in this project that dependent projects also need 99 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need 100 | ## DEPENDS: system dependencies of this project that dependent projects also need 101 | catkin_package( 102 | # INCLUDE_DIRS include 103 | # LIBRARIES ros_test_project 104 | # CATKIN_DEPENDS rospy std_msgs 105 | # DEPENDS system_lib 106 | ) 107 | 108 | ########### 109 | ## Build ## 110 | ########### 111 | 112 | ## Specify additional locations of header files 113 | ## Your package locations should be listed before other locations 114 | # include_directories(include) 115 | include_directories( 116 | ${catkin_INCLUDE_DIRS} 117 | ) 118 | 119 | ## Declare a C++ library 120 | # add_library(ros_test_project 121 | # src/${PROJECT_NAME}/ros_test_project.cpp 122 | # ) 123 | 124 | ## Add cmake target dependencies of the library 125 | ## as an example, code may need to be generated before libraries 126 | ## either from message generation or dynamic reconfigure 127 | # add_dependencies(ros_test_project ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 128 | 129 | ## Declare a C++ executable 130 | # add_executable(ros_test_project_node src/ros_test_project_node.cpp) 131 | 132 | ## Add cmake target dependencies of the executable 133 | ## same as for the library above 134 | # add_dependencies(ros_test_project_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 135 | 136 | ## Specify libraries to link a library or executable target against 137 | # target_link_libraries(ros_test_project_node 138 | # ${catkin_LIBRARIES} 139 | # ) 140 | 141 | ############# 142 | ## Install ## 143 | ############# 144 | 145 | # all install targets should use catkin DESTINATION variables 146 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html 147 | 148 | ## Mark executable scripts (Python etc.) for installation 149 | ## in contrast to setup.py, you can choose the destination 150 | # install(PROGRAMS 151 | # scripts/my_python_script 152 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 153 | # ) 154 | 155 | ## Mark executables and/or libraries for installation 156 | # install(TARGETS ros_test_project ros_test_project_node 157 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 158 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 159 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 160 | # ) 161 | 162 | ## Mark cpp header files for installation 163 | # install(DIRECTORY include/${PROJECT_NAME}/ 164 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 165 | # FILES_MATCHING PATTERN "*.h" 166 | # PATTERN ".svn" EXCLUDE 167 | # ) 168 | 169 | ## Mark other files for installation (e.g. launch and bag files, etc.) 170 | # install(FILES 171 | # # myfile1 172 | # # myfile2 173 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 174 | # ) 175 | 176 | ############# 177 | ## Testing ## 178 | ############# 179 | 180 | ## Add gtest based cpp test target and link libraries 181 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_ros_test_project.cpp) 182 | # if(TARGET ${PROJECT_NAME}-test) 183 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) 184 | # endif() 185 | 186 | ## Add folders to be run by python nosetests 187 | # catkin_add_nosetests(test) 188 | -------------------------------------------------------------------------------- /ros_test_project/launch/main.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /ros_test_project/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ros_test_project 4 | 0.0.0 5 | The ros_test_project package 6 | 7 | 8 | 9 | 10 | vagrant 11 | 12 | 13 | 14 | 15 | 16 | TODO 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 | catkin 43 | rospy 44 | std_msgs 45 | rospy 46 | std_msgs 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | -------------------------------------------------------------------------------- /ros_test_project/scripts/node_geometry_msgs.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python 2 | 3 | import random as rd 4 | import rospy 5 | 6 | from geometry_msgs.msg import * 7 | 8 | 9 | if __name__ == '__main__': 10 | rospy.init_node('geometry_msgs') 11 | pub_accel = rospy.Publisher('Accel', Accel, queue_size=10) 12 | pub_accel_stamped = rospy.Publisher('AccelStamped', AccelStamped, queue_size=10) 13 | pub_accel_cov = rospy.Publisher('AccelWithCovariance', AccelWithCovariance, queue_size=10) 14 | pub_accel_cov_stamped = rospy.Publisher('AccelWithCovarianceStamped', AccelWithCovarianceStamped, queue_size=10) 15 | pub_inertia = rospy.Publisher('Inertia', Inertia, queue_size=10) 16 | pub_point = rospy.Publisher('Point', Point, queue_size=10) 17 | pub_point32 = rospy.Publisher('Point32', Point32, queue_size=10) 18 | pub_point_stamped = rospy.Publisher('PointStamped', PointStamped, queue_size=10) 19 | pub_polygon = rospy.Publisher('Polygon', Polygon, queue_size=10) 20 | pub_pose = rospy.Publisher('Pose', Pose, queue_size=10) 21 | pub_pose2d = rospy.Publisher('Pose2D', Pose2D, queue_size=10) 22 | pub_pose_array = rospy.Publisher('PoseArray', PoseArray, queue_size=10) 23 | pub_pose_stamped = rospy.Publisher('PoseStamped', Pose, queue_size=10) 24 | pub_quaternion = rospy.Publisher('Quaternion', Quaternion, queue_size=10) 25 | pub_quaternion_stamped = rospy.Publisher('QuaternionStamped', QuaternionStamped, queue_size=10) 26 | pub_transform = rospy.Publisher('Transform', Transform, queue_size=10) 27 | pub_twist = rospy.Publisher('Twist', Twist, queue_size=10) 28 | pub_vector3 = rospy.Publisher('Vector3', Vector3, queue_size=10) 29 | pub_vector3_stamped = rospy.Publisher('Vector3Stamped', Vector3Stamped, queue_size=10) 30 | pub_wrench = rospy.Publisher('Wrench', Wrench, queue_size=10) 31 | pub_wrench_stamped = rospy.Publisher('WrenchStamped', WrenchStamped, queue_size=10) 32 | 33 | r = rospy.Rate(2) # [Hz] 34 | 35 | while not rospy.is_shutdown(): 36 | 37 | msg = Point(x=rd.uniform(-10, 10), y=rd.uniform(-10, 10), z=rd.uniform(-10, 10)) 38 | pub_point.publish(msg) 39 | 40 | r.sleep() 41 | -------------------------------------------------------------------------------- /ros_test_project/scripts/node_sensor_msgs.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python 2 | 3 | import random as rd 4 | import rospy 5 | 6 | from sensor_msgs.msg import * 7 | 8 | 9 | if __name__ == '__main__': 10 | rospy.init_node('sensor_msgs') 11 | pub_battery_state = rospy.Publisher('BatteryState', BatteryState, queue_size=10) 12 | pub_camera_info = rospy.Publisher('CameraInfo', CameraInfo, queue_size=10) 13 | pub_compressed_image = rospy.Publisher('CompressedImage', CameraInfo, queue_size=10) 14 | pub_fluid_pressure = rospy.Publisher('FluidPressure', CameraInfo, queue_size=10) 15 | pub_illuminance = rospy.Publisher('Illuminance', Illuminance, queue_size=10) 16 | pub_image = rospy.Publisher('Image', Image, queue_size=10) 17 | pub_imu = rospy.Publisher('Imu', Imu, queue_size=10) 18 | pub_joint_state = rospy.Publisher('JointState', JointState, queue_size=10) 19 | pub_joy = rospy.Publisher('Joy', Joy, queue_size=10) 20 | pub_joy_feedback = rospy.Publisher('JoyFeedback', JoyFeedback, queue_size=10) 21 | pub_magnetic_field = rospy.Publisher('MagneticField', MagneticField, queue_size=10) 22 | pub_nav_sat_fix = rospy.Publisher('NavSatFix', NavSatFix, queue_size=10) 23 | pub_nav_sat_status = rospy.Publisher('NavSatStatus', NavSatStatus, queue_size=10) 24 | pub_point_cloud = rospy.Publisher('PointCloud', PointCloud, queue_size=10) 25 | pub_range = rospy.Publisher('Range', Range, queue_size=10) 26 | pub_region_of_interest = rospy.Publisher('RegionOfInterest', RegionOfInterest, queue_size=10) 27 | pub_relative_humidity = rospy.Publisher('RelativeHumidity', RelativeHumidity, queue_size=10) 28 | pub_temperature = rospy.Publisher('Temperature', Temperature, queue_size=10) 29 | pub_time_reference = rospy.Publisher('TimeReference', TimeReference, queue_size=10) 30 | 31 | r = rospy.Rate(2) # [Hz] 32 | 33 | while not rospy.is_shutdown(): 34 | 35 | msg = Imu() 36 | msg.linear_acceleration.x = rd.uniform(0.8, 1.2) 37 | msg.linear_acceleration.y = rd.uniform(0.2, 0.5) 38 | msg.linear_acceleration.z = rd.uniform(0.1, 0.4) 39 | pub_imu.publish(msg) 40 | 41 | r.sleep() 42 | -------------------------------------------------------------------------------- /ros_test_project/scripts/node_std_msgs.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python 2 | 3 | import random as rd 4 | import rospy 5 | 6 | from std_msgs.msg import * 7 | 8 | 9 | if __name__ == '__main__': 10 | rospy.init_node('std_msgs') 11 | pub_bool = rospy.Publisher('Bool', Bool, queue_size=10) 12 | pub_colorrgba = rospy.Publisher('ColorRGBA', ColorRGBA, queue_size=10) 13 | pub_duration = rospy.Publisher('Duration', Duration, queue_size=10) 14 | pub_empty = rospy.Publisher('Empty', Empty, queue_size=10) 15 | pub_float32 = rospy.Publisher('Float32', Float32, queue_size=10) 16 | pub_float64 = rospy.Publisher('Float64', Float64, queue_size=10) 17 | pub_int16 = rospy.Publisher('Int16', Int16, queue_size=10) 18 | pub_int32 = rospy.Publisher('Int32', Int32, queue_size=10) 19 | pub_int64 = rospy.Publisher('Int64', Int64, queue_size=10) 20 | pub_int8 = rospy.Publisher('Int8', Int8, queue_size=10) 21 | pub_string = rospy.Publisher('String', String, queue_size=10) 22 | pub_time = rospy.Publisher('Time', Time, queue_size=10) 23 | pub_uint16 = rospy.Publisher('UInt16', UInt16, queue_size=10) 24 | pub_uint32 = rospy.Publisher('UInt32', UInt32, queue_size=10) 25 | pub_uint64 = rospy.Publisher('UInt64', UInt64, queue_size=10) 26 | pub_uint8 = rospy.Publisher('UInt8', UInt8, queue_size=10) 27 | 28 | r = rospy.Rate(2) # [Hz] 29 | 30 | while not rospy.is_shutdown(): 31 | pub_bool.publish(Bool(data=rd.choice([True, False]))) 32 | pub_colorrgba.publish(ColorRGBA(r=255, g=255, b=255, a=0)) 33 | pub_empty.publish(Empty()) 34 | pub_float32.publish(Float32(data=rd.uniform(-10.0, 10.0))) 35 | pub_float64.publish(Float64(data=rd.uniform(-10.0, 10.0))) 36 | pub_string.publish(String(data=rd.choice(['hello', 'world']))) 37 | pub_uint16.publish(UInt16(data=rd.choice([0, 1, 2]))) 38 | pub_uint32.publish(UInt32(data=rd.choice([0, 1, 2]))) 39 | pub_uint64.publish(UInt64(data=rd.choice([0, 1, 2]))) 40 | pub_uint8.publish(UInt8(data=rd.choice([0, 1, 2]))) 41 | 42 | r.sleep() 43 | -------------------------------------------------------------------------------- /ros_test_project/scripts/node_std_srvs.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/python 2 | 3 | import random as rd 4 | import rospy 5 | 6 | from std_srvs.srv import * 7 | 8 | 9 | def empty(req): 10 | return EmptyResponse() 11 | 12 | 13 | def set_bool(req): 14 | return SetBoolResponse(req.data, 'Message Text.') 15 | 16 | 17 | def trigger(req): 18 | rospy.loginfo('Triggered.') 19 | success = rd.choice([True, False]) 20 | return TriggerResponse(success, 'Message Success.' if success else 'Message Failure') 21 | 22 | 23 | if __name__ == '__main__': 24 | rospy.init_node('std_srvs') 25 | ser_empty = rospy.Service('Empty', Empty, empty) 26 | ser_set_bool = rospy.Service('SetBool', SetBool, set_bool) 27 | ser_trigger = rospy.Service('Trigger', Trigger, trigger) 28 | 29 | rospy.spin() 30 | -------------------------------------------------------------------------------- /src/app/app-routing.module.ts: -------------------------------------------------------------------------------- 1 | import { NgModule } from '@angular/core'; 2 | import { Routes, RouterModule } from '@angular/router'; 3 | 4 | import { DashboardComponent } from './dashboard/dashboard.component'; 5 | import { SettingsComponent } from './settings/settings.component'; 6 | 7 | const routes: Routes = [ 8 | { path: 'dashboard', component: DashboardComponent }, 9 | { path: 'settings', component: SettingsComponent }, 10 | { path: '**', redirectTo: '/dashboard' }, 11 | ]; 12 | 13 | @NgModule({ 14 | imports: [RouterModule.forRoot(routes)], 15 | exports: [RouterModule] 16 | }) 17 | export class AppRoutingModule { } 18 | -------------------------------------------------------------------------------- /src/app/app.component.html: -------------------------------------------------------------------------------- 1 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /src/app/app.component.ts: -------------------------------------------------------------------------------- 1 | import { Component } from '@angular/core'; 2 | 3 | @Component({ 4 | selector: 'app-root', 5 | templateUrl: './app.component.html' 6 | }) 7 | export class AppComponent { 8 | title = 'app'; 9 | } 10 | -------------------------------------------------------------------------------- /src/app/app.d.ts: -------------------------------------------------------------------------------- 1 | interface Topic { 2 | name: string; 3 | type: string; 4 | info?: any; 5 | } 6 | 7 | type Service = any; 8 | 9 | interface Parameter { 10 | name: string; 11 | value: any; 12 | node?: string; 13 | } 14 | 15 | interface Node { 16 | name: string; 17 | topics: Topic[]; 18 | services: Service[]; 19 | params: Parameter[]; 20 | 21 | publishing?: string[]; 22 | subscribing?: string[]; 23 | } 24 | 25 | interface Type { 26 | type: string; 27 | name: string; 28 | 29 | members?: Type[]; 30 | example?: any; 31 | length?: number; 32 | } 33 | -------------------------------------------------------------------------------- /src/app/app.module.ts: -------------------------------------------------------------------------------- 1 | import { BrowserModule } from '@angular/platform-browser'; 2 | import { NgModule } from '@angular/core'; 3 | import { FormsModule } from '@angular/forms'; 4 | 5 | import { AppRoutingModule } from './app-routing.module'; 6 | import { AppComponent } from './app.component'; 7 | import { DashboardComponent } from './dashboard/dashboard.component'; 8 | import { SettingsComponent } from './settings/settings.component'; 9 | import { ParameterComponent } from './parameter/parameter.component'; 10 | import { TopicComponent } from './topic/topic.component'; 11 | import { ServiceComponent } from './service/service.component'; 12 | 13 | import { HumanizePipe } from './humanize.pipe'; 14 | import { TypeComponent } from './type/type.component'; 15 | 16 | 17 | @NgModule({ 18 | declarations: [ 19 | AppComponent, 20 | DashboardComponent, 21 | SettingsComponent, 22 | ParameterComponent, 23 | TopicComponent, 24 | ServiceComponent, 25 | HumanizePipe, 26 | TypeComponent, 27 | ], 28 | entryComponents: [], 29 | imports: [ 30 | BrowserModule, 31 | FormsModule, 32 | AppRoutingModule 33 | ], 34 | providers: [], 35 | bootstrap: [AppComponent] 36 | }) 37 | export class AppModule { } 38 | -------------------------------------------------------------------------------- /src/app/dashboard/dashboard.component.css: -------------------------------------------------------------------------------- 1 | .sidebar { 2 | border-left: 1px solid #f4f5f7; 3 | 4 | overflow-x: scroll; 5 | overflow-y: auto; 6 | } 7 | .console-row { 8 | border-bottom: 1px solid #f4f5f7; 9 | } 10 | .battery { 11 | position: absolute; 12 | bottom: 0; 13 | padding: 15px 15px 0 15px; 14 | width: 100%; 15 | 16 | background-color: white; 17 | border-top: 1px solid #f4f5f7; 18 | } 19 | -------------------------------------------------------------------------------- /src/app/dashboard/dashboard.component.html: -------------------------------------------------------------------------------- 1 |
2 |
3 |
4 | Loading... 5 |
6 | 7 |
8 | There is nothing to show... In default mode, ROS Control Center does not show default nodes / parameters / services and topics. You can show every item by using the advanced view setting, either in the seperate settings tab or here: 9 | 10 |
11 | 12 | 15 |
16 | 17 |
18 |
19 |
20 |
21 |
22 |
{{ n.name | humanize }}
23 |
24 | 25 | 26 |
27 | 28 |
29 |

{{ activeNode.name | humanize }}

30 | 31 | 32 | 33 | 34 |
35 |
36 |
37 | 38 |
39 | 52 | 53 |
54 | Battery
55 | 56 |
57 |
58 |

{{ 100 * batteryStatus | number: 1 }} %

59 |
60 | 61 |
62 | 63 |
64 |
65 | 66 |

No battery data yet.

67 |
68 |
69 |
70 |
71 | -------------------------------------------------------------------------------- /src/app/dashboard/dashboard.component.ts: -------------------------------------------------------------------------------- 1 | import { Component, OnInit } from '@angular/core'; 2 | import { Observable } from 'rxjs/Observable'; 3 | 4 | declare var ROSLIB: any; 5 | import 'roslib/build/roslib.js'; 6 | import 'rxjs/add/operator/map'; 7 | import 'rxjs/add/operator/mergeMap'; 8 | import 'rxjs/add/observable/forkJoin'; 9 | 10 | import { Setting } from '../settings/setting'; 11 | 12 | 13 | export let ros; 14 | let isConnected = false; 15 | 16 | 17 | @Component({ 18 | selector: 'app-dashboard', 19 | templateUrl: './dashboard.component.html', 20 | styleUrls: ['./dashboard.component.css'], 21 | providers: [] 22 | }) 23 | export class DashboardComponent implements OnInit { 24 | data: { 25 | rosout: any[], 26 | nodes: Node[], 27 | globalParameters: Parameter[], 28 | }; 29 | activeNode: Node; 30 | isConnected: boolean; 31 | setting: Setting; 32 | maxConsoleEntries = 200; 33 | batteryStatus: any; 34 | ready = false; 35 | hasNodes = true; 36 | 37 | ngOnInit() { 38 | this.isConnected = isConnected; 39 | this.setting = Setting.getCurrent(); 40 | 41 | // Load ROS connection and keep trying if it fails 42 | this.newRosConnection(); 43 | setInterval(() => { 44 | this.newRosConnection(); 45 | }, 1000); // [ms] 46 | 47 | this.data = { 48 | rosout: [], 49 | nodes: [], 50 | globalParameters: [], 51 | }; 52 | 53 | if (isConnected) { 54 | this.onConnected(); 55 | } 56 | } 57 | 58 | // The active node shows further information in the center view 59 | setActiveNode(node: Node): void { 60 | this.activeNode = node; 61 | } 62 | 63 | newRosConnection(): void { 64 | if (isConnected) { 65 | return; 66 | } 67 | 68 | if (ros) { 69 | ros.close(); // Close old connection 70 | ros = false; 71 | return; 72 | } 73 | 74 | ros = new ROSLIB.Ros({ url: `ws://${this.setting.address}:${this.setting.port}` }); 75 | 76 | ros.on('connection', () => { 77 | this.onConnected(); 78 | isConnected = true; 79 | this.isConnected = isConnected; 80 | }); 81 | 82 | ros.on('error', () => { 83 | isConnected = false; 84 | this.isConnected = isConnected; 85 | }); 86 | 87 | ros.on('close', () => { 88 | isConnected = false; 89 | this.isConnected = isConnected; 90 | }); 91 | } 92 | 93 | onConnected(): void { 94 | this.data = { 95 | rosout: [], 96 | nodes: [], 97 | globalParameters: [], 98 | }; 99 | 100 | this.loadData(); 101 | 102 | this.setConsole(); 103 | if (this.setting.battery) { 104 | this.setBattery(); 105 | } 106 | } 107 | 108 | // Setup of console (in the right sidebar) 109 | setConsole(): void { 110 | const consoleTopic = new ROSLIB.Topic({ 111 | ros, 112 | name: this.setting.log, 113 | messageType: 'rosgraph_msgs/Log', 114 | }); 115 | consoleTopic.subscribe(message => { 116 | if (!this.setting.advanced && !this.filterString(message.name)) { 117 | return; 118 | } 119 | 120 | const nameArray = message.name.split('/'); 121 | const d = new Date((message.header.stamp.secs * 1E3) + (message.header.stamp.nsecs * 1E-6)); 122 | 123 | message.name = (nameArray.length > 1) ? nameArray[1] : message.name; 124 | 125 | // String formatting of message time and date 126 | function addZero(i) { return i < 10 ? `0${i}` : `${i}`; } 127 | message.dateString = `${addZero(d.getHours())}: 128 | ${addZero(d.getMinutes())}: 129 | ${addZero(d.getSeconds())}. 130 | ${addZero(d.getMilliseconds())}`; 131 | this.data.rosout.unshift(message); 132 | 133 | if (this.data.rosout.length > this.maxConsoleEntries) { 134 | this.data.rosout.pop(); 135 | } 136 | }); 137 | } 138 | 139 | // Setup battery status 140 | setBattery(): void { 141 | const batteryTopic = new ROSLIB.Topic({ 142 | ros, 143 | name: this.setting.batteryTopic, 144 | messageType: 'std_msgs/Float32', 145 | }); 146 | batteryTopic.subscribe(message => { 147 | this.batteryStatus = message.data; 148 | }); 149 | } 150 | 151 | 152 | parseTypedef(typedef: any): Type { 153 | const info = typedef.map(inf => ({ 154 | type: inf.type, 155 | members: inf.examples.map((e, i) => ({ 156 | example: inf.examples[i], 157 | name: inf.fieldnames[i], 158 | length: inf.fieldarraylen[i], 159 | type: inf.fieldtypes[i], 160 | })), 161 | })); 162 | 163 | function findMembers(obj) { 164 | for (const e of obj.members) { 165 | if (info.find(i => e.type === i.type)) { 166 | e.members = info.find(i => e.type === i.type).members; 167 | } 168 | if (e.members) { 169 | findMembers(e); 170 | } 171 | } 172 | } 173 | 174 | findMembers(info[0]); 175 | return info[0]; 176 | } 177 | 178 | 179 | getNodes(): Observable { 180 | return Observable.create(obs => { 181 | ros.getNodes(data => { 182 | obs.next(data); 183 | obs.complete(); 184 | }); 185 | }).flatMap(data => { 186 | return Observable.forkJoin(data.map(name => Observable.create(obs => { 187 | const detailClient = new ROSLIB.Service({ 188 | ros: ros, 189 | name: '/rosapi/node_details', 190 | serviceType: 'rosapi/NodeDetails' 191 | }); 192 | const request = new ROSLIB.ServiceRequest({ node: name }); 193 | detailClient.callService(request, data2 => { 194 | obs.next({ name, publishing: data2.publishing, subscribing: data2.subscribing, services: data2.services }); 195 | obs.complete(); 196 | }); 197 | }))); 198 | }); 199 | } 200 | 201 | getTopics(): Observable { 202 | return Observable.create(obs => { 203 | ros.getTopics(data => { 204 | obs.next(data); 205 | obs.complete(); 206 | }); 207 | }).flatMap(data => { 208 | return Observable.forkJoin(data.topics.map((name, i) => Observable.create(obs => { 209 | ros.getMessageDetails(data.types[i], typedef => { 210 | obs.next({ name, type: data.types[i], info: this.parseTypedef(typedef) }); 211 | obs.complete(); 212 | }, error => { 213 | obs.next({ name, type: data.types[i] }); 214 | obs.complete(); 215 | }); 216 | }))); 217 | }); 218 | } 219 | 220 | getServices(): Observable { 221 | return Observable.create(obs => { 222 | ros.getServices(data => { 223 | obs.next(data); 224 | obs.complete(); 225 | }); 226 | }).flatMap(data => { 227 | return Observable.forkJoin(data.map(name => Observable.create(obs => { 228 | ros.getServiceType(name, type => { 229 | obs.next({ name, type }); 230 | obs.complete(); 231 | }); 232 | }))); 233 | }).flatMap(data => { 234 | return Observable.forkJoin(data.map(data2 => Observable.create(obs => { 235 | const detailClient = new ROSLIB.Service({ 236 | ros: ros, 237 | name: '/rosapi/service_request_details', 238 | serviceType: 'rosapi/ServiceRequestDetails' 239 | }); 240 | const request = new ROSLIB.ServiceRequest({ type: data2.type }); 241 | detailClient.callService(request, data3 => { 242 | obs.next({ ...data2, request_info: this.parseTypedef(data3.typedefs) }); 243 | obs.complete(); 244 | }); 245 | }))); 246 | }).flatMap(data => { 247 | return Observable.forkJoin(data.map(data2 => Observable.create(obs => { 248 | const detailClient = new ROSLIB.Service({ 249 | ros: ros, 250 | name: '/rosapi/service_response_details', 251 | serviceType: 'rosapi/ServiceResponseDetails' 252 | }); 253 | const request = new ROSLIB.ServiceRequest({ type: data2.type }); 254 | detailClient.callService(request, data3 => { 255 | obs.next({ ...data2, response_info: this.parseTypedef(data3.typedefs) }); 256 | obs.complete(); 257 | }); 258 | }))); 259 | }) 260 | } 261 | 262 | getParams(): Observable { 263 | return Observable.create(obs => { 264 | ros.getParams(data => { 265 | obs.next(data); 266 | obs.complete(); 267 | }); 268 | }).flatMap(data => { 269 | return Observable.forkJoin(data.map(name => Observable.create(obs => { 270 | const param = new ROSLIB.Param({ ros, name }); 271 | const nameArray = name.split('/'); 272 | param.get(value => { 273 | if (nameArray.length > 2) { 274 | obs.next({ node: '/' + nameArray[1], name, value }); 275 | } else { 276 | obs.next({ name, value }); 277 | } 278 | obs.complete(); 279 | }); 280 | }))); 281 | }); 282 | } 283 | 284 | filterString(s: any): boolean { 285 | if (s.name) { 286 | s = s.name; 287 | } 288 | 289 | if ([ 290 | '/rosapi', 291 | '/rosout', 292 | '/rosbridge_websocket', 293 | '/rosversion', 294 | '/run_id', 295 | '/rosdistro', 296 | ].includes(s)) { 297 | return false; 298 | } 299 | 300 | const nameArray = s.split('/'); 301 | if ([ 302 | 'set_logger_level', 303 | 'get_loggers', 304 | ].includes(nameArray[nameArray.length - 1])) { 305 | return false; 306 | } 307 | 308 | return true; 309 | } 310 | 311 | // Load structure, all data, parameters, topics, services, nodes... 312 | loadData(): void { 313 | Observable.forkJoin(this.getNodes(), this.getTopics(), this.getServices(), this.getParams()) 314 | .subscribe(([nodes, topics, services, params]) => { 315 | 316 | if (!this.setting.advanced) { 317 | nodes = nodes.filter(this.filterString); 318 | params = params.filter(this.filterString); 319 | 320 | for (const n of nodes) { 321 | n.services = n.services.filter(this.filterString); 322 | n.publishing = n.publishing.filter(this.filterString); 323 | n.subscribing = n.subscribing.filter(this.filterString); 324 | } 325 | } 326 | 327 | this.data.nodes = nodes; 328 | this.data.globalParameters = params.filter(param => !param.node); 329 | 330 | for (const n of this.data.nodes) { 331 | n.services = n.services.map(name => services.find(e => e.name === name)); 332 | n.topics = n.publishing.concat(n.subscribing).map(name => topics.find(e => e.name === name)); 333 | n.params = params.filter(param => param.node === n.name); 334 | } 335 | 336 | this.setActiveNode(this.data.nodes[0]); 337 | this.ready = true; 338 | }); 339 | } 340 | } 341 | -------------------------------------------------------------------------------- /src/app/humanize.pipe.spec.ts: -------------------------------------------------------------------------------- 1 | import { HumanizePipe } from './humanize.pipe'; 2 | 3 | describe('HumanizePipe', () => { 4 | it('create an instance', () => { 5 | const pipe = new HumanizePipe(); 6 | expect(pipe).toBeTruthy(); 7 | }); 8 | }); 9 | -------------------------------------------------------------------------------- /src/app/humanize.pipe.ts: -------------------------------------------------------------------------------- 1 | import { Pipe, PipeTransform } from '@angular/core'; 2 | 3 | @Pipe({ 4 | name: 'humanize' 5 | }) 6 | export class HumanizePipe implements PipeTransform { 7 | transform(value: any, args?: any): any { 8 | return value.replace(/_/g, ' ').replace(/\//g, ' ').trim().split(' ').map(e => e.charAt(0).toUpperCase() + e.slice(1)).join(' '); 9 | } 10 | } 11 | -------------------------------------------------------------------------------- /src/app/parameter/parameter.component.css: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/pantor/ros-control-center/dc853cd61f7a599ad19bcf5166b7ff8be92fe216/src/app/parameter/parameter.component.css -------------------------------------------------------------------------------- /src/app/parameter/parameter.component.html: -------------------------------------------------------------------------------- 1 |
2 |
{{ parameter.name | humanize }}
3 | 4 |
5 |
6 |
7 | 8 |
9 | 10 | 11 |
12 |
13 |
14 | -------------------------------------------------------------------------------- /src/app/parameter/parameter.component.ts: -------------------------------------------------------------------------------- 1 | import { Component, OnInit, Input } from '@angular/core'; 2 | 3 | declare var ROSLIB: any; 4 | import 'roslib/build/roslib.js'; 5 | 6 | import { ros } from '../dashboard/dashboard.component'; 7 | 8 | 9 | @Component({ 10 | selector: 'app-parameter', 11 | templateUrl: './parameter.component.html', 12 | styleUrls: ['./parameter.component.css'] 13 | }) 14 | export class ParameterComponent implements OnInit { 15 | @Input() parameter: Parameter; 16 | private roslibParam: any; 17 | 18 | ngOnInit() { 19 | this.roslibParam = new ROSLIB.Param({ ros, name: this.parameter.name }); 20 | } 21 | 22 | setValue(): void { 23 | this.roslibParam.set(this.parameter.value); 24 | } 25 | } 26 | -------------------------------------------------------------------------------- /src/app/service/service.component.css: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/pantor/ros-control-center/dc853cd61f7a599ad19bcf5166b7ff8be92fe216/src/app/service/service.component.css -------------------------------------------------------------------------------- /src/app/service/service.component.html: -------------------------------------------------------------------------------- 1 |
2 |
3 | {{ service.name | humanize }} 4 | ({{ service.type }} / Default) 5 |
6 | 7 |
8 |
9 | 10 | 11 | 12 |
13 | 14 |
15 |
16 | 17 |
18 |
19 |
20 | -------------------------------------------------------------------------------- /src/app/service/service.component.ts: -------------------------------------------------------------------------------- 1 | import { Component, ViewChild, OnInit, Input } from '@angular/core'; 2 | 3 | declare var ROSLIB: any; 4 | import 'roslib/build/roslib.js'; 5 | 6 | import { ros } from '../dashboard/dashboard.component'; 7 | import { TypeComponent } from '../type/type.component'; 8 | 9 | 10 | @Component({ 11 | selector: 'app-service', 12 | templateUrl: './service.component.html', 13 | styleUrls: ['./service.component.css'] 14 | }) 15 | export class ServiceComponent implements OnInit { 16 | @ViewChild(TypeComponent) child: TypeComponent; 17 | 18 | @Input() service: Service; 19 | private roslibService: any; 20 | public input = {}; 21 | public response: any; 22 | 23 | ngOnInit() { 24 | this.roslibService = new ROSLIB.Service({ 25 | ros, 26 | name: this.service.name, 27 | serviceType: this.service.type, 28 | }); 29 | } 30 | 31 | callService(): void { 32 | const request = new ROSLIB.ServiceRequest(this.child.data); 33 | this.roslibService.callService(request, response => { 34 | this.response = response; 35 | }); 36 | } 37 | } 38 | -------------------------------------------------------------------------------- /src/app/settings/setting.ts: -------------------------------------------------------------------------------- 1 | export class Setting { 2 | name: string; 3 | address: string; 4 | port: number; 5 | log: string; 6 | imagePreview: { port: number, quality: number, width: number, height: number }; 7 | battery: boolean; 8 | batteryTopic: string; 9 | advanced: boolean; 10 | 11 | static getDefault(): Setting { 12 | return { 13 | name: 'Robot Name', 14 | address: '127.0.0.1', // use localhost 15 | port: 9090, // default port of rosbridge_server 16 | log: '/rosout', 17 | imagePreview: { port: 0, quality: 70, width: 640, height: 480 }, 18 | battery: false, 19 | batteryTopic: '', 20 | advanced: false, 21 | }; 22 | } 23 | 24 | static getCurrent(): Setting { 25 | const settings = JSON.parse(localStorage.getItem('roscc2-settings')) || [ Setting.getDefault() ]; 26 | const index = JSON.parse(localStorage.getItem('roscc2-index')) || 0; 27 | 28 | return settings[index]; 29 | } 30 | } 31 | -------------------------------------------------------------------------------- /src/app/settings/settings.component.css: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/pantor/ros-control-center/dc853cd61f7a599ad19bcf5166b7ff8be92fe216/src/app/settings/settings.component.css -------------------------------------------------------------------------------- /src/app/settings/settings.component.html: -------------------------------------------------------------------------------- 1 |
2 |
3 | 6 | 7 | 8 | 9 |
10 | 11 |
12 | 13 |
14 |
15 | 16 |
17 | 18 |
19 |
20 |
21 | 22 |
23 | 24 | Please reload after URL change 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 | 69 |
70 |
71 |
72 | 73 |
74 | 75 |
76 | 77 | The message type should be std_msgs/Float32. 78 |
79 |
80 |
81 | 82 |
83 | 84 |
85 |
86 |
87 |
88 |
89 | 93 |
94 |
95 |
96 |
97 |
98 | -------------------------------------------------------------------------------- /src/app/settings/settings.component.ts: -------------------------------------------------------------------------------- 1 | import { Component, OnInit } from '@angular/core'; 2 | 3 | import { Setting } from './setting'; 4 | 5 | 6 | @Component({ 7 | selector: 'app-settings', 8 | templateUrl: './settings.component.html', 9 | styleUrls: ['./settings.component.css'] 10 | }) 11 | export class SettingsComponent implements OnInit { 12 | settings: Setting[]; 13 | index: number; 14 | private storageSettingsName = 'roscc2-settings'; 15 | private storageIndexName = 'roscc2-index'; 16 | 17 | ngOnInit() { 18 | this.settings = JSON.parse(localStorage.getItem(this.storageSettingsName)) || [ Setting.getDefault() ]; 19 | this.index = JSON.parse(localStorage.getItem(this.storageIndexName)) || 0; 20 | } 21 | 22 | save(): void { 23 | localStorage.setItem(this.storageSettingsName, JSON.stringify(this.settings)); 24 | localStorage.setItem(this.storageIndexName, JSON.stringify(this.index)); 25 | } 26 | 27 | add(): void { 28 | this.settings.push( Setting.getDefault() ); // Clone object 29 | this.index = this.settings.length - 1; 30 | this.save(); 31 | } 32 | 33 | remove(): void { 34 | this.settings.splice(this.index, 1); 35 | this.index = 0; 36 | 37 | if (!this.settings.length) { 38 | this.add(); 39 | } 40 | this.save(); 41 | } 42 | } 43 | -------------------------------------------------------------------------------- /src/app/topic/topic.component.css: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/pantor/ros-control-center/dc853cd61f7a599ad19bcf5166b7ff8be92fe216/src/app/topic/topic.component.css -------------------------------------------------------------------------------- /src/app/topic/topic.component.html: -------------------------------------------------------------------------------- 1 |
2 |
3 |
4 | {{ topic.name | humanize }} 5 | ({{ topic.type }}) 6 |
7 | 8 | 9 |
10 | 11 |
12 |
13 | 14 | 15 | 16 |
17 |
18 |
19 | -------------------------------------------------------------------------------- /src/app/topic/topic.component.ts: -------------------------------------------------------------------------------- 1 | import { Component, OnInit, Input } from '@angular/core'; 2 | 3 | declare var ROSLIB: any; 4 | import 'roslib/build/roslib.js'; 5 | 6 | import { ros } from '../dashboard/dashboard.component'; 7 | 8 | 9 | @Component({ 10 | selector: 'app-topic', 11 | templateUrl: './topic.component.html', 12 | styleUrls: ['./topic.component.css'] 13 | }) 14 | export class TopicComponent implements OnInit { 15 | @Input() topic: Topic; 16 | private roslibTopic: any; 17 | public input = {}; 18 | public isSubscribing = false; 19 | 20 | ngOnInit() { 21 | this.roslibTopic = new ROSLIB.Topic({ 22 | ros, 23 | name: this.topic.name, 24 | messageType: this.topic.type, 25 | }); 26 | } 27 | 28 | toggleSubscription(isSubscribing: boolean): void { 29 | if (isSubscribing) { 30 | this.roslibTopic.subscribe(message => { 31 | this.input = message; 32 | }); 33 | } else { 34 | this.roslibTopic.unsubscribe(); 35 | } 36 | this.isSubscribing = isSubscribing; 37 | } 38 | 39 | publish(): void { 40 | const message = new ROSLIB.Message(this.input); 41 | this.roslibTopic.publish(message); 42 | } 43 | } 44 | -------------------------------------------------------------------------------- /src/app/type/type.component.css: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/pantor/ros-control-center/dc853cd61f7a599ad19bcf5166b7ff8be92fe216/src/app/type/type.component.css -------------------------------------------------------------------------------- /src/app/type/type.component.html: -------------------------------------------------------------------------------- 1 |
2 |
3 |
4 | 5 | {{ m.name | humanize }} {{ m.length }} 6 | 7 | 8 |
9 | 10 |
11 | 12 | {{ m.name | humanize }} {{ m.length }} 13 | 14 |
15 | 16 | 17 | 18 | 19 | 20 | 21 |
22 | Time 23 |
24 |
25 |
26 |
27 |
28 | -------------------------------------------------------------------------------- /src/app/type/type.component.spec.ts: -------------------------------------------------------------------------------- 1 | import { async, ComponentFixture, TestBed } from '@angular/core/testing'; 2 | 3 | import { TypeComponent } from './type.component'; 4 | 5 | describe('TypeComponent', () => { 6 | let component: TypeComponent; 7 | let fixture: ComponentFixture; 8 | 9 | beforeEach(async(() => { 10 | TestBed.configureTestingModule({ 11 | declarations: [ TypeComponent ] 12 | }) 13 | .compileComponents(); 14 | })); 15 | 16 | beforeEach(() => { 17 | fixture = TestBed.createComponent(TypeComponent); 18 | component = fixture.componentInstance; 19 | fixture.detectChanges(); 20 | }); 21 | 22 | it('should create', () => { 23 | expect(component).toBeTruthy(); 24 | }); 25 | }); 26 | -------------------------------------------------------------------------------- /src/app/type/type.component.ts: -------------------------------------------------------------------------------- 1 | import { Component, OnInit, Input, Output, EventEmitter } from '@angular/core'; 2 | 3 | @Component({ 4 | selector: 'app-type', 5 | templateUrl: './type.component.html', 6 | styleUrls: ['./type.component.css'] 7 | }) 8 | export class TypeComponent implements OnInit { 9 | @Output() childEvent = new EventEmitter(); 10 | @Input() info: Type; 11 | @Input() data: any; 12 | @Input() readonly: boolean; 13 | @Input() level = 0; 14 | public horizontal = false; 15 | 16 | ngOnInit() { 17 | this.horizontal = this.info && this.info.members && !this.info.members.some(e => typeof e.members !== 'undefined'); 18 | } 19 | 20 | getLooseType(primitiveType: string): string { 21 | const numbers = [ 22 | 'int8', 23 | 'uint8', 24 | 'int16', 25 | 'uint16', 26 | 'int32', 27 | 'uint32', 28 | 'int64', 29 | 'uint64', 30 | 'float32', 31 | 'float64', 32 | ]; 33 | if (numbers.includes(primitiveType)) { 34 | return 'number'; 35 | } 36 | return primitiveType; 37 | } 38 | 39 | update(object: { names: string[], value: any }) { 40 | if (this.level > 0) { 41 | object.names.unshift(this.info.name); 42 | this.childEvent.emit(object); 43 | } else { 44 | if (this.data === undefined) { 45 | this.data = {}; 46 | } 47 | let dataElement = this.data; 48 | for (const n of object.names.slice(0, -1)) { 49 | if (dataElement[n] === undefined) { 50 | dataElement[n] = {}; 51 | } 52 | dataElement = dataElement[n]; 53 | } 54 | dataElement[object.names[object.names.length - 1]] = object.value; 55 | } 56 | } 57 | } 58 | -------------------------------------------------------------------------------- /src/assets/ros-logo.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /src/assets/ros.svg: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 18 | 20 | 44 | 46 | 47 | 49 | image/svg+xml 50 | 52 | 53 | 54 | 55 | 56 | 62 | 68 | 74 | 80 | 86 | 87 | 88 | -------------------------------------------------------------------------------- /src/assets/screenshot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/pantor/ros-control-center/dc853cd61f7a599ad19bcf5166b7ff8be92fe216/src/assets/screenshot.png -------------------------------------------------------------------------------- /src/environments/environment.prod.ts: -------------------------------------------------------------------------------- 1 | export const environment = { 2 | production: true 3 | }; 4 | -------------------------------------------------------------------------------- /src/environments/environment.ts: -------------------------------------------------------------------------------- 1 | // The file contents for the current environment will overwrite these during build. 2 | // The build system defaults to the dev environment which uses `environment.ts`, but if you do 3 | // `ng build --env=prod` then `environment.prod.ts` will be used instead. 4 | // The list of which env maps to which file can be found in `.angular-cli.json`. 5 | 6 | export const environment = { 7 | production: false 8 | }; 9 | -------------------------------------------------------------------------------- /src/index.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | ROS Control Center 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /src/main.ts: -------------------------------------------------------------------------------- 1 | import { enableProdMode } from '@angular/core'; 2 | import { platformBrowserDynamic } from '@angular/platform-browser-dynamic'; 3 | 4 | import { AppModule } from './app/app.module'; 5 | import { environment } from './environments/environment'; 6 | 7 | if (environment.production) { 8 | enableProdMode(); 9 | } 10 | 11 | platformBrowserDynamic().bootstrapModule(AppModule); 12 | -------------------------------------------------------------------------------- /src/polyfills.ts: -------------------------------------------------------------------------------- 1 | /** 2 | * This file includes polyfills needed by Angular and is loaded before the app. 3 | * You can add your own extra polyfills to this file. 4 | * 5 | * This file is divided into 2 sections: 6 | * 1. Browser polyfills. These are applied before loading ZoneJS and are sorted by browsers. 7 | * 2. Application imports. Files imported after ZoneJS that should be loaded before your main 8 | * file. 9 | * 10 | * The current setup is for so-called "evergreen" browsers; the last versions of browsers that 11 | * automatically update themselves. This includes Safari >= 10, Chrome >= 55 (including Opera), 12 | * Edge >= 13 on the desktop, and iOS 10 and Chrome on mobile. 13 | * 14 | * Learn more in https://angular.io/docs/ts/latest/guide/browser-support.html 15 | */ 16 | 17 | /*************************************************************************************************** 18 | * BROWSER POLYFILLS 19 | */ 20 | 21 | /** IE9, IE10 and IE11 requires all of the following polyfills. **/ 22 | // import 'core-js/es6/symbol'; 23 | // import 'core-js/es6/object'; 24 | // import 'core-js/es6/function'; 25 | // import 'core-js/es6/parse-int'; 26 | // import 'core-js/es6/parse-float'; 27 | // import 'core-js/es6/number'; 28 | // import 'core-js/es6/math'; 29 | // import 'core-js/es6/string'; 30 | // import 'core-js/es6/date'; 31 | // import 'core-js/es6/array'; 32 | // import 'core-js/es6/regexp'; 33 | // import 'core-js/es6/map'; 34 | // import 'core-js/es6/weak-map'; 35 | // import 'core-js/es6/set'; 36 | 37 | /** IE10 and IE11 requires the following for NgClass support on SVG elements */ 38 | // import 'classlist.js'; // Run `npm install --save classlist.js`. 39 | 40 | /** IE10 and IE11 requires the following to support `@angular/animation`. */ 41 | // import 'web-animations-js'; // Run `npm install --save web-animations-js`. 42 | 43 | 44 | /** Evergreen browsers require these. **/ 45 | import 'core-js/es6/reflect'; 46 | import 'core-js/es7/reflect'; 47 | 48 | 49 | /** ALL Firefox browsers require the following to support `@angular/animation`. **/ 50 | // import 'web-animations-js'; // Run `npm install --save web-animations-js`. 51 | 52 | 53 | 54 | /*************************************************************************************************** 55 | * Zone JS is required by Angular itself. 56 | */ 57 | import 'zone.js/dist/zone'; // Included with Angular CLI. 58 | 59 | 60 | 61 | /*************************************************************************************************** 62 | * APPLICATION IMPORTS 63 | */ 64 | 65 | /** 66 | * Date, currency, decimal and percent pipes. 67 | * Needed for: All but Chrome, Firefox, Edge, IE11 and Safari 10 68 | */ 69 | // import 'intl'; // Run `npm install --save intl`. 70 | /** 71 | * Need to import at least one locale-data with intl. 72 | */ 73 | // import 'intl/locale-data/jsonp/en'; 74 | -------------------------------------------------------------------------------- /src/styles.css: -------------------------------------------------------------------------------- 1 | @import url("../node_modules/bootstrap/dist/css/bootstrap.css"); 2 | 3 | .card { 4 | margin-bottom: 5px; 5 | } 6 | .card.active { 7 | color: white; 8 | background-color: #2E3D5F; 9 | border: 1px #2E3D5F solid; 10 | } 11 | .card-node { 12 | cursor: pointer; 13 | overflow: hidden; 14 | } 15 | .card-title { 16 | margin: 0.6rem 0.8rem; 17 | } 18 | .card-body-sm { 19 | margin: 0 0.6rem 0.6rem 0.6rem; 20 | } 21 | 22 | .form-margin { 23 | margin: 0 15px; 24 | } 25 | .btn-title { 26 | padding: 0.1rem 0.5rem; 27 | margin: 0.3rem 0.6rem; 28 | } 29 | 30 | .d-flex-g { 31 | flex-grow: 1; 32 | } 33 | 34 | app-type { 35 | flex: 1; 36 | } 37 | -------------------------------------------------------------------------------- /src/tsconfig.app.json: -------------------------------------------------------------------------------- 1 | { 2 | "extends": "../tsconfig.json", 3 | "compilerOptions": { 4 | "outDir": "../out-tsc/app", 5 | "module": "es2015", 6 | "baseUrl": "", 7 | "types": [] 8 | }, 9 | "exclude": [ 10 | "test.ts", 11 | "**/*.spec.ts" 12 | ] 13 | } 14 | -------------------------------------------------------------------------------- /src/tsconfig.spec.json: -------------------------------------------------------------------------------- 1 | { 2 | "extends": "../tsconfig.json", 3 | "compilerOptions": { 4 | "outDir": "../out-tsc/spec", 5 | "module": "commonjs", 6 | "target": "es5", 7 | "baseUrl": "", 8 | "types": [ 9 | "jasmine", 10 | "node" 11 | ] 12 | }, 13 | "files": [ 14 | "test.ts" 15 | ], 16 | "include": [ 17 | "**/*.spec.ts", 18 | "**/*.d.ts" 19 | ] 20 | } 21 | -------------------------------------------------------------------------------- /src/typings.d.ts: -------------------------------------------------------------------------------- 1 | /* SystemJS module definition */ 2 | declare var module: NodeModule; 3 | interface NodeModule { 4 | id: string; 5 | } 6 | -------------------------------------------------------------------------------- /tsconfig.json: -------------------------------------------------------------------------------- 1 | { 2 | "compileOnSave": false, 3 | "compilerOptions": { 4 | "outDir": "./dist/out-tsc", 5 | "baseUrl": "src", 6 | "sourceMap": true, 7 | "declaration": false, 8 | "moduleResolution": "node", 9 | "emitDecoratorMetadata": true, 10 | "experimentalDecorators": true, 11 | "target": "es5", 12 | "typeRoots": [ 13 | "node_modules/@types" 14 | ], 15 | "lib": [ 16 | "es2016", 17 | "dom" 18 | ] 19 | } 20 | } 21 | -------------------------------------------------------------------------------- /tslint.json: -------------------------------------------------------------------------------- 1 | { 2 | "rulesDirectory": [ 3 | "node_modules/codelyzer" 4 | ], 5 | "rules": { 6 | "arrow-return-shorthand": true, 7 | "callable-types": true, 8 | "class-name": true, 9 | "comment-format": [ 10 | true, 11 | "check-space" 12 | ], 13 | "curly": true, 14 | "eofline": true, 15 | "forin": true, 16 | "import-blacklist": [ 17 | true, 18 | "rxjs" 19 | ], 20 | "import-spacing": true, 21 | "indent": [ 22 | true, 23 | "spaces" 24 | ], 25 | "interface-over-type-literal": true, 26 | "label-position": true, 27 | "max-line-length": [ 28 | true, 29 | 140 30 | ], 31 | "member-access": false, 32 | "member-ordering": [ 33 | true, 34 | "static-before-instance", 35 | "variables-before-functions" 36 | ], 37 | "no-arg": true, 38 | "no-bitwise": true, 39 | "no-console": [ 40 | true, 41 | "debug", 42 | "info", 43 | "time", 44 | "timeEnd", 45 | "trace" 46 | ], 47 | "no-construct": true, 48 | "no-debugger": true, 49 | "no-duplicate-super": true, 50 | "no-empty": false, 51 | "no-empty-interface": true, 52 | "no-eval": true, 53 | "no-inferrable-types": [ 54 | true, 55 | "ignore-params" 56 | ], 57 | "no-misused-new": true, 58 | "no-non-null-assertion": true, 59 | "no-shadowed-variable": true, 60 | "no-string-literal": false, 61 | "no-string-throw": true, 62 | "no-switch-case-fall-through": true, 63 | "no-trailing-whitespace": true, 64 | "no-unnecessary-initializer": true, 65 | "no-unused-expression": true, 66 | "no-use-before-declare": true, 67 | "no-var-keyword": true, 68 | "object-literal-sort-keys": false, 69 | "one-line": [ 70 | true, 71 | "check-open-brace", 72 | "check-catch", 73 | "check-else", 74 | "check-whitespace" 75 | ], 76 | "prefer-const": true, 77 | "quotemark": [ 78 | true, 79 | "single" 80 | ], 81 | "radix": true, 82 | "semicolon": [ 83 | "always" 84 | ], 85 | "triple-equals": [ 86 | true, 87 | "allow-null-check" 88 | ], 89 | "typedef-whitespace": [ 90 | true, 91 | { 92 | "call-signature": "nospace", 93 | "index-signature": "nospace", 94 | "parameter": "nospace", 95 | "property-declaration": "nospace", 96 | "variable-declaration": "nospace" 97 | } 98 | ], 99 | "typeof-compare": true, 100 | "unified-signatures": true, 101 | "variable-name": false, 102 | "whitespace": [ 103 | true, 104 | "check-branch", 105 | "check-decl", 106 | "check-operator", 107 | "check-separator", 108 | "check-type" 109 | ], 110 | "directive-selector": [ 111 | true, 112 | "attribute", 113 | "app", 114 | "camelCase" 115 | ], 116 | "component-selector": [ 117 | true, 118 | "element", 119 | "app", 120 | "kebab-case" 121 | ], 122 | "use-input-property-decorator": true, 123 | "use-output-property-decorator": true, 124 | "use-host-property-decorator": true, 125 | "no-input-rename": true, 126 | "no-output-rename": true, 127 | "use-life-cycle-interface": true, 128 | "use-pipe-transform-interface": true, 129 | "component-class-suffix": true, 130 | "directive-class-suffix": true 131 | } 132 | } 133 | --------------------------------------------------------------------------------