Skip to content
This repository has been archived by the owner on Dec 13, 2024. It is now read-only.

Commit

Permalink
Remove usage of YAML variable interpolators (#300)
Browse files Browse the repository at this point in the history
* Prep for deprecation of interpolating env variables into YAML

* update comment

* Remove `%>>` expressions

* Remove deprecated fields in config.yaml (#315)

---------

Co-authored-by: Abishalini Sivaraman <[email protected]>
  • Loading branch information
EzraBrooks and Abishalini authored Jul 22, 2024
1 parent 1934127 commit 40976e1
Show file tree
Hide file tree
Showing 8 changed files with 29 additions and 93 deletions.
50 changes: 8 additions & 42 deletions src/picknik_ur_base_config/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,17 +7,10 @@
# Baseline hardware configuration parameters for MoveIt Pro.
# [Required]
hardware:
# Used by the ur_description package to set kinematics and geometry for a specific robot type.
# You can change this to another UR model but you must update any configuration affected by the different arm size.
# UR models in the ur_description package are ur3, ur3e, ur5, ur5e, ur10, ur10e, and ur16e.
# [Required]
type: ${UR_HARDWARE_TYPE:-ur5e}

# Set simulated to false if you are using this as a configuration for real hardware.
# Override-able by setting the $MOCK_HARDWARE environment variable to 'True'.
# This allows users to switch between mock and real hardware using the same configuration.
# This allows users to switch between mock and real hardware by changing a single parameter with config inheritance.
# [Required]
simulated: ${MOCK_HARDWARE:-true}
simulated: true

# If the MoveIt Pro Agent should launch the ros2 controller node.
# [Optional, default=True]
Expand All @@ -28,18 +21,11 @@ hardware:
# [Optional, default=True]
launch_robot_state_publisher: True

# The robot's IP address.
# [Required]
ip: "0.0.0.0"

# Specify additional launch files for running the robot with real hardware.
# [Optional, defaults to a blank launch file if not specified]
robot_driver_persist_launch_file:
package: "picknik_ur_base_config"
path: "launch/robot_drivers_to_persist.launch.py"
hardware_launch_file:
package: "moveit_studio_agent"
path: "launch/blank.launch.py"

# Specify any additional launch files for running the robot in simulation mode.
# Used when hardware.simulated is True.
Expand All @@ -65,13 +51,13 @@ hardware:
# Many of these are specific to the UR descriptions packages, and can be customized as needed.
# [Optional]
urdf_params:
- name: "%>> hardware.type"
- name: "ur5e"
- prefix: ""
- use_fake_hardware: "%>> hardware.simulated"
- use_fake_hardware: "true"
- use_pinch_links: "true"
- fake_sensor_commands: "false"
- headless_mode: "true"
- robot_ip: "%>> hardware.ip"
- robot_ip: "0.0.0.0"
- joint_limits_parameters_file:
package: "picknik_ur_base_config"
path: "config/moveit/joint_limits.yaml"
Expand All @@ -81,15 +67,15 @@ hardware:
- kinematics_parameters_file:
# Load default_kinematics.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/default_kinematics.yaml"
path: "config/ur5e/default_kinematics.yaml"
- physical_parameters_file:
# Load physical_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/physical_parameters.yaml"
path: "config/ur5e/physical_parameters.yaml"
- visual_parameters_file:
# Load visual_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/visual_parameters.yaml"
path: "config/ur5e/visual_parameters.yaml"

# Sets ROS global params for launch.
# [Optional]
Expand All @@ -98,13 +84,6 @@ ros_global_params:
# [Optional, default=False]
use_sim_time: False

# Configure additional, optional features in MoveIt Pro.
# [Optional]
optional_feature_params:
# Whether or not to use the Formant bridge for over-the-internet comms.
# [Optional, default=False]
use_formant_bridge: False
# Configuration files for MoveIt.
# For more information, refer to https://moveit.picknik.ai/main/doc/how_to_guides/moveit_configuration/moveit_configuration_tutorial.html
# [Required]
Expand Down Expand Up @@ -155,13 +134,6 @@ moveit_params:
allowed_goal_duration_margin: 5.0
allowed_start_tolerance: 0.01

# Additional configurable parameters for the MoveIt Pro user interface.
# [Required]
ui_params:
# By default, we use a frame named "grasp_link" for tool grasp pose rendering and planning.
# [Required]
servo_endpoint_frame_id: "grasp_link"
# Configuration for launching ros2_control processes.
# [Required, if using ros2_control]
ros2_control:
Expand Down Expand Up @@ -192,12 +164,6 @@ ros2_control:
# [Optional, default=[]]
controller_shared_topics: []

# Octomap manager configuration parameters
octomap_manager:
# Input point cloud topic name. The *output* point cloud topic published by
# the Octomap manager node is defined in sensors_3d.yaml.
input_point_cloud_topic: "/wrist_mounted_camera/depth/color/points"
# Configuration for loading behaviors and objectives.
# [Required]
objectives:
Expand Down
32 changes: 8 additions & 24 deletions src/picknik_ur_gazebo_config/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,21 +6,16 @@
based_on_package: "picknik_ur_site_config"

# Optional parameters that can be read in your launch files for specific functionality
optional_feature_params:
gazebo_world_name: "space_station_blocks_world.sdf"
gazebo_gui: False
gazebo_verbose: True
# optional_feature_params:
# gazebo_world_name: "space_station_blocks_world.sdf"
# gazebo_gui: False
# gazebo_verbose: True

# Enable simulation time so nodes are synced with the Gazebo block.
ros_global_params:
use_sim_time: True

hardware:
# Used by the ur_description package to set kinematics and geometry for a specific robot type.
# You can change this to another UR model but you must update any configuration affected by the different arm size
# UR models in the ur_description package are ur3, ur3e, ur5, ur5e, ur10, ur10e, and ur16e.
type: "ur5e"

# This is the only option for this site_config
simulated: True

Expand All @@ -31,9 +26,6 @@ hardware:
# This should be false if you are launching the robot state publisher as part of drivers.
launch_robot_state_publisher: True

# The robot's IP address
ip: "0.0.0.0"

# The following launch file is started when hardware.simulated is True
simulated_hardware_launch_file:
package: "picknik_ur_gazebo_config"
Expand All @@ -47,25 +39,22 @@ hardware:
package: "picknik_ur_gazebo_config"
path: "config/moveit/picknik_ur_gazebo.srdf.xacro"
urdf_params:
- name: "%>> hardware.type"
- name: "ur5e"
- gripper_name: "robotiq_85"
- use_pinch_links: "false"
- simulation: "gazebo"
# Using the ogre renderer as it is compatible with most host hardware.
# ogre2 (which is the Gazebo default) is also an option if your system supports it.
- gazebo_renderer: ${GAZEBO_RENDERER:-ogre}
- kinematics_parameters_file:
# Load default_kinematics.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/default_kinematics.yaml"
path: "config/ur5e/default_kinematics.yaml"
- physical_parameters_file:
# Load physical_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/physical_parameters.yaml"
path: "config/ur5e/physical_parameters.yaml"
- visual_parameters_file:
# Load visual_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/visual_parameters.yaml"
path: "config/ur5e/visual_parameters.yaml"

# Override MoveIt parameters
moveit_params:
Expand All @@ -76,11 +65,6 @@ moveit_params:
package: "picknik_ur_gazebo_config"
path: "config/moveit/ur_servo.yaml"

octomap_manager:
# Input point cloud topic name. The *output* point cloud topic published by
# the Octomap manager node is defined in sensors_3d.yaml.
input_point_cloud_topic: "/wrist_mounted_camera/depth/color/points"
# This configures what controllers gets run at startup
ros2_control:
controllers_active_at_startup:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@ def generate_simulation_description(context, *args, **settings):
)
use_gui = settings.get("gazebo_gui", False)
is_verbose = settings.get("gazebo_verbose", False)
gz_renderer = os.environ.get("GAZEBO_RENDERER", "ogre")

# Create a Gazebo world file that swaps out package:// paths with absolute path.
original_world_file = get_ros_path(
Expand All @@ -78,7 +77,7 @@ def generate_simulation_description(context, *args, **settings):
print(f"Starting Gazebo with world at {world_path}")
print(f"GUI: {use_gui}, Verbose: {is_verbose}")

sim_args = f"-r --render-engine {gz_renderer}"
sim_args = "-r --render-engine ogre"
if is_verbose:
sim_args += " -v 4"
if not use_gui:
Expand Down
3 changes: 0 additions & 3 deletions src/picknik_ur_mock_hw_config/config/config.yaml
Original file line number Diff line number Diff line change
@@ -1,9 +1,6 @@
based_on_package: "picknik_ur_base_config"

hardware:

# Be sure to set your robot's IP address.
ip: "0.0.0.0"
simulated: True

# Update robot description for machine tending world.
Expand Down
15 changes: 7 additions & 8 deletions src/picknik_ur_multi_arm_config/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,9 @@ hardware:
type: ur5e

# Set simulated to false if you are using this as a configuration for real hardware.
# Override-able by setting the $MOCK_HARDWARE environment variable to 'True'.
# This allows users to switch between mock and real hardware using the same configuration.
# This allows users to switch between mock and real hardware by changing a single parameter with config inheritance.
# [Required]
simulated: ${MOCK_HARDWARE:-true}
simulated: true

# If the MoveIt Pro Agent should launch the ros2 controller node.
# [Optional, default=True]
Expand Down Expand Up @@ -61,11 +60,11 @@ hardware:
urdf_params:
- name: "multi_arm_ur"
- prefix: ""
- use_fake_hardware: "%>> hardware.simulated"
- use_fake_hardware: "true"
- use_pinch_links: "true"
- fake_sensor_commands: "false"
- headless_mode: "true"
- robot_ip: "%>> hardware.ip"
- robot_ip: "0.0.0.0"
- joint_limits_parameters_file:
package: "picknik_ur_base_config"
path: "config/moveit/joint_limits.yaml"
Expand All @@ -75,15 +74,15 @@ hardware:
- kinematics_parameters_file:
# Load default_kinematics.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/default_kinematics.yaml"
path: "config/ur5e/default_kinematics.yaml"
- physical_parameters_file:
# Load physical_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/physical_parameters.yaml"
path: "config/ur5e/physical_parameters.yaml"
- visual_parameters_file:
# Load visual_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/visual_parameters.yaml"
path: "config/ur5e/visual_parameters.yaml"
# Set advanced camera settings to improve point cloud accuracy
json_file_path:
package: "picknik_ur_base_config"
Expand Down
11 changes: 4 additions & 7 deletions src/picknik_ur_multi_arm_gazebo_config/config/config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -67,12 +67,9 @@ hardware:
- gripper_name: "robotiq_85"
- use_pinch_links: "true"
- simulation: "gazebo"
# Using the ogre renderer as it is compatible with most host hardware.
# ogre2 (which is the Gazebo default) is also an option if your system supports it.
- gazebo_renderer: ${GAZEBO_RENDERER:-ogre}
- fake_sensor_commands: "false"
- headless_mode: "true"
- robot_ip: "%>> hardware.ip"
- robot_ip: "0.0.0.0"
- joint_limits_parameters_file:
package: "picknik_ur_base_config"
path: "config/moveit/joint_limits.yaml"
Expand All @@ -82,15 +79,15 @@ hardware:
- kinematics_parameters_file:
# Load default_kinematics.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/default_kinematics.yaml"
path: "config/ur5e/default_kinematics.yaml"
- physical_parameters_file:
# Load physical_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/physical_parameters.yaml"
path: "config/ur5e/physical_parameters.yaml"
- visual_parameters_file:
# Load visual_parameters.yaml from ur_description/config/<ur_type>
package: "ur_description"
path: "config/%>> hardware.type <<%/visual_parameters.yaml"
path: "config/ur5e/visual_parameters.yaml"

# Sets ROS global params for launch.
# [Optional]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,6 @@ def generate_simulation_description(context, *args, **settings):
)
use_gui = settings.get("gazebo_gui", False)
is_verbose = settings.get("gazebo_verbose", False)
gz_renderer = os.environ.get("GAZEBO_RENDERER", "ogre")

# Create a Gazebo world file that swaps out package:// paths with absolute path.
original_world_file = get_ros_path(
Expand All @@ -78,7 +77,7 @@ def generate_simulation_description(context, *args, **settings):
print(f"Starting Gazebo with world at {world_path}")
print(f"GUI: {use_gui}, Verbose: {is_verbose}")

sim_args = f"-r --render-engine {gz_renderer}"
sim_args = "-r --render-engine ogre"
if is_verbose:
sim_args += " -v 4"
if not use_gui:
Expand Down
5 changes: 0 additions & 5 deletions src/picknik_ur_site_config/config/config.yaml
Original file line number Diff line number Diff line change
@@ -1,10 +1,5 @@
based_on_package: "picknik_ur_base_config"

hardware:

# Be sure to set your robot's IP address.
ip: "0.0.0.0"

objectives:
behavior_loader_plugins: {}
objective_library_paths:
Expand Down

0 comments on commit 40976e1

Please sign in to comment.