Skip to content

Commit

Permalink
Merge pull request #2 from mikaelarguedas/refine_policies_round1
Browse files Browse the repository at this point in the history
update access control policies
  • Loading branch information
mikaelarguedas authored Aug 3, 2019
2 parents 6072f2e + 0f53a1d commit f793598
Show file tree
Hide file tree
Showing 7 changed files with 215 additions and 576 deletions.
50 changes: 6 additions & 44 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -85,52 +85,13 @@ All the artifacts will be placed in `<OVERLAY_WORKSPACE>/keystore`
```bash
source <OVERLAY_WORKSPACE>/install/setup.bash
cd <OVERLAY_WORKSPACE>
ros2 security generate_artifacts -k keystore -n \
/_client_node \
/_ros2cli \
/amcl \
/amcl_rclcpp_node \
/bt_navigator \
/bt_navigator_client_node \
/bt_navigator_global_localization_client \
/bt_navigator_rclcpp_node \
/dwb_controller \
/dwb_controller_rclcpp_node \
/gazebo \
/global_costmap \
/global_costmap/global_costmap \
/global_costmap/global_costmap_rclcpp_node \
/global_costmap_client \
/global_localization \
/launch_ros \
/lifecycle_manager \
/lifecycle_managerservice_client \
/local_costmap \
/local_costmap/local_costmap \
/local_costmap/local_costmap_rclcpp_node \
/local_costmap_client \
/map_server \
/navfn_planner \
/navfn_planner_GetCostmap_client \
/navfn_planner_GetRobotPose_client \
/navfn_planner_rclcpp_node \
/navigation_dialog_action_client \
/recoveries \
/recovery_GetRobotPose_client \
/robot_state_publisher \
/rviz2 \
/transform_listener_impl \
/turtlebot3_diff_drive \
/turtlebot3_imu \
/turtlebot3_joint_state \
/turtlebot3_laserscan \
/world_model
export DEMO_POLICY_FILE="<TB3_DEMO_REPO>/policies/tb3_gazebo_policy.xml"
ros2 security generate_artifacts -k keystore \
-n \
/_client_node \
-p `DEMO_POLICY_FILE`
```

<!--
ros2 security generate_artifacts -k keystore -p <PATH_TO_POLICY_FILE>
-->

#### Setup the environment to use security

To notify ROS 2 that we want ot use DDS-Security, we use environment variables
Expand All @@ -139,6 +100,7 @@ Run these commands in shell 1 and 4 for the navigation demo.
export ROS_SECURITY_ENABLE=true
export ROS_SECURITY_STRATEGY=Enforce
export ROS_SECURITY_ROOT_DIRECTORY=<OVERLAY_WORKSPACE>/keystore
export ROS_SECURITY_LOOKUP_TYPE=MATCH_PREFIX
```

Then refer to steps described in "Navigating a known map"
16 changes: 16 additions & 0 deletions policies/common/lifecycle_node.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0" encoding="UTF-8"?>

<profile xmlns:xi="http://www.w3.org/2003/XInclude">
<xi:include href="node.xml"
xpointer="xpointer(/profile/*)"/>
<services reply="ALLOW">
<service>~change_state</service>
<service>~get_available_states</service>
<service>~get_available_transitions</service>
<service>~get_state</service>
<service>~get_transition_graph</service>
</services>
<topics publish="ALLOW">
<topic>~transition_event</topic>
</topics>
</profile>
9 changes: 9 additions & 0 deletions policies/common/node.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<?xml version="1.0" encoding="UTF-8"?>
<profile xmlns:xi="http://www.w3.org/2003/XInclude">
<xi:include href="node/logging.xml"
xpointer="xpointer(/profile/*)"/>
<xi:include href="node/time.xml"
xpointer="xpointer(/profile/*)"/>
<xi:include href="node/parameters.xml"
xpointer="xpointer(/profile/*)"/>
</profile>
6 changes: 6 additions & 0 deletions policies/common/node/logging.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<profile>
<topics publish="ALLOW" >
<topic>rosout</topic>
</topics>
</profile>
15 changes: 15 additions & 0 deletions policies/common/node/parameters.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<?xml version="1.0" encoding="UTF-8"?>
<profile>
<topics publish="ALLOW" subscribe="ALLOW" >
<topic>parameter_events</topic>
</topics>

<services reply="ALLOW" request="ALLOW" >
<service>~describe_parameters</service>
<service>~get_parameter_types</service>
<service>~get_parameters</service>
<service>~list_parameters</service>
<service>~set_parameters</service>
<service>~set_parameters_atomically</service>
</services>
</profile>
6 changes: 6 additions & 0 deletions policies/common/node/time.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<profile>
<topics subscribe="ALLOW" >
<topic>/clock</topic>
</topics>
</profile>
Loading

0 comments on commit f793598

Please sign in to comment.