├── .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 | [](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 |
13 | The ROS Control Center is not connected to a robot running rosbridge_suite at {{ setting.address }}:{{ setting.port }}. You can change the URL in the Settings tab, further information can be found in the GitHub Repository.
14 |