Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

remove use_mock_hardware from moveit launchfile #853

Closed
wants to merge 7 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 1 addition & 2 deletions ur_moveit_config/config/controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,10 @@ controller_names:
- scaled_joint_trajectory_controller
- joint_trajectory_controller


scaled_joint_trajectory_controller:
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
default: false
joints:
- shoulder_pan_joint
- shoulder_lift_joint
Expand Down
93 changes: 9 additions & 84 deletions ur_moveit_config/launch/ur_moveit.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,8 @@
def launch_setup(context, *args, **kwargs):
# Initialize Arguments
ur_type = LaunchConfiguration("ur_type")
use_mock_hardware = LaunchConfiguration("use_mock_hardware")
safety_limits = LaunchConfiguration("safety_limits")
safety_pos_margin = LaunchConfiguration("safety_pos_margin")
safety_k_position = LaunchConfiguration("safety_k_position")
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
# General arguments
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
moveit_config_package = LaunchConfiguration("moveit_config_package")
moveit_joint_limits_file = LaunchConfiguration("moveit_joint_limits_file")
moveit_config_file = LaunchConfiguration("moveit_config_file")
Expand All @@ -59,68 +54,6 @@ def launch_setup(context, *args, **kwargs):
use_sim_time = LaunchConfiguration("use_sim_time")
launch_rviz = LaunchConfiguration("launch_rviz")
launch_servo = LaunchConfiguration("launch_servo")

joint_limit_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"]
)
kinematics_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "default_kinematics.yaml"]
)
physical_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "physical_parameters.yaml"]
)
visual_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "visual_parameters.yaml"]
)

robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution([FindPackageShare(description_package), "urdf", description_file]),
" ",
"robot_ip:=xxx.yyy.zzz.www",
" ",
"joint_limit_params:=",
joint_limit_params,
" ",
"kinematics_params:=",
kinematics_params,
" ",
"physical_params:=",
physical_params,
" ",
"visual_params:=",
visual_params,
" ",
"safety_limits:=",
safety_limits,
" ",
"safety_pos_margin:=",
safety_pos_margin,
" ",
"safety_k_position:=",
safety_k_position,
" ",
"name:=",
"ur",
" ",
"ur_type:=",
ur_type,
" ",
"script_filename:=ros_control.urscript",
" ",
"input_recipe_filename:=rtde_input_recipe.txt",
" ",
"output_recipe_filename:=rtde_output_recipe.txt",
" ",
"prefix:=",
prefix,
" ",
]
)
robot_description = {"robot_description": robot_description_content}

# MoveIt Configuration
robot_description_semantic_content = Command(
[
Expand All @@ -131,9 +64,7 @@ def launch_setup(context, *args, **kwargs):
),
" ",
"name:=",
# Also ur_type parameter could be used but then the planning group names in yaml
# configs has to be updated!
"ur",
ur_type,
" ",
"prefix:=",
prefix,
Expand Down Expand Up @@ -166,11 +97,8 @@ def launch_setup(context, *args, **kwargs):

# Trajectory Execution Configuration
controllers_yaml = load_yaml("ur_moveit_config", "config/controllers.yaml")
# the scaled_joint_trajectory_controller does not work on mock hardware
change_controllers = context.perform_substitution(use_mock_hardware)
if change_controllers == "true":
controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False
controllers_yaml["joint_trajectory_controller"]["default"] = True
initial_controller = context.perform_substitution(initial_joint_controller)
controllers_yaml[initial_controller]["default"] = True

moveit_controllers = {
"moveit_simple_controller_manager": controllers_yaml,
Expand All @@ -183,7 +111,6 @@ def launch_setup(context, *args, **kwargs):
"trajectory_execution.allowed_goal_duration_margin": 0.5,
"trajectory_execution.allowed_start_tolerance": 0.01,
}

planning_scene_monitor_parameters = {
"publish_planning_scene": True,
"publish_geometry_updates": True,
Expand All @@ -202,7 +129,6 @@ def launch_setup(context, *args, **kwargs):
executable="move_group",
output="screen",
parameters=[
robot_description,
robot_description_semantic,
robot_description_kinematics,
robot_description_planning,
Expand All @@ -227,7 +153,6 @@ def launch_setup(context, *args, **kwargs):
output="log",
arguments=["-d", rviz_config_file],
parameters=[
robot_description,
robot_description_semantic,
ompl_planning_pipeline_config,
robot_description_kinematics,
Expand All @@ -245,7 +170,6 @@ def launch_setup(context, *args, **kwargs):
executable="servo_node_main",
parameters=[
servo_params,
robot_description,
robot_description_semantic,
],
output="screen",
Expand All @@ -258,7 +182,7 @@ def launch_setup(context, *args, **kwargs):

def generate_launch_description():
declared_arguments = []
# UR specific arguments
# UR specific arguments.
declared_arguments.append(
DeclareLaunchArgument(
"ur_type",
Expand All @@ -268,9 +192,10 @@ def generate_launch_description():
)
declared_arguments.append(
DeclareLaunchArgument(
"use_mock_hardware",
default_value="false",
description="Indicate whether robot is running with mock hardware mirroring command to its states.",
"initial_joint_controller",
default_value="scaled_joint_trajectory_controller",
description="Initial controller used by MoveIt!.",
choices=["scaled_joint_trajectory_controller", "joint_trajectory_controller"],
)
)
declared_arguments.append(
Expand Down
4 changes: 1 addition & 3 deletions ur_moveit_config/srdf/ur.srdf.xacro
Original file line number Diff line number Diff line change
@@ -1,13 +1,11 @@
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="$(arg name)">

<!-- robot name parameter -->
<xacro:arg name="name" default="ur"/>
<!-- parameters -->
<xacro:arg name="prefix" default="" />

<xacro:include filename="$(find ur_moveit_config)/srdf/ur_macro.srdf.xacro"/>

<xacro:ur_srdf name="$(arg name)" prefix="$(arg prefix)"/>
<xacro:ur_srdf prefix="$(arg prefix)"/>

</robot>
10 changes: 5 additions & 5 deletions ur_moveit_config/srdf/ur_macro.srdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,33 +4,33 @@
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<xacro:macro name="ur_srdf" params="name prefix">
<xacro:macro name="ur_srdf" params="prefix">
<!--GROUPS - Representation of a set of joints and links. This can be useful for specifying DOF to plan for, defining arms, end effectors, etc-->
<!--LINKS - When a link is specified, the parent joint of that link (if it exists) is automatically included-->
<!--JOINTS - When a joint is specified, the child link of that joint (which will always exist) is automatically included-->
<!--CHAINS - When a chain is specified, all the links along the chain (including endpoints) are included in the group. Additionally, all the joints that are parents to included links are also included. This means that joints along the chain and the parent joint of the base link are included in the group-->
<!--SUBGROUPS - Groups can also be formed by referencing to already defined group names-->
<group name="${prefix}${name}_manipulator">
<group name="${prefix}ur_manipulator">
<chain base_link="${prefix}base_link" tip_link="${prefix}tool0" />
</group>
<!--GROUP STATES - Purpose - Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_state name="${prefix}home" group="${prefix}${name}_manipulator">
<group_state name="${prefix}home" group="${prefix}ur_manipulator">
<joint name="${prefix}elbow_joint" value="0" />
<joint name="${prefix}shoulder_lift_joint" value="-1.5707" />
<joint name="${prefix}shoulder_pan_joint" value="0" />
<joint name="${prefix}wrist_1_joint" value="0" />
<joint name="${prefix}wrist_2_joint" value="0" />
<joint name="${prefix}wrist_3_joint" value="0" />
</group_state>
<group_state name="${prefix}up" group="${prefix}${name}_manipulator">
<group_state name="${prefix}up" group="${prefix}ur_manipulator">
<joint name="${prefix}elbow_joint" value="0" />
<joint name="${prefix}shoulder_lift_joint" value="-1.5707" />
<joint name="${prefix}shoulder_pan_joint" value="0" />
<joint name="${prefix}wrist_1_joint" value="-1.5707" />
<joint name="${prefix}wrist_2_joint" value="0" />
<joint name="${prefix}wrist_3_joint" value="0" />
</group_state>
<group_state name="${prefix}test_configuration" group="${prefix}${name}_manipulator">
<group_state name="${prefix}test_configuration" group="${prefix}ur_manipulator">
<joint name="${prefix}elbow_joint" value="1.4" />
<joint name="${prefix}shoulder_lift_joint" value="-1.62" />
<joint name="${prefix}shoulder_pan_joint" value="1.54" />
Expand Down
14 changes: 9 additions & 5 deletions ur_robot_driver/doc/usage.rst
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ outside of this driver's scope.
* - mode
- available controllers
* - mock_hardware
- :raw-html-m2r:`<ul><li>joint_trajectory_controller</li><li>forward_velocity_controller</li><li>forward_position_controller</li></ul>`
- :raw-html-m2r:`<ul><li>joint_trajectory_controller</li><li>scaled_joint_trajectory_controller </li><li>forward_velocity_controller</li><li>forward_position_controller</li></ul>`
* - real hardware / URSim
- :raw-html-m2r:`<ul><li>joint_trajectory_controller</li><li>scaled_joint_trajectory_controller </li><li>forward_velocity_controller</li><li>forward_position_controller</li></ul>`

Expand Down Expand Up @@ -194,14 +194,18 @@ robot as explained `here <https://moveit.picknik.ai/galactic/doc/tutorials/quick
Mock hardware
^^^^^^^^^^^^^

Currently, the ``scaled_joint_trajectory_controller`` does not work with ros2_control mock_hardware. There is an
`upstream Merge-Request <https://github.com/ros-controls/ros2_control/pull/822>`_ pending to fix that. Until this is merged and released, you'll have to fallback to the ``joint_trajectory_controller`` by passing ``initial_controller:=joint_trajectory_controller`` to the driver's startup. Also, you'll have to tell MoveIt! that you're using mock_hardware as it then has to map to the other controller:
To test the driver on mock hardware with the example MoveIt-setup, first start the driver as described
`above <#start-hardware-simulator-or-mockup>`_.

.. code-block::

ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=yyy.yyy.yyy.yyy use_mock_hardware:=true launch_rviz:=false initial_joint_controller:=joint_trajectory_controller
ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=yyy.yyy.yyy.yyy use_mock_hardware:=true launch_rviz:=false
# and in another shell
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5e launch_rviz:=true use_mock_hardware:=true
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5e launch_rviz:=true

Now you should be able to use the MoveIt Plugin in rviz2 to plan and execute trajectories with the
robot as explained `in the MoveIt! documentation <https://moveit.picknik.ai/galactic/doc/tutorials/quickstart_in_rviz/quickstart_in_rviz_tutorial.html>`_.


Robot frames
------------
Expand Down