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 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 0 additions & 15 deletions ur_moveit_config/config/controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,5 @@
controller_names:
- scaled_joint_trajectory_controller
- joint_trajectory_controller


scaled_joint_trajectory_controller:
action_ns: follow_joint_trajectory
Expand All @@ -14,16 +12,3 @@ scaled_joint_trajectory_controller:
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint


joint_trajectory_controller:
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: false
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
13 changes: 0 additions & 13 deletions ur_moveit_config/launch/ur_moveit.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,6 @@
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")
Expand Down Expand Up @@ -166,11 +165,6 @@ 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

moveit_controllers = {
"moveit_simple_controller_manager": controllers_yaml,
Expand Down Expand Up @@ -266,13 +260,6 @@ def generate_launch_description():
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"],
)
)
declared_arguments.append(
DeclareLaunchArgument(
"use_mock_hardware",
default_value="false",
description="Indicate whether robot is running with mock hardware mirroring command to its states.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"safety_limits",
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 `here <https://moveit.picknik.ai/galactic/doc/tutorials/quickstart_in_rviz/quickstart_in_rviz_tutorial.html>`_.
fmauch marked this conversation as resolved.
Show resolved Hide resolved


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