Skip to content

Commit 7dd61ae

Browse files
committed
REVERT_ME: Default to passthrough controller
1 parent 868f240 commit 7dd61ae

File tree

2 files changed

+4
-2
lines changed

2 files changed

+4
-2
lines changed

ur_moveit_config/config/moveit_controllers.yaml

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,11 @@ trajectory_execution:
1010
moveit_simple_controller_manager:
1111
controller_names:
1212
- scaled_joint_trajectory_controller
13+
- passthrough_trajectory_controller
1314
- joint_trajectory_controller
1415

15-
scaled_joint_trajectory_controller:
16+
#scaled_joint_trajectory_controller:
17+
passthrough_trajectory_controller:
1618
action_ns: follow_joint_trajectory
1719
type: FollowJointTrajectory
1820
default: true

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -337,7 +337,7 @@ def generate_launch_description():
337337
declared_arguments.append(
338338
DeclareLaunchArgument(
339339
"initial_joint_controller",
340-
default_value="scaled_joint_trajectory_controller",
340+
default_value="passthrough_trajectory_controller",
341341
choices=[
342342
"scaled_joint_trajectory_controller",
343343
"joint_trajectory_controller",

0 commit comments

Comments
 (0)