diff --git a/Dockerfile b/Dockerfile
index 73d55590..8006e4e0 100644
--- a/Dockerfile
+++ b/Dockerfile
@@ -119,10 +119,6 @@ ENV USER_WS=${USER_WS}
# Compile the workspace
WORKDIR $USER_WS
-# hadolint ignore=SC1091
-RUN --mount=type=cache,target=/home/${USERNAME}/.ccache \
- . /opt/overlay_ws/install/setup.sh && \
- colcon build
# Set up the user's .bashrc file and shell.
CMD ["/usr/bin/bash"]
diff --git a/docker-compose.yaml b/docker-compose.yaml
index ce0be75c..2c94baf9 100644
--- a/docker-compose.yaml
+++ b/docker-compose.yaml
@@ -14,7 +14,7 @@ services:
target: user-overlay
args:
- USER_UID=${STUDIO_USER_UID:-1000}
- - USER_GID=${STUDIO_USER_UID:-1000}
+ - USER_GID=${STUDIO_USER_GID:-1000}
- USERNAME=${STUDIO_USERNAME:-studio-user}
- MOVEIT_STUDIO_BASE_IMAGE=picknikciuser/moveit-studio:${STUDIO_DOCKER_TAG:-main}
diff --git a/src/arm_on_rail_sim/config/moveit/hard_joint_limits.yaml b/src/arm_on_rail_sim/config/moveit/hard_joint_limits.yaml
index 60ddbf2c..53b218df 100644
--- a/src/arm_on_rail_sim/config/moveit/hard_joint_limits.yaml
+++ b/src/arm_on_rail_sim/config/moveit/hard_joint_limits.yaml
@@ -15,7 +15,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
- max_acceleration: 0.1
+ max_acceleration: 10.0
max_effort: 150.0
max_position: 2.9
max_velocity: 0.175
@@ -25,7 +25,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
- max_acceleration: !degrees 90.0
+ max_acceleration: !degrees 180.0
max_effort: 150.0
max_position: !degrees 180.0
max_velocity: !degrees 30.0
@@ -35,7 +35,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
- max_acceleration: !degrees 90.0
+ max_acceleration: !degrees 180.0
max_effort: 150.0
max_position: !degrees 90.0
max_velocity: !degrees 30.0
@@ -45,7 +45,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
- max_acceleration: !degrees 90.0
+ max_acceleration: !degrees 180.0
max_effort: 150.0
# we artificially limit this joint to half its actual joint position limit
# to avoid (MoveIt/OMPL) planning problems, as due to the physical
@@ -65,7 +65,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
- max_acceleration: !degrees 90.0
+ max_acceleration: !degrees 180.0
max_effort: 28.0
max_position: !degrees 180.0
max_velocity: !degrees 60.0
diff --git a/src/arm_on_rail_sim/description/ur5e.xml b/src/arm_on_rail_sim/description/ur5e.xml
index 4e6f28c3..5970e239 100644
--- a/src/arm_on_rail_sim/description/ur5e.xml
+++ b/src/arm_on_rail_sim/description/ur5e.xml
@@ -11,8 +11,8 @@
gaintype="fixed"
biastype="affine"
ctrlrange="-6.2831 6.2831"
- gainprm="2000"
- biasprm="0 -2000 -400"
+ gainprm="20000"
+ biasprm="0 -20000 -1000"
forcerange="-150 150"
/>
@@ -22,7 +22,11 @@
-
+
diff --git a/src/external_dependencies/picknik_accessories b/src/external_dependencies/picknik_accessories
index fcdb1ff8..c8f11ba1 160000
--- a/src/external_dependencies/picknik_accessories
+++ b/src/external_dependencies/picknik_accessories
@@ -1 +1 @@
-Subproject commit fcdb1ff8b729c93dbd5f15a09c33098b32caeac5
+Subproject commit c8f11ba132ff65ea41c1fe1f2623e0ed56fa16dd
diff --git a/src/external_dependencies/picknik_registration b/src/external_dependencies/picknik_registration
index 5ce93428..220e5c96 160000
--- a/src/external_dependencies/picknik_registration
+++ b/src/external_dependencies/picknik_registration
@@ -1 +1 @@
-Subproject commit 5ce934289fddcdf84a13fc6b569d10c50a7f5da1
+Subproject commit 220e5c96aac04bf4879b4106f16238fee2a46825
diff --git a/src/external_dependencies/ros2_robotiq_gripper b/src/external_dependencies/ros2_robotiq_gripper
index 93ecde7f..2ff85455 160000
--- a/src/external_dependencies/ros2_robotiq_gripper
+++ b/src/external_dependencies/ros2_robotiq_gripper
@@ -1 +1 @@
-Subproject commit 93ecde7f66499d56e620d775eb984345889532aa
+Subproject commit 2ff85455d4b9f973c4b0bab1ce95fb09367f0d26
diff --git a/src/picknik_ur_base_config/launch/pro_rs_launch.py b/src/picknik_ur_base_config/launch/pro_rs_launch.py
index 685f5bde..7aaec2b2 100644
--- a/src/picknik_ur_base_config/launch/pro_rs_launch.py
+++ b/src/picknik_ur_base_config/launch/pro_rs_launch.py
@@ -56,5 +56,14 @@ def generate_launch_description():
)
return LaunchDescription(
rs_launch.declare_configurable_parameters(rs_launch.configurable_parameters)
- + [OpaqueFunction(function=rs_launch.launch_setup)]
+ + [
+ OpaqueFunction(
+ function=rs_launch.launch_setup,
+ kwargs={
+ "params": rs_launch.set_configurable_parameters(
+ rs_launch.configurable_parameters
+ )
+ },
+ )
+ ]
)
diff --git a/src/picknik_ur_base_config/objectives/request_teleoperation.xml b/src/picknik_ur_base_config/objectives/request_teleoperation.xml
index b34b6226..33c019f1 100644
--- a/src/picknik_ur_base_config/objectives/request_teleoperation.xml
+++ b/src/picknik_ur_base_config/objectives/request_teleoperation.xml
@@ -159,4 +159,11 @@
+
+
+
+
+
+
+
diff --git a/src/picknik_ur_site_config/config/config.yaml b/src/picknik_ur_site_config/config/config.yaml
index 575b8836..b722faeb 100644
--- a/src/picknik_ur_site_config/config/config.yaml
+++ b/src/picknik_ur_site_config/config/config.yaml
@@ -32,8 +32,6 @@ ros2_control:
# [Optional, default=[]]
controllers_inactive_at_startup:
- "joint_trajectory_controller"
- - "admittance_controller_open_door"
- - "joint_trajectory_controller_chained_open_door"
- "joint_trajectory_admittance_controller"
- "velocity_force_controller"
# Any controllers here will not be spawned by MoveIt Pro.
diff --git a/src/picknik_ur_site_config/config/control/picknik_ur.ros2_control.yaml b/src/picknik_ur_site_config/config/control/picknik_ur.ros2_control.yaml
index 138f849a..17851768 100644
--- a/src/picknik_ur_site_config/config/control/picknik_ur.ros2_control.yaml
+++ b/src/picknik_ur_site_config/config/control/picknik_ur.ros2_control.yaml
@@ -15,10 +15,6 @@ controller_manager:
type: robotiq_controllers/RobotiqActivationController
servo_controller:
type: joint_trajectory_controller/JointTrajectoryController
- admittance_controller_open_door:
- type: admittance_controller/AdmittanceController
- joint_trajectory_controller_chained_open_door:
- type: joint_trajectory_controller/JointTrajectoryController
joint_trajectory_admittance_controller:
type: joint_trajectory_admittance_controller/JointTrajectoryAdmittanceController
velocity_force_controller:
@@ -81,47 +77,6 @@ joint_trajectory_controller:
wrist_3_joint:
goal: 0.05
-joint_trajectory_controller_chained_open_door:
- ros__parameters:
- joints:
- - shoulder_pan_joint
- - shoulder_lift_joint
- - elbow_joint
- - wrist_1_joint
- - wrist_2_joint
- - wrist_3_joint
- command_interfaces:
- - position
- - velocity
- state_interfaces:
- - position
- - velocity
- command_joints:
- - admittance_controller_open_door/shoulder_pan_joint
- - admittance_controller_open_door/shoulder_lift_joint
- - admittance_controller_open_door/elbow_joint
- - admittance_controller_open_door/wrist_1_joint
- - admittance_controller_open_door/wrist_2_joint
- - admittance_controller_open_door/wrist_3_joint
- state_publish_rate: 100.0
- action_monitor_rate: 20.0
- allow_partial_joints_goal: false
- constraints:
- stopped_velocity_tolerance: 0.0
- goal_time: 0.0
- shoulder_pan_joint:
- goal: 0.25
- shoulder_lift_joint:
- goal: 0.25
- elbow_joint:
- goal: 0.25
- wrist_1_joint:
- goal: 0.25
- wrist_2_joint:
- goal: 0.25
- wrist_3_joint:
- goal: 0.25
-
servo_controller:
ros__parameters:
joints:
@@ -172,97 +127,6 @@ robotiq_activation_controller:
ros__parameters:
default: true
-admittance_controller_open_door:
- ros__parameters:
- joints:
- - shoulder_pan_joint
- - shoulder_lift_joint
- - elbow_joint
- - wrist_1_joint
- - wrist_2_joint
- - wrist_3_joint
-
- command_interfaces:
- - position
-
- state_interfaces:
- - position
- - velocity
-
- chainable_command_interfaces:
- - position
- - velocity
-
- kinematics:
- plugin_name: kinematics_interface_kdl/KinematicsInterfaceKDL
- plugin_package: kinematics_interface
- base: base_link # Assumed to be stationary
- tip: grasp_link # The end effector frame
- alpha: 0.05
-
- ft_sensor:
- name: tcp_fts_sensor
- frame:
- id: wrist_3_link # Wrench measurements are in this frame
- filter_coefficient: 0.1
-
- control:
- frame:
- id: grasp_link # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
-
- fixed_world_frame:
- frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link)
- id: base_link # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector
-
- gravity_compensation:
- frame:
- id: wrist_3_link
-
- CoG: # specifies the center of gravity of the end effector
- pos:
- - 0.1 # x
- - 0.0 # y
- - 0.0 # z
- force: 0.0 # mass * 9.81
-
- admittance:
- selected_axes:
- - true # x
- - true # y
- - true # z
- - true # rx
- - true # ry
- - true # rz
-
- # Having ".0" at the end is MUST, otherwise there is a loading error
- # F = M*a + D*v + S*(x - x_d)
- mass:
- - 10.0 # x
- - 10.0 # y
- - 10.0 # z
- - 5.0 # rx
- - 5.0 # ry
- - 5.0 # rz
-
- damping_ratio: # damping can be used instead: zeta = D / (2 * sqrt( M * S ))
- - 5.0 # x
- - 5.0 # y
- - 5.0 # z
- - 5.0 # rx
- - 5.0 # ry
- - 5.0 # rz
-
- stiffness:
- - 500.0 # x
- - 500.0 # y
- - 500.0 # z
- - 100.0 # rx
- - 100.0 # ry
- - 100.0 # rz
-
- # general settings
- enable_parameter_update_without_reactivation: true
-
joint_trajectory_admittance_controller:
ros__parameters:
joints:
diff --git a/src/picknik_ur_site_config/objectives/close_cabinet_door.xml b/src/picknik_ur_site_config/objectives/close_cabinet_door.xml
index 0c52d689..fcca6052 100644
--- a/src/picknik_ur_site_config/objectives/close_cabinet_door.xml
+++ b/src/picknik_ur_site_config/objectives/close_cabinet_door.xml
@@ -6,7 +6,7 @@
>
-
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/src/picknik_ur_site_config/objectives/push_button.xml b/src/picknik_ur_site_config/objectives/push_button.xml
index 21de49d5..2c6e75e9 100644
--- a/src/picknik_ur_site_config/objectives/push_button.xml
+++ b/src/picknik_ur_site_config/objectives/push_button.xml
@@ -6,7 +6,7 @@
>
-
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/src/picknik_ur_site_config/objectives/push_button_ml.xml b/src/picknik_ur_site_config/objectives/push_button_ml.xml
index c99a0349..53359d83 100644
--- a/src/picknik_ur_site_config/objectives/push_button_ml.xml
+++ b/src/picknik_ur_site_config/objectives/push_button_ml.xml
@@ -94,7 +94,7 @@
graspable_object="{button}"
pose="{button_pose}"
/>
-
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/src/picknik_ur_site_config/objectives/retreat_to_initial_pose.xml b/src/picknik_ur_site_config/objectives/retreat_to_initial_pose.xml
new file mode 100644
index 00000000..ee4c82a9
--- /dev/null
+++ b/src/picknik_ur_site_config/objectives/retreat_to_initial_pose.xml
@@ -0,0 +1,64 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+