Skip to content

Commit

Permalink
Revert "Migrate to UR robots"
Browse files Browse the repository at this point in the history
This reverts commit 822ea75.

Signed-off-by: Luca Della Vedova <lucadv@intrinsic.ai>
  • Loading branch information
luca-della-vedova committed Nov 19, 2024
1 parent 822ea75 commit f398956
Show file tree
Hide file tree
Showing 26 changed files with 523 additions and 253 deletions.
8 changes: 3 additions & 5 deletions .github/workflows/nexus_integration_tests.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,9 @@ jobs:
with:
path: ~/.cache/ccache
key: ccache
# TODO(luca) Remove build from source of UR robots
# This is only temporary until a new Jazzy sync that includes https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/pull/1153/ is made
- name: TEMPORARY build UR from source
run:
git clone -b 2.4.13 https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver
- name: vcs
run: |
vcs import . < abb.repos
- name: rosdep
run: |
apt update
Expand Down
21 changes: 21 additions & 0 deletions abb.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
repositories:
thirdparty/abb/abb_libegm:
type: git
url: https://github.com/yadunund/abb_libegm.git
version: feature/scara
thirdparty/abb/abb_librws:
type: git
url: https://github.com/ros-industrial/abb_librws.git
version: master
thirdparty/abb/abb_egm_rws_managers:
type: git
url: https://github.com/yadunund/abb_egm_rws_managers.git
version: feature/scara
thirdparty/abb/abb_ros2_msgs:
type: git
url: https://github.com/gbartyzel/abb_ros2_msgs.git
version: rolling
thirdparty/abb/abb_ros2:
type: git
url: https://github.com/yadunund/abb_ros2.git
version: main
78 changes: 78 additions & 0 deletions nexus_integration_tests/config/abb_irb1300_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
controller_manager:
ros__parameters:
update_rate: 250 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

robot_controller_server:
ros__parameters:
managed_controllers: ["joint_state_broadcaster", "joint_trajectory_controller"]

joint_trajectory_controller:
ros__parameters:
joints:
- joint_1
- joint_2
- joint_3
- joint_4
- joint_5
- joint_6
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.01
goal_time: 0.0
gains:
joint_1:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_2:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_3:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_4:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_5:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_6:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
58 changes: 58 additions & 0 deletions nexus_integration_tests/config/abb_irb1300_planner_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
motion_planner_server:
ros__parameters:
# List of robots to generate motion plans for
manipulators: ["abb_irb1300"]
# The default moveit group for each manipulator
default_group_name: "manipulator"
# Seconds to wait to connect to an action or service server
timeout_duration: 5
# Configure the planner_server to query motion plans directly from a move_group
# node that is running by initializing a move_group_interface.
# When set to false, the planner_server will initialize planning pipelines
# to directly compute plans but this has not been implemented yet.
use_move_group_interfaces: true
# When planning for multiple robots, set this to true.
use_namespace: false
# Tolerance for goal position.
goal_tolerance: 0.05
# Maximum seconds to generate a plan.
planning_time: 1.0
# Maximum number of replanning attempts
replan_attempts: 10
# If true, the cartesian interpolator will check for collisions.
collision_aware_cartesian_path: false
# The value of the max_step parameter used in cartesian interpolation.
cartesian_max_step: 0.001
# The value of the jump_threshold parameter used in cartesian interpolation.
cartesian_jump_threshold: 0.0
# Set true if trajectory should be executed after a plan is generated.
# The execution is a blocking event.
execute_trajectory: false
# The min_x of workspace bounding box.
workspace_min_x: -1.0
# The min_y of workspace bounding box.
workspace_min_y: -1.0
# The min_z of workspace bounding box.
workspace_min_z: -1.0
# The max_x of workspace bounding box.
workspace_max_x: 1.0
# The max_y of workspace bounding box.
workspace_max_y: 1.0
# The max_z of workspace bounding box.
workspace_max_z: 1.0
# The seconds within which the current robot state should be valid.
get_state_wait_seconds: 0.01
# Namespaced parameters for each robot when use_namespace is true.
# Is important to ensure move_group, robot_state_publisher and
# joint_state broadcaster all have the same namespace.
# Note: If use_namespace is false, pass these parameters directly.
abb_irb1300:
robot_description: ""
robot_description_semantic: ""
group_name: "manipulator"
# Group specific kinematic properties.
manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
79 changes: 79 additions & 0 deletions nexus_integration_tests/config/abb_irb910sc_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
controller_manager:
ros__parameters:
update_rate: 250 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController

forward_command_controller_position:
type: forward_command_controller/ForwardCommandController

robot_controller_server:
ros__parameters:
managed_controllers: [
"joint_state_broadcaster",
"joint_trajectory_controller",
# "forward_command_controller_position"
]

joint_trajectory_controller:
ros__parameters:
joints:
- joint_1
- joint_2
- joint_3
- joint_4
command_interfaces:
- position
- velocity
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.01
goal_time: 0.0
open_loop_control: false
gains:
joint_1:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_2:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_3:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false
joint_4:
p: 0.0
i: 0.0
d: 0.0
i_clamp: 0.0
ff_velocity_scale: 0.0
normalize_error: false

forward_command_controller_position:
ros__parameters:
joints:
- joint_1
- joint_2
- joint_3
- joint_4
interface_name: position
43 changes: 43 additions & 0 deletions nexus_integration_tests/config/abb_irb910sc_planner_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
motion_planner_server:
ros__parameters:
# List of robots to generate motion plans for
manipulators: ["abb_irb910sc"]
# The default moveit group for each manipulator
default_group_name: "manipulator"
# Seconds to wait to connect to an action or service server
timeout_duration: 5
# Configure the planner_server to query motion plans directly from a move_group
# node that is running by initializing a move_group_interface.
# When set to false, the planner_server will initialize planning pipelines
# to directly compute plans but this has not been implemented yet.
use_move_group_interfaces: true
# When planning for multiple robots, set this to true.
use_namespace: false
# Tolerance for goal position.
goal_tolerance: 0.05
# Maximum seconds to generate a plan.
planning_time: 5.0
# Maximum number of replanning attempts
replan_attempts: 10
# If true, the cartesian interpolator will check for collisions.
collision_aware_cartesian_path: false
# Set true if trajectory should be executed after a plan is generated.
# The execution is a blocking event.
execute_trajectory: false
# The seconds within which the current robot state should be valid.
get_state_wait_seconds: 0.01

# Namespaced parameters for each robot when use_namespace is true.
# Is important to ensure move_group, robot_state_publisher and
# joint_state broadcaster all have the same namespace.
# Note: If use_namespace is false, pass these parameters directly.
abb_irb910sc:
robot_description: ""
robot_description_semantic: ""
group_name: "manipulator"
# Group specific kinematic properties.
manipulator:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
Original file line number Diff line number Diff line change
Expand Up @@ -5,23 +5,23 @@
<dispense_item.DispenseItem name="dispense_item" item="productA" />

<ApplyTransform base_pose="pickup_pose" x="0" y="0" z="-0.02" qx="0" qy="0" qz="0" qw="1" local="true" result="{pickup_top_goal}" />
<plan_motion.PlanMotion name="plan_to_pickup_top" robot_name="ur5e" goal="{pickup_top_goal}" scale_speed="0.5" cartesian="true" result="{pickup_top_traj}" />
<plan_motion.PlanMotion name="plan_to_pickup_top" robot_name="abb_irb910sc" goal="{pickup_top_goal}" scale_speed="0.5" cartesian="true" result="{pickup_top_traj}" />
<GetJointConstraints trajectory="{pickup_top_traj}" joint_constraints="{joint_constraints}" />
<execute_trajectory.ExecuteTrajectory name="execute_pickup_top" trajectory="{pickup_top_traj}" />

<plan_motion.PlanMotion name="plan_to_pickup" robot_name="ur5e" goal="pickup_pose" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{pickup_traj}" />
<plan_motion.PlanMotion name="plan_to_pickup" robot_name="abb_irb910sc" goal="pickup_pose" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{pickup_traj}" />
<GetJointConstraints trajectory="{pickup_traj}" joint_constraints="{joint_constraints}" />
<execute_trajectory.ExecuteTrajectory name="execute_pickup" trajectory="{pickup_traj}" />
<gripper.GripperControl name="pickup_product" gripper="workcell_1_mock_gripper" position="0.0" max_effort="1.0" />

<plan_motion.PlanMotion name="plan_to_dropoff" robot_name="ur5e" goal="dropoff_pose" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{dropoff_traj}" />
<plan_motion.PlanMotion name="plan_to_dropoff" robot_name="abb_irb910sc" goal="dropoff_pose" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{dropoff_traj}" />
<GetJointConstraints trajectory="{dropoff_traj}" joint_constraints="{joint_constraints}" />

<WaitForSignal name="wait_for_pallet" signal="transporter_done" clear="true"/>
<execute_trajectory.ExecuteTrajectory name="execute_dropoff" trajectory="{dropoff_traj}" />
<gripper.GripperControl name="dropoff_product" gripper="workcell_1_mock_gripper" position="1.0" max_effort="0.0" />

<plan_motion.PlanMotion name="plan_to_home" robot_name="ur5e" goal="home" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{home_traj}" />
<plan_motion.PlanMotion name="plan_to_home" robot_name="abb_irb910sc" goal="home" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{home_traj}" />
<execute_trajectory.ExecuteTrajectory name="execute_home" trajectory="{home_traj}" />


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,25 +9,25 @@
<detection.GetDetectionPose detection="{current_product_detection}" result="{current_product_pose}" />

<ApplyTransform base_pose="{current_product_pose}" x="0" y="0" z="-0.02" qx="0" qy="0" qz="0" qw="1" local="true" result="{pickup_top_goal}" />
<plan_motion.PlanMotion name="plan_to_pickup_top" robot_name="ur5e" goal="{pickup_top_goal}" scale_speed="0.5" result="{pickup_top_traj}" />
<plan_motion.PlanMotion name="plan_to_pickup_top" robot_name="abb_irb1300" goal="{pickup_top_goal}" scale_speed="0.5" result="{pickup_top_traj}" />
<GetJointConstraints trajectory="{pickup_top_traj}" joint_constraints="{joint_constraints}" />
<execute_trajectory.ExecuteTrajectory name="execute_pickup" trajectory="{pickup_top_traj}" />

<plan_motion.PlanMotion name="plan_to_product" robot_name="ur5e" goal="{current_product_pose}" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{pickup_traj}" />
<plan_motion.PlanMotion name="plan_to_product" robot_name="abb_irb1300" goal="{current_product_pose}" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{pickup_traj}" />
<GetJointConstraints trajectory="{pickup_traj}" joint_constraints="{joint_constraints}" />
<execute_trajectory.ExecuteTrajectory name="execute_pickup" trajectory="{pickup_traj}" />
<gripper.GripperControl name="pickup_product" gripper="workcell_2_mock_gripper" position="0.0" max_effort="1.0" />

<ApplyTransform base_pose="dropoff_pose" x="0" y="0" z="-0.02" qx="0" qy="0" qz="0" qw="1" result="{dropoff_top_goal}" />
<plan_motion.PlanMotion name="plan_to_dropoff_top" robot_name="ur5e" goal="{dropoff_top_goal}" scale_speed="0.5" result="{dropoff_top_traj}" />
<plan_motion.PlanMotion name="plan_to_dropoff_top" robot_name="abb_irb1300" goal="{dropoff_top_goal}" scale_speed="0.5" result="{dropoff_top_traj}" />
<GetJointConstraints trajectory="{dropoff_top_traj}" joint_constraints="{joint_constraints}" />
<execute_trajectory.ExecuteTrajectory name="execute_dropoff_top" trajectory="{dropoff_top_traj}" />

<plan_motion.PlanMotion name="plan_to_dropoff" robot_name="ur5e" goal="dropoff_pose" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{dropoff_traj}" />
<plan_motion.PlanMotion name="plan_to_dropoff" robot_name="abb_irb1300" goal="dropoff_pose" scale_speed="0.5" cartesian="true" start_constraints="{joint_constraints}" result="{dropoff_traj}" />
<GetJointConstraints trajectory="{dropoff_traj}" joint_constraints="{joint_constraints}" />
<gripper.GripperControl name="pickup_product" gripper="workcell_2_mock_gripper" position="1.0" max_effort="0.0" />

<plan_motion.PlanMotion name="plan_to_home" robot_name="ur5e" goal="home" scale_speed="0.5" start_constraints="{joint_constraints}" result="{home_traj}" />
<plan_motion.PlanMotion name="plan_to_home" robot_name="abb_irb1300" goal="home" scale_speed="0.5" start_constraints="{joint_constraints}" result="{home_traj}" />
<execute_trajectory.ExecuteTrajectory name="execute_home" trajectory="{home_traj}" />
</Sequence>
</BehaviorTree>
Expand Down
Loading

0 comments on commit f398956

Please sign in to comment.