diff --git a/.docker/overlay.repos b/.docker/overlay.repos deleted file mode 100644 index d993590..0000000 --- a/.docker/overlay.repos +++ /dev/null @@ -1,37 +0,0 @@ -repositories: - # turtlebot3: - # type: git - # url: https://github.com/ROBOTIS-GIT/turtlebot3 - # version: ros2-devel - # turtlebot3/turtlebot3_msgs: - # type: git - # url: https://github.com/ROBOTIS-GIT/turtlebot3_msgs.git - # version: ros2-devel - # turtlebot3/turtlebot3_simulations: - # type: git - # url: https://github.com/ROBOTIS-GIT/turtlebot3_simulations.git - # version: ros2-devel - # cartographer/cartographer: - # type: git - # url: https://github.com/ROBOTIS-GIT/cartographer.git - # version: dashing - # cartographer/cartographer_ros: - # type: git - # url: https://github.com/ros2/cartographer_ros.git - # version: dashing - ros2/sros2: - type: git - url: https://github.com/ros2/sros2.git - version: master - launch-ros-sandbox: - type: git - url: https://github.com/aws-robotics/launch-ros-sandbox - version: master - # ros2/pcl_conversions: - # type: git - # url: https://github.com/ros2/pcl_conversions.git - # version: ros2 - # ros-planning/navigation2: - # type: git - # url: https://github.com/ros-planning/navigation2.git - # version: master \ No newline at end of file diff --git a/Dockerfile b/Dockerfile index 1804332..18c71f1 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,91 +1,119 @@ -FROM osrf/ros:dashing-desktop -# FROM osrf/ros2:nightly +ARG FROM_IMAGE=ros:foxy +ARG OVERLAY_WS=/opt/ros/overlay_ws + +# multi-stage for caching +FROM $FROM_IMAGE AS cacher + +# copy overlay source +ARG OVERLAY_WS +WORKDIR $OVERLAY_WS +COPY ./overlay ./ +RUN vcs import src < overlay.repos && \ + find src -name ".git" | xargs rm -rf || true + +# copy manifests for caching +WORKDIR /opt +RUN mkdir -p /tmp/opt && \ + find ./ -name "package.xml" | \ + xargs cp --parents -t /tmp/opt && \ + find ./ -name "COLCON_IGNORE" | \ + xargs cp --parents -t /tmp/opt || true + +# multi-stage for building +FROM $FROM_IMAGE AS builder +ARG DEBIAN_FRONTEND=noninteractive # install helpful developer tools RUN apt-get update && apt-get install -y \ bash-completion \ byobu \ + ccache \ fish \ glances \ + micro \ nano \ python3-argcomplete \ tree \ vim \ - && cd /usr/bin && curl https://getmic.ro | bash \ && rm -rf /var/lib/apt/lists/* -# install turtlebot external packages -RUN apt-get update && apt-get install -y \ - ros-$ROS_DISTRO-rqt* \ - ros-$ROS_DISTRO-turtlebot3-cartographer \ - ros-$ROS_DISTRO-turtlebot3-navigation2 \ - ros-$ROS_DISTRO-turtlebot3-simulations \ - ros-$ROS_DISTRO-turtlebot3-teleop \ - && rm -rf /var/lib/apt/lists/* +# # install RTI Connext DDS +# # set up environment +# ENV NDDSHOME /opt/rti.com/rti_connext_dds-6.0.1 +# WORKDIR $NDDSHOME +# COPY ./rti ./ +# RUN yes | ./rti_connext_dds-6.0.1-eval-x64Linux3gcc5.4.0.run && \ +# mv y/*/* ./ && rm -rf y +# # set RTI DDS environment +# ENV CONNEXTDDS_DIR $NDDSHOME +# ENV PATH "$NDDSHOME/bin":$PATH +# ENV LD_LIBRARY_PATH "$NDDSHOME/lib/x64Linux3gcc5.4.0":$LD_LIBRARY_PATH +# # set RTI openssl environment +# ENV PATH "$NDDSHOME/third_party/openssl-1.1.1d/x64Linux4gcc7.3.0/release/bin":$PATH +# ENV LD_LIBRARY_PATH "$NDDSHOME/third_party/openssl-1.1.1d/x64Linux4gcc7.3.0/release/lib":$LD_LIBRARY_PATH -# clone overlay package repos -ENV TB3_OVERLAY_WS /opt/tb3_overlay_ws -RUN mkdir -p $TB3_OVERLAY_WS/src -WORKDIR $TB3_OVERLAY_WS -COPY .docker/overlay.repos ./ -RUN vcs import src < overlay.repos -# Install extra sources from this repo -COPY example_nodes/ src/example_nodes -# RUN vcs import src < src/ros-planning/navigation2/tools/ros2_dependencies.repos - -# install overlay package dependencies -RUN . /opt/ros/$ROS_DISTRO/setup.sh \ - && rosdep update \ - && rosdep install -y \ +# install overlay dependencies +ARG OVERLAY_WS +WORKDIR $OVERLAY_WS +COPY --from=cacher /tmp/$OVERLAY_WS/src ./src +RUN . /opt/ros/$ROS_DISTRO/setup.sh && \ + apt-get update && rosdep update \ + --rosdistro $ROS_DISTRO && \ + apt-get upgrade -y && \ + rosdep install -q -y \ --from-paths src \ --ignore-src \ - --skip-keys " \ - ament_mypy \ - libopensplice69 \ - rti-connext-dds-5.3.1 \ - " \ && rm -rf /var/lib/apt/lists/* -# build overlay package source -# RUN touch $TB3_OVERLAY_WS/src/turtlebot3/turtlebot3_node/COLCON_IGNORE +# build overlay source +COPY --from=cacher $OVERLAY_WS/src ./src +ARG OVERLAY_MIXINS="release ccache" RUN . /opt/ros/$ROS_DISTRO/setup.sh && \ colcon build \ - --symlink-install + --symlink-install \ + --mixin $OVERLAY_MIXINS -# fetch and install tools for reconnaissance -WORKDIR /tmp -RUN apt-get -qq update && DEBIAN_FRONTEND=noninteractive apt-get -y install \ - libgmp3-dev gengetopt \ - libpcap-dev flex byacc \ - libjson-c-dev unzip \ - libunistring-dev wget \ - libxml2-dev libxslt1-dev \ - libffi-dev libssl-dev \ - tshark && \ - rm -rf /var/lib/apt/lists/* -RUN git clone https://github.com/aliasrobotics/aztarna && \ - cd aztarna && python3 setup.py install +# # install RTI Connext +# ENV RTI_NC_LICENSE_ACCEPTED yes +# RUN apt-get update && apt-get install -y \ +# ros-$ROS_DISTRO-rmw-connext-cpp \ +# && rm -rf /var/lib/apt/lists/* +# # set up environment +# ENV NDDSHOME /opt/rti.com/rti_connext_dds-5.3.1 +# ENV PATH "$NDDSHOME/bin":$PATH +# ENV LD_LIBRARY_PATH "$NDDSHOME/lib/x64Linux3gcc5.4.0":$LD_LIBRARY_PATH +# # install RTI Security +# WORKDIR $NDDSHOME +# # ADD https://s3.amazonaws.com/RTI/Bundles/5.3.1/Evaluation/rti_connext_dds_secure-5.3.1-eval-x64Linux3gcc5.4.0.tar.gz ./ +# # RUN tar -xvf rti_connext_dds_secure-5.3.1-eval-x64Linux3gcc5.4.0.tar.gz -C ./ +# COPY ./rti ./ +# RUN rtipkginstall rti_security_plugins-5.3.1-eval-x64Linux3gcc5.4.0.rtipkg && \ +# rtipkginstall openssl-1.0.2n-5.3.1-host-x64Linux.rtipkg && \ +# tar -xvf openssl-1.0.2n-target-x64Linux3gcc5.4.0.tar.gz +# ENV PATH "$NDDSHOME/openssl-1.0.2n/x64Linux3gcc5.4.0/release/bin":$PATH +# ENV LD_LIBRARY_PATH "$NDDSHOME/openssl-1.0.2n/x64Linux3gcc5.4.0/release/lib":$LD_LIBRARY_PATH +# # install RTI QoS +# ENV NDDS_QOS_PROFILES "$NDDSHOME/NDDS_QOS_PROFILES.xml" # generate artifacts for keystore -ENV TB3_DEMO_DIR $TB3_OVERLAY_WS/.. +ENV TB3_DEMO_DIR $OVERLAY_WS/.. WORKDIR $TB3_DEMO_DIR COPY policies policies -RUN . $TB3_OVERLAY_WS/install/setup.sh && \ +RUN . $OVERLAY_WS/install/setup.sh && \ ros2 security generate_artifacts -k keystore \ - -p policies/tb3_gazebo_policy.xml \ - -n /_ros2cli + -p policies/tb3_gazebo_policy.xml # copy demo files -COPY maps maps COPY configs configs COPY .gazebo /root/.gazebo # source overlay workspace from entrypoint +ENV OVERLAY_WS $OVERLAY_WS RUN sed --in-place \ - 's|^source .*|source "$TB3_OVERLAY_WS/install/setup.bash"|' \ + 's|^source .*|source "$OVERLAY_WS/install/setup.bash"|' \ /ros_entrypoint.sh && \ cp /etc/skel/.bashrc ~/ && \ - echo 'source "$TB3_OVERLAY_WS/install/setup.bash"' >> ~/.bashrc + echo 'source "$OVERLAY_WS/install/setup.bash"' >> ~/.bashrc ENV TURTLEBOT3_MODEL='burger' \ - GAZEBO_MODEL_PATH=/opt/ros/$ROS_DISTRO/share/turtlebot3_gazebo/models:$GAZEBO_MODEL_PATH + GAZEBO_MODEL_PATH=$OVERLAY_WS/install/turtlebot3_gazebo/share/turtlebot3_gazebo/models:$GAZEBO_MODEL_PATH diff --git a/README.md b/README.md index e5f8ae3..f1302b5 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ # Secure Turtlebot3 Demo -This repository includes a demo for securing a simulated Turtlebot3 using SROS2; including sensor and control topics as well the relevant portions of the cartographer and navigation2 software stacks. +This repository includes a demo for securing a simulated Turtlebot3 using SROS2; including sensor and control topics as well the relevant portions of the slam_toolbox and navigation2 software stacks. ## Setting the Demo @@ -16,7 +16,7 @@ To run this demo using docker, the following dependencies are required: * Please ensure display forwarding is working with rocker. * [nvidia-docker](https://github.com/NVIDIA/nvidia-docker) is also useful for those with a GPU. * [off-your-rocker](https://github.com/sloretz/off-your-rocker) - * Rocker extension. Required to run the sandbox demo. Used to pass arbitrary arguments Docker arguments through rocker. + * Rocker extension, for passing through arbitrary Docker arguments. For those who can't use linux containers or for detailed instructions on how to build, you may still follow the general build steps of the [Dockerfile](Dockerfile). @@ -41,7 +41,7 @@ Byobu starts a new session and launch the turtlebot3 demo over several windows: * initialize pose script * navigation goal script * `mapping` - * cartographer mapping stack + * slam_toolbox mapping stack * save map file * map topic info * `sros` @@ -55,50 +55,10 @@ You can first drive the robot around and generate a map using the teleoperation [![](media/mapping3.png)](media/mapping.mp4) -Feel free to poke around, open a new window and list or echo topics and services. You can explore the other panes as well, for example you can stop cartographer in the `mapping` window and start the navigation launchfile from the `navigation` window. You will stat by localizing the robot by initializing the pose and then setting a navigation goal via the scripts in the respective window panes. This can also be done graphically via rviz. +Feel free to poke around, open a new window and list or echo topics and services. You can explore the other panes as well, for example you can stop slam_toolbox in the `mapping` window and start the navigation launchfile from the `navigation` window. You will stat by localizing the robot by initializing the pose and then setting a navigation goal via the scripts in the respective window panes. This can also be done graphically via rviz. [![](media/localize.png)](media/localize.mp4) -## Running the reconnaissance demo: - -Reconnaissance is the act of gathering preliminary data or intelligence on your target. The data is gathered in order to better plan for your attack. Reconnaissance can be performed actively (meaning that you are directly touching/connecting-to the target) or passively (meaning that your reconnaissance is being performed through an intermediary). - -The purpose of reconnaissance is to accumulate as much information as possible about a robot or robot component, including the available ROS abstractions (topics, services, etc.), the version of ROS, the target’s hardware platform and more. - -In this short tutorial we'll demonstrate the use of [`aztarna`](https://github.com/aliasrobotics/aztarna/), a tool for performing reconnaissance in a variety of robotic systems. Particularly, we'll look at the information we can obtain by performing active reconnaissance in an unsecure robot acting both as an attacker with direct access to the robot ("host/container" insider) and as an attacker with access to the local internal network where ROS 2 operates. - -### Host/container insider attacker -``` bash -rocker --x11 --nvidia rosswg/turtlebot3_demo:roscon19 "byobu -f configs/unsecure.conf attach" -``` - -### Internal network attacker -``` bash -# in Terminal (terminal 1), initialize first a swarm -docker swarm init -# in Terminal (terminal 1), create the network overlay -docker network create -d overlay \ - --subnet=10.0.0.0/24 \ - --gateway=10.0.0.1 \ - --ip-range 10.0.0.192/27 \ - --attachable \ - overlay - -# in another Terminal (terminal 2), launch demo -rocker --x11 --nvidia --network overlay rosswg/turtlebot3_demo:roscon19 "byobu -f configs/unsecure.conf attach" - -# in another Terminal (terminal 3), launch another container -docker run -it --rm --network overlay --name aztarna rosswg/turtlebot3_demo:roscon19 /bin/bash -# then perform a scan -$ aztarna -t ros2 -``` - -Cleanup afterwards: -```bash -docker network rm overlay -``` - - ## Running the secure demo: So far we've simply launched the turtlebot3 without using SROS2. To enable security, simply exit the previous byobu session and start a new one now using the secure config: @@ -120,7 +80,6 @@ These variables simply enable as well as enforce security for all ros2 nodes whi * https://design.ros2.org/articles/ros2_dds_security.html - ## Re-generate security artifacts Using the same attached session above, now lets try and generate security artifacts for ourselves, rather than simply using the same artifacts that came bundled in the demo docker image. We can start by switching over to the sros window and clearing out the existing keystore: @@ -188,51 +147,11 @@ export ROS_SECURITY_ENABLE=true Now try starting another teleop node with security disabled and check that only the secure teleop node can drive the robot. -## Sandboxed Nodes Demo - -The [ROSCon 2019](https://ros-swg.github.io/ROSCon19_Security_Workshop/) [ROS2 Security Workshop](https://ros-swg.github.io/ROSCon19_Security_Workshop/) -will present the opportunity to run the Turtlebot3 demo using the [launch-ros-sandbox](https://github.com/aws-robotics/launch-ros-sandbox) -package. Specifically, the demo uses this package to launch the Turtlebot3 navigation nodes in a docker container. See the -configs/sandbox_demo/navigation_sandbox.launch.py launch file for details. - -### Running the Security Workshop Sandbox Node Demo - -``` bash -rocker --x11 --nvidia rosswg/turtlebot3_demo "byobu -f configs/sandbox_demo/unsecure.conf attach" -``` - -Omit the `--nvidia` arg if you don't have dedicated GPU for hardware acceleration of 3D OpenGL views. - -Likewise, the following command is used to run the demo using the secure config: - -``` bash -rocker --x11 --nvidia rosswg/turtlebot3_demo "byobu -f configs/sandbox_demo/secure.conf attach" -``` - -### Demonstrating Sandbox Resource Limits - -This demo shows how robot code, acting improperly, can negatively affect the entire robotic system. - -``` bash -rocker --x11 --nvidia rosswg/turtlebot3_demo "byobu -f configs/sandbox_demo/bad_actor.conf attach" --oyr-run-arg " -v /var/run/docker.sock:/var/run/docker.sock " -``` - -After launching with the above config, there are two commands ready in the `bad_actor` byobu window. -They are ready to run a cpu hog that will fork many busy processes. -This is a contrived example - but it illustrates what could happen if a node that you are using hits an untested code path and goes into an infinite loop. - -If you run the top command (`ros2 run...`), you can see the CPU of your system jump to 100% usage (check the `diagnostic` byobu window), grinding everything else to a halt. - -However, if you kill that and run the bottom command (`ros2 launch ...`), it will launch inside a container that has a CPU resource limit set. -This launch will be able to use at most 2 CPUs worth of processing, allowing the rest of the demo to still run at a normal speed. -See `example_nodes/launch/sandboxed_cpu_hog.launch.py` for some more info on the arguments that make this happen. - - ## Developing To rebuild this demo locally if you are working on it, you can rebuild the Docker image with the same tag, so all above demo commands will work correctly. ``` bash git clone git@github.com:ros-swg/turtlebot3_demo.git cd turtlebot3_demo -docker build . -t rosswg/turtlebot3_demo +docker build --tag rosswg/turtlebot3_demo . ``` diff --git a/configs/common.conf b/configs/common.conf index 55c2692..4c2db22 100644 --- a/configs/common.conf +++ b/configs/common.conf @@ -13,7 +13,7 @@ select-pane -t 1 # create navigation window new-window -n navigation -send-keys 'ros2 launch turtlebot3_navigation2 navigation2.launch.py use_sim_time:=true map:=maps/map.yaml' # Enter +send-keys 'ros2 launch nav2_bringup tb3_simulation_launch.py use_simulator:=False' Enter split-window -h send-keys 'configs/initial_pose.sh' @@ -26,15 +26,16 @@ select-pane -t 1 # create mapping window new-window -n mapping -send-keys 'ros2 launch turtlebot3_cartographer cartographer.launch.py use_sim_time:=true' Enter +send-keys 'ros2 launch nav2_bringup tb3_simulation_launch.py use_simulator:=False slam:=True' # Enter split-window -h -send-keys 'ros2 run nav2_map_server map_saver -f maps/map' +send-keys 'mkdir maps' Enter +send-keys 'ros2 run nav2_map_server map_saver_cli -f maps/my_map' split-window -v -send-keys 'ros2 topic info /map' +send-keys 'ros2 topic info -v /map' -# Select cartographer pane +# Select slam_toolbox pane select-pane -t 0 # create sros window @@ -42,23 +43,14 @@ new-window -n sros send-keys 'tree keystore -d' Enter split-window -h -send-keys 'ros2 security generate_artifacts -k keystore -p policies/tb3_gazebo_policy.xml -n /_ros2cli' +send-keys 'ros2 security generate_artifacts -k keystore -p policies/tb3_gazebo_policy.xml -e /admin' split-window -v send-keys 'env | grep ROS' Enter -new-window -n reconnaissance -send-keys 'aztarna -t ros2' - -split-window -h -send-keys 'tshark -i eth0 -f "udp" -Y "rtps"' - -# Select ROS2 reconnaissance pane -select-pane -t 0 - # create rqt window new-window -n rqt -send-keys 'ROS_SECURITY_NODE_DIRECTORY=$TB3_DEMO_DIR/keystore/_ros2cli rqt' +send-keys 'ROS_SECURITY_ENCLAVE_OVERRIDE=/admin rqt' # reselect turtlebot window (the one with teleop) select-window -t turtlebot diff --git a/configs/debug.conf b/configs/debug.conf index a99d46f..414a4e9 100644 --- a/configs/debug.conf +++ b/configs/debug.conf @@ -7,7 +7,7 @@ send-keys 'glances' Enter setenv FOO "foo" setenv ROS_SECURITY_ENABLE true setenv ROS_SECURITY_STRATEGY Enforce -setenv ROS_SECURITY_NODE_DIRECTORY $TB3_DEMO_DIR/keystore/_ros2cli -setenv ROS_SECURITY_LOOKUP_TYPE MATCH_PREFIX +setenv ROS_SECURITY_KEYSTORE $TB3_DEMO_DIR/keystore +setenv ROS_SECURITY_ENCLAVE_OVERRIDE / source configs/common.conf diff --git a/configs/initial_pose.sh b/configs/initial_pose.sh index e4ab72c..be109e6 100755 --- a/configs/initial_pose.sh +++ b/configs/initial_pose.sh @@ -6,8 +6,8 @@ header: pose: pose: position: - x: -2.7 - y: 0.4 + x: -2.0 + y: -0.5 z: 0.0 orientation: x: 0.0 diff --git a/configs/navigate_to_pose.sh b/configs/navigate_to_pose.sh index 7935903..cce0e25 100755 --- a/configs/navigate_to_pose.sh +++ b/configs/navigate_to_pose.sh @@ -1,6 +1,6 @@ #!/usr/bin/env bash -ros2 action send_goal /NavigateToPose nav2_msgs/action/NavigateToPose " +ros2 action send_goal /navigate_to_pose nav2_msgs/action/NavigateToPose " pose: pose: position: diff --git a/configs/sandbox_demo/bad_actor.conf b/configs/sandbox_demo/bad_actor.conf deleted file mode 100644 index 8426c35..0000000 --- a/configs/sandbox_demo/bad_actor.conf +++ /dev/null @@ -1,15 +0,0 @@ -source $BYOBU_PREFIX/share/byobu/profiles/tmux - -# setup secure session -new-session -s secure -n diagnostic -d -send-keys 'glances' Enter - -setenv FOO "foo" - -source configs/sandbox_demo/security_workshop_demo_common.conf - -new-window -n bad_actor -send-keys 'ros2 run example_nodes cpu_hog 32' - -split-window -v -send-keys 'ros2 launch example_nodes sandboxed_cpu_hog.launch.py' diff --git a/configs/sandbox_demo/navigation_sandbox.launch.py b/configs/sandbox_demo/navigation_sandbox.launch.py deleted file mode 100644 index 93c1789..0000000 --- a/configs/sandbox_demo/navigation_sandbox.launch.py +++ /dev/null @@ -1,222 +0,0 @@ -# Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -""" -This launch file is meant to be used to showcase the launch_ros_sandbox -package capabilities. - -When running the Turtlebot 3 security demo, the navigation nodes are sandboxed, -i.e., running in a docker container. Using the launch_ros_sandbox -SandboxedNodeContainer and SandboxedNode here, we can replace the following -launch files: - - ros-swg/turtlebot3_demo/navigation2.launch.py - ros-planning/navigation2/nav2_bringup_launch.py - ros-planning/navigation2/nav2_localization_launch.py - ros-planning/navigation2/nav2_navigation_launch.py - -For more details please see the launch_ros_sandbox project at -https://github.com/aws-robotics/launch-ros-sandbox -""" -import os - -from ament_index_python.packages import get_package_prefix, get_package_share_directory - -from nav2_common.launch import RewrittenYaml - -from launch import LaunchDescription -from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir -from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable -from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable -from launch_ros.actions import Node - -from launch_ros_sandbox.actions import SandboxedNodeContainer -from launch_ros_sandbox.descriptions import DockerPolicy -from launch_ros_sandbox.descriptions import SandboxedNode - -TURTLEBOT3_MODEL = os.environ['TURTLEBOT3_MODEL'] - - -def generate_launch_description(): - # Get the launch directory - use_sim_time = LaunchConfiguration('use_sim_time', default=True) - autostart = LaunchConfiguration('autostart') - params_file = LaunchConfiguration('params_file') - bt_xml_file = LaunchConfiguration('bt_xml_file') - map_subscribe_transient_local = LaunchConfiguration( - 'map_subscribe_transient_local') - - # Create our own temporary YAML files that include substitutions - param_substitutions = { - 'use_sim_time': use_sim_time, - 'bt_xml_filename': bt_xml_file, - 'autostart': autostart, - 'map_subscribe_transient_local': map_subscribe_transient_local} - - configured_params = RewrittenYaml( - source_file=params_file, - rewrites=param_substitutions, - convert_types=True) - - map_dir = LaunchConfiguration( - 'map', - default=os.path.join( - get_package_share_directory('turtlebot3_navigation2'), - 'map', - 'map.yaml')) - - param_file_name = TURTLEBOT3_MODEL + '.yaml' - param_dir = LaunchConfiguration( - 'params', - default=os.path.join( - get_package_share_directory('turtlebot3_navigation2'), - 'param', - param_file_name)) - - rviz_config_dir = os.path.join( - get_package_share_directory('nav2_bringup'), - 'launch', - 'nav2_default_view.rviz') - - return LaunchDescription([ - # Set env var to print messages to stdout immediately - SetEnvironmentVariable('RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1'), - - - DeclareLaunchArgument( - 'map', - default_value=map_dir, - description='Full path to map file to load'), - - DeclareLaunchArgument( - 'use_sim_time', default_value='false', - description='Use simulation (Gazebo) clock if true'), - - DeclareLaunchArgument( - 'autostart', default_value='true', - description='Automatically startup the nav2 stack'), - - DeclareLaunchArgument( - 'params_file', - default_value=param_dir, - description='Full path to the ROS2 parameters file to use'), - - DeclareLaunchArgument( - 'bt_xml_file', - default_value=os.path.join(get_package_prefix('nav2_bt_navigator'), - 'behavior_trees', 'navigate_w_replanning_and_recovery.xml'), - description='Full path to the behavior tree xml file to use'), - - DeclareLaunchArgument( - 'use_lifecycle_mgr', default_value='true', - description='Whether to launch the lifecycle manager'), - - DeclareLaunchArgument( - 'map_subscribe_transient_local', default_value='false', - description='Whether to set the map subscriber QoS to transient local'), - - # The following defines a list of SandboxedNodes running in a docker container - SandboxedNodeContainer( - sandbox_name='security_sandbox', - policy=DockerPolicy( - tag='roscon19', - repository='rosswg/turtlebot3_demo', - container_name='turtlebot3_navigation', - ), - node_descriptions=[ - SandboxedNode( - package='nav2_lifecycle_manager', - node_executable='lifecycle_manager', - node_name='lifecycle_manager', - # output='screen', - parameters=[{'use_sim_time': use_sim_time}, - {'autostart': autostart}, - {'node_names': ['map_server', - 'amcl', - 'controller_server', - 'planner_server', - 'bt_navigator']}]), - SandboxedNode( - package='nav2_map_server', - node_executable='map_server', - node_name='map_server', - # output='screen', - parameters=[configured_params]), - - SandboxedNode( - package='nav2_amcl', - node_executable='amcl', - node_name='amcl', - # output='screen', - parameters=[configured_params]), - - SandboxedNode( - package='nav2_lifecycle_manager', - node_executable='lifecycle_manager', - node_name='lifecycle_manager_localization', - # output='screen', - parameters=[{'use_sim_time': use_sim_time}, - {'autostart': autostart}, - {'node_names': ['map_server', 'amcl']}]), - - SandboxedNode( - package='nav2_controller', - node_executable='controller_server', - # output='screen', - parameters=[configured_params]), - - SandboxedNode( - package='nav2_planner', - node_executable='planner_server', - node_name='planner_server', - # output='screen', - parameters=[configured_params]), - - SandboxedNode( - package='nav2_recoveries', - node_executable='recoveries_node', - node_name='recoveries', - # output='screen', - parameters=[{'use_sim_time': use_sim_time}]), - - SandboxedNode( - package='nav2_bt_navigator', - node_executable='bt_navigator', - node_name='bt_navigator', - # output='screen', - parameters=[configured_params]), - - SandboxedNode( - package='nav2_lifecycle_manager', - node_executable='lifecycle_manager', - node_name='lifecycle_manager_navigation', - # output='screen', - parameters=[{'use_sim_time': use_sim_time}, - {'autostart': autostart}, - {'node_names': ['controller_server', - 'navfn_planner', - 'bt_navigator']}]), - ] - ), - - Node( - package='rviz2', - node_executable='rviz2', - node_name='rviz2', - arguments=['-d', rviz_config_dir], - parameters=[{'use_sim_time': use_sim_time}], - # output='screen' - ), - - ]) diff --git a/configs/sandbox_demo/secure.conf b/configs/sandbox_demo/secure.conf deleted file mode 100644 index d54baf3..0000000 --- a/configs/sandbox_demo/secure.conf +++ /dev/null @@ -1,13 +0,0 @@ -source $BYOBU_PREFIX/share/byobu/profiles/tmux - -# setup secure session -new-session -s secure -n diagnostic -d -send-keys 'glances' Enter - -setenv FOO "foo" -setenv ROS_SECURITY_ENABLE true -setenv ROS_SECURITY_STRATEGY Enforce -setenv ROS_SECURITY_ROOT_DIRECTORY $TB3_DEMO_DIR/keystore -setenv ROS_SECURITY_LOOKUP_TYPE MATCH_PREFIX - -source configs/sandbox_demo/security_workshop_demo_common.conf diff --git a/configs/sandbox_demo/security_workshop_demo_common.conf b/configs/sandbox_demo/security_workshop_demo_common.conf deleted file mode 100644 index 0f63d14..0000000 --- a/configs/sandbox_demo/security_workshop_demo_common.conf +++ /dev/null @@ -1,52 +0,0 @@ -# setup secure session -new-window -n turtlebot -send-keys 'ros2 launch turtlebot3_gazebo turtlebot3_world.launch.py' Enter - -split-window -h -send-keys 'ros2 run turtlebot3_teleop teleop_keyboard' Enter - -split-window -v -send-keys 'ros2 topic echo /cmd_vel' Enter - -# Select teleop pane -select-pane -t 1 - -# create navigation window -new-window -n navigation -# launch navigation using the workshop demo launch script (sandbox nodes) -send-keys 'ros2 launch configs/sandbox_demo/navigation_sandbox.launch.py' Enter - -split-window -h -send-keys 'configs/initial_pose.sh' - -split-window -v -send-keys 'configs/navigate_to_pose.sh' - -# Select initial_pose pane -select-pane -t 1 - -# create mapping window -new-window -n mapping -send-keys 'ros2 launch turtlebot3_cartographer cartographer.launch.py use_sim_time:=true' - -split-window -h -send-keys 'ros2 run nav2_map_server map_saver -f maps/map' - -split-window -v -send-keys 'ros2 topic info /map' - -# Select cartographer pane -select-pane -t 0 - -# create sros window -new-window -n sros -send-keys 'tree keystore -d' Enter - -split-window -h -send-keys 'ros2 security generate_artifacts -k keystore -p policies/tb3_gazebo_policy.xml -n /_ros2cli' - -split-window -v -send-keys 'env | grep ROS' Enter - -# reselect turtlebot window (the one with teleop) -select-window -t turtlebot diff --git a/configs/sandbox_demo/unsecure.conf b/configs/sandbox_demo/unsecure.conf deleted file mode 100644 index 29f7048..0000000 --- a/configs/sandbox_demo/unsecure.conf +++ /dev/null @@ -1,9 +0,0 @@ -source $BYOBU_PREFIX/share/byobu/profiles/tmux - -# setup secure session -new-session -s secure -n diagnostic -d -send-keys 'glances' Enter - -setenv FOO "foo" - -source configs/sandbox_demo/security_workshop_demo_common.conf diff --git a/configs/secure.conf b/configs/secure.conf index f73ad45..b77a0d0 100644 --- a/configs/secure.conf +++ b/configs/secure.conf @@ -5,9 +5,11 @@ new-session -s secure -n diagnostic -d send-keys 'glances' Enter setenv FOO "foo" +# setenv RMW_IMPLEMENTATION rmw_connext_cpp +# setenv RMW_IMPLEMENTATION rmw_connextdds setenv ROS_SECURITY_ENABLE true setenv ROS_SECURITY_STRATEGY Enforce -setenv ROS_SECURITY_ROOT_DIRECTORY $TB3_DEMO_DIR/keystore -setenv ROS_SECURITY_LOOKUP_TYPE MATCH_PREFIX +setenv ROS_SECURITY_KEYSTORE $TB3_DEMO_DIR/keystore +setenv ROS_SECURITY_ENCLAVE_OVERRIDE / -source configs/common.conf \ No newline at end of file +source configs/common.conf diff --git a/configs/unsecure.conf b/configs/unsecure.conf index a2b5a54..013fd54 100644 --- a/configs/unsecure.conf +++ b/configs/unsecure.conf @@ -5,5 +5,7 @@ new-session -s secure -n diagnostic -d send-keys 'glances' Enter setenv FOO "foo" +# setenv RMW_IMPLEMENTATION rmw_connext_cpp +# setenv RMW_IMPLEMENTATION rmw_connextdds -source configs/common.conf \ No newline at end of file +source configs/common.conf diff --git a/example_nodes/CMakeLists.txt b/example_nodes/CMakeLists.txt deleted file mode 100644 index 28c3331..0000000 --- a/example_nodes/CMakeLists.txt +++ /dev/null @@ -1,44 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(example_nodes) - -# Default to C99 -if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 99) -endif() - -# Default to C++14 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rcutils REQUIRED) - -add_executable(cpu_hog src/cpu_hog.cpp) -target_include_directories(cpu_hog PUBLIC - $ - $) -ament_target_dependencies( - cpu_hog - "rcutils" -) - -install(TARGETS cpu_hog - EXPORT export_${PROJECT_NAME} - DESTINATION lib/${PROJECT_NAME}) - -install(DIRECTORY - launch - DESTINATION share/${PROJECT_NAME}/) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/example_nodes/launch/sandboxed_cpu_hog.launch.py b/example_nodes/launch/sandboxed_cpu_hog.launch.py deleted file mode 100644 index c47307b..0000000 --- a/example_nodes/launch/sandboxed_cpu_hog.launch.py +++ /dev/null @@ -1,72 +0,0 @@ -# Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -""" -This launchfile demonstrates resource limitations on sandboxed nodes. - -It spins up a program that tries to fork 32 simultaneous processes that each take up as much -CPU time as possible. -However, due to the constraints put on this node by the sandbox, it is not able to significantly -disrupt the performance of the navigation demo. - -For more details please see the launch_ros_sandbox project at -https://github.com/aws-robotics/launch-ros-sandbox - -For more information on configurable resource limits, see the `docker run` documentation -https://docs.docker.com/engine/reference/run/#runtime-constraints-on-resources -""" -from launch import LaunchDescription - -from launch_ros_sandbox.actions import SandboxedNodeContainer -from launch_ros_sandbox.descriptions import DockerPolicy -from launch_ros_sandbox.descriptions import SandboxedNode - - -def generate_launch_description(): - ld = LaunchDescription() - ld.add_action( - SandboxedNodeContainer( - sandbox_name='my_sandbox', - policy=DockerPolicy( - tag='latest', - repository='rosswg/turtlebot3_demo', - container_name='sandboxed-cpu-hog', - run_args={ - # CPU quota, in microseconds per scheduler period. - # The default scheduler period is 100ms == 100000us - # Therefore the below value of 200000us limits this container to using, - # at most, 2 cpu cores' worth of processing - 'cpu_period': 100000, - 'cpu_quota': 200000, - }, - entrypoint='/ros_entrypoint.sh', - ), - node_descriptions=[ - SandboxedNode( - package='example_nodes', - node_executable='cpu_hog', - ), - ] - ) - ) - - return ld - - -if __name__ == '__main__': - import sys - from launch import LaunchService - ls = LaunchService(argv=sys.argv[1:], debug=True) - ls.include_launch_description(generate_launch_description()) - sys.exit(ls.run()) diff --git a/example_nodes/package.xml b/example_nodes/package.xml deleted file mode 100644 index d261995..0000000 --- a/example_nodes/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - example_nodes - 0.0.0 - Example nodes for the ROSCon 2019 security workshop - AWS RoboMaker - Apache 2.0 - - ament_cmake - - rcutils - - launch_ros_sandbox - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/example_nodes/src/cpu_hog.cpp b/example_nodes/src/cpu_hog.cpp deleted file mode 100644 index f9808ce..0000000 --- a/example_nodes/src/cpu_hog.cpp +++ /dev/null @@ -1,99 +0,0 @@ -// Copyright 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved. -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "rcutils/logging_macros.h" - -/* Fork some threads to hog the CPU */ -int start_hogs(uint forks) -{ - int pid, retval = 0; - uint i; - double d; - - for (i = 0; forks == 0 || i < forks; i++) { - switch (pid = fork()) { - case 0: // If I'm the child fork - // Use a backoff sleep to ensure we get good fork throughput. - usleep(3000); - - // Do meaningless work! - while (1) { - d = sqrt(std::rand()); - } - // This case never falls through, it works forever (until parent is exited) - case -1: - RCUTILS_LOG_ERROR("Worker fork failed."); - return 1; - default: - // I'm the parent fork - RCUTILS_LOG_INFO("--> Worker forked (%i)", pid); - } - } - (void) d; // For the linter - - // Wait for all child forks to exit - while (i) { - int status, ret; - - if ((pid = wait(&status)) > 0) { - if ((WIFEXITED(status)) != 0) { - if ((ret = WEXITSTATUS(status)) != 0) { - RCUTILS_LOG_INFO("Worker process %i exited %i", pid, ret); - retval += ret; - } else { - RCUTILS_LOG_INFO("<-- Worker exited (%i)", pid); - } - } else { - RCUTILS_LOG_INFO("<-- Worker signalled (%i)", pid); - } - - --i; - } else { - RCUTILS_LOG_INFO("wait() returned error: %s", strerror(errno)); - RCUTILS_LOG_ERROR("detected missing hogcpu worker children"); - ++retval; - break; - } - } - - return retval; -} - - -int main(int argc, char ** argv) -{ - int num_processes = 32; - if (argc == 2) { - num_processes = atoi(argv[1]); - } else if (argc > 2) { - RCUTILS_LOG_ERROR("Usage: cpu_hog [NUM_PROCESSES]"); - return 1; - } - if (num_processes <= 0) { - RCUTILS_LOG_ERROR("NUM_PROCESSES must be greater than 0"); - return 1; - } - RCUTILS_LOG_INFO("Forking %d cpu hogs", num_processes); - return start_hogs(num_processes); -} diff --git a/maps/map.pgm b/maps/map.pgm deleted file mode 100644 index 555a42e..0000000 Binary files a/maps/map.pgm and /dev/null differ diff --git a/maps/map.yaml b/maps/map.yaml deleted file mode 100644 index d8dd99d..0000000 --- a/maps/map.yaml +++ /dev/null @@ -1,7 +0,0 @@ -image: ./map.pgm -resolution: 0.050000 -origin: [-4.019254, -2.259888, 0.000000] -negate: 0 -occupied_thresh: 0.65 -free_thresh: 0.196 - diff --git a/overlay/overlay.repos b/overlay/overlay.repos new file mode 100644 index 0000000..7ab9b81 --- /dev/null +++ b/overlay/overlay.repos @@ -0,0 +1,21 @@ +repositories: + # rticommunity/rmw_connextdds: + # type: git + # url: https://github.com/rticommunity/rmw_connextdds.git + # version: master + # ROBOTIS-GIT/turtlebot3: + # type: git + # # url: https://github.com/ROBOTIS-GIT/turtlebot3.git + # # version: ros2 + # url: https://github.com/ruffsl/turtlebot3.git + # version: navigation2_simulation + # ROBOTIS-GIT/turtlebot3_msgs: + # type: git + # url: https://github.com/ROBOTIS-GIT/turtlebot3_msgs.git + # version: ros2 + # ROBOTIS-GIT/turtlebot3_simulations: + # type: git + # # url: https://github.com/ROBOTIS-GIT/turtlebot3_simulations.git + # # version: ros2 + # url: https://github.com/ruffsl/turtlebot3_simulations.git + # version: navigation2_simulation diff --git a/overlay/src/turtlebot3_demo/CMakeLists.txt b/overlay/src/turtlebot3_demo/CMakeLists.txt new file mode 100644 index 0000000..3f964a4 --- /dev/null +++ b/overlay/src/turtlebot3_demo/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 3.5) +project(turtlebot3_demo) +find_package(ament_cmake REQUIRED) +ament_package() \ No newline at end of file diff --git a/overlay/src/turtlebot3_demo/package.xml b/overlay/src/turtlebot3_demo/package.xml new file mode 100644 index 0000000..ba9b4c7 --- /dev/null +++ b/overlay/src/turtlebot3_demo/package.xml @@ -0,0 +1,31 @@ + + + + turtlebot3_demo + + 0.0.0 + + + ROS 2 packages for TurtleBot3 demo + + + Apache 2.0 + + https://github.com/ros-swg/turtlebot3_demo + https://github.com/ros-swg/turtlebot3_demo/issues + + Ruffin White + Ruffin White + Mikael Arguedas + + ament_cmake + + navigation2 + desktop + slam_toolbox + turtlebot3_simulations + + + ament_cmake + + \ No newline at end of file diff --git a/policies/common/lifecycle_node.xml b/policies/common/lifecycle_node.xml index 3c14bec..6dbe1c0 100644 --- a/policies/common/lifecycle_node.xml +++ b/policies/common/lifecycle_node.xml @@ -4,13 +4,13 @@ - ~change_state - ~get_available_states - ~get_available_transitions - ~get_state - ~get_transition_graph + ~/change_state + ~/get_available_states + ~/get_available_transitions + ~/get_state + ~/get_transition_graph - ~transition_event + ~/transition_event diff --git a/policies/common/node/parameters.xml b/policies/common/node/parameters.xml index f6ef2bb..dbed939 100644 --- a/policies/common/node/parameters.xml +++ b/policies/common/node/parameters.xml @@ -5,11 +5,11 @@ - ~describe_parameters - ~get_parameter_types - ~get_parameters - ~list_parameters - ~set_parameters - ~set_parameters_atomically + ~/describe_parameters + ~/get_parameter_types + ~/get_parameters + ~/list_parameters + ~/set_parameters + ~/set_parameters_atomically diff --git a/policies/tb3_gazebo_policy.xml b/policies/tb3_gazebo_policy.xml index 9c3d615..04aec40 100644 --- a/policies/tb3_gazebo_policy.xml +++ b/policies/tb3_gazebo_policy.xml @@ -1,914 +1,459 @@ - - - - - global_costmap/clear_entirely_global_costmap - - - parameter_events - rosout - - - parameter_events - - - - - local_costmap/clear_entirely_local_costmap - - - parameter_events - rosout - - - parameter_events - - - - - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - global_localization - request_nomotion_update - - - ~/transition_event - amcl_pose - parameter_events - particlecloud - rosout - - - clock - initialpose - map - parameter_events - tf - tf_static - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - tf - - - clock - parameter_events - scan - - - - - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - ~/transition_event - parameter_events - rosout - - - clock - parameter_events - - - - - ComputePathToPose - FollowPath - NavigateToPose - Spin - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - amcl_pose - odom - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - global_localization - - - parameter_events - rosout - - - parameter_events - - - - - NavigateToPose - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - move_base_simple/goal - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - finish_trajectory - start_trajectory - submap_query - write_state - - - constraint_list - landmark_poses_list - parameter_events - rosout - scan_matched_points2 - submap_list - tf - trajectory_node_list - - - clock - imu - odom - parameter_events - scan - tf - tf_static - - - - - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - cmd_vel - cost_cloud - ~/transition_event - evaluation - local_plan - marker - parameter_events - received_global_plan - rosout - transformed_global_plan - - - clock - odom - parameter_events - - - - - FollowPath - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - pause_physics - reset_simulation - reset_world - unpause_physics - - - clock - parameter_events - rosout - - - clock - parameter_events - - - - - clear_around_global_costmap - clear_entirely_global_costmap - clear_except_global_costmap - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - costmap - costmap_raw - costmap_updates - ~/transition_event - parameter_events - published_footprint - rosout - - - /clock - footprint - parameter_events - /map - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - /clock - parameter_events - /scan - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - ~/shutdown - ~/startup - - - parameter_events - rosout - - - clock - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - amcl/change_state - amcl/get_state - bt_navigator/change_state - bt_navigator/get_state - dwb_controller/change_state - dwb_controller/get_state - map_server/change_state - map_server/get_state - navfn_planner/change_state - navfn_planner/get_state - world_model/change_state - world_model/get_state - - - parameter_events - rosout - - - parameter_events - - - - - clear_around_local_costmap - clear_entirely_local_costmap - clear_except_local_costmap - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - costmap - costmap_raw - costmap_updates - ~/transition_event - parameter_events - published_footprint - rosout - - - /clock - footprint - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - /clock - parameter_events - /scan - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - map - parameter_events - - - - - map - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - map - ~/transition_event - parameter_events - rosout - - - clock - parameter_events - - - - - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - endpoints - ~/transition_event - parameter_events - plan - rosout - - - clock - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - GetCostmap - - - parameter_events - rosout - - - clock - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - GetRobotPose - - - parameter_events - rosout - - - parameter_events - - - - - ComputePathToPose - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - parameter_events - - - - - NavigateToPose - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - clock - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - submap_query - - - map - parameter_events - rosout - - - clock - parameter_events - submap_list - - - - - BackUp - Spin - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - cmd_vel - parameter_events - rosout - - - amcl_pose - clock - global_costmap/costmap_raw - global_costmap/published_footprint - odom - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - GetRobotPose - - - parameter_events - rosout - - - clock - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - robot_description - rosout - tf - tf_static - - - clock - joint_states - parameter_events - - - - - NavigateToPose - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - lifecycle_manager/shutdown - lifecycle_manager/startup - - - clicked_point - initialpose - goal - parameter_events - rosout - - - clock - constraint_list - endpoints - endpoints_array - global_costmap/costmap - global_costmap/costmap_updates - landmark_poses_list - local_costmap/costmap - local_costmap/costmap_updates - local_costmap/published_footprint - local_plan - map - map_updates - marker - mobile_base/sensors/bumper_pointcloud - parameter_events - particlecloud - plan - robot_description - scan - scan_matched_points2 - tf - tf_static - trajectory_node_list - visualization_marker_array - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - cmd_vel - parameter_events - rosout - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - - - parameter_events - tf - tf_static - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - odom - parameter_events - rosout - tf - - - clock - cmd_vel - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - imu - parameter_events - rosout - - - clock - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - joint_states - parameter_events - rosout - - - clock - parameter_events - - - - - ~/describe_parameters - ~/get_parameter_types - ~/get_parameters - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - scan - - - clock - parameter_events - - - - - GetCostmap - GetRobotPose - ~/change_state - ~/describe_parameters - ~/get_available_states - ~/get_available_transitions - ~/get_parameter_types - ~/get_parameters - ~/get_state - ~/get_transition_graph - ~/list_parameters - ~/set_parameters - ~/set_parameters_atomically - - - parameter_events - rosout - ~/transition_event - - - clock - parameter_events - - - + + + + + + + + * + + + * + + + + + + + + + + * + + + * + + + + + diff --git a/rti/.gitignore b/rti/.gitignore new file mode 100644 index 0000000..73d1538 --- /dev/null +++ b/rti/.gitignore @@ -0,0 +1,4 @@ +*.dat +*.rtipkg +*.run +*.tar.gz diff --git a/rti/NDDS_QOS_PROFILES.xml b/rti/NDDS_QOS_PROFILES.xml new file mode 100644 index 0000000..7fc45d5 --- /dev/null +++ b/rti/NDDS_QOS_PROFILES.xml @@ -0,0 +1,43 @@ + + + + + + ALL + ALL + TIMESTAMPED + /tmp/log.xml + + + + + 65535 + + + + + dds.transport.UDPv4.builtin.parent.message_size_max + 65535 + + + dds.transport.UDPv4.builtin.send_socket_buffer_size + 65535 + + + dds.transport.UDPv4.builtin.recv_socket_buffer_size + 65535 + + + dds.transport.shmem.builtin.parent.message_size_max + 65535 + + + dds.transport.shmem.builtin.receive_buffer_size + 65535 + + + + + + +