diff --git a/config/arm.xacro b/config/arm.xacro index f5be8b4..0556385 100644 --- a/config/arm.xacro +++ b/config/arm.xacro @@ -7,67 +7,67 @@ - + - - - - - - - + + + + + + + - - - - - - - + + + + + + + - + - - - - - - - - - + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + diff --git a/config/fake_controllers.yaml b/config/fake_controllers.yaml index ef67f6e..6a6759c 100644 --- a/config/fake_controllers.yaml +++ b/config/fake_controllers.yaml @@ -1,31 +1,22 @@ controller_list: - - name: fake_panda_arm_controller + - name: fake_$(arg arm_id)_arm_controller type: $(arg fake_execution_type) joints: - - panda_joint1 - - panda_joint2 - - panda_joint3 - - panda_joint4 - - panda_joint5 - - panda_joint6 - - panda_joint7 - - name: fake_hand_controller + - $(arg arm_id)_joint1 + - $(arg arm_id)_joint2 + - $(arg arm_id)_joint3 + - $(arg arm_id)_joint4 + - $(arg arm_id)_joint5 + - $(arg arm_id)_joint6 + - $(arg arm_id)_joint7 + + - name: fake_$(arg arm_id)_hand_controller type: $(arg fake_execution_type) joints: - - panda_finger_joint1 - - name: fake_panda_arm_hand_controller - type: $(arg fake_execution_type) - joints: - - panda_joint1 - - panda_joint2 - - panda_joint3 - - panda_joint4 - - panda_joint5 - - panda_joint6 - - panda_joint7 - - panda_finger_joint1 + - $(arg arm_id)_finger_joint1 + initial: # Define initial robot poses per group - - group: panda_arm + - group: $(arg arm_id)_arm pose: ready - group: hand pose: open \ No newline at end of file diff --git a/config/hand.xacro b/config/hand.xacro index 1bea787..e9ec8e3 100644 --- a/config/hand.xacro +++ b/config/hand.xacro @@ -3,16 +3,16 @@ - - - - - - - - - - + + + + + + + + + + @@ -21,41 +21,41 @@ - - - + + + - - + + - - + + - - - - - + + + + + - - - - - - - - - + + + + + + + + + - - - + + + diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml index d531621..9bdaadd 100644 --- a/config/joint_limits.yaml +++ b/config/joint_limits.yaml @@ -14,47 +14,47 @@ default_acceleration_scaling_factor: 0.1 # max_jerk = (max_acceleration - min_acceleration) / 0.001 joint_limits: - panda_finger_joint1: + $(arg arm_id)_finger_joint1: has_velocity_limits: true max_velocity: 0.1 has_acceleration_limits: false max_acceleration: 0 - panda_finger_joint2: + $(arg arm_id)_finger_joint2: has_velocity_limits: true max_velocity: 0.1 has_acceleration_limits: false max_acceleration: 0 - panda_joint1: + $(arg arm_id)_joint1: has_velocity_limits: true max_velocity: 2.1750 has_acceleration_limits: true max_acceleration: 3.75 - panda_joint2: + $(arg arm_id)_joint2: has_velocity_limits: true max_velocity: 2.1750 has_acceleration_limits: true max_acceleration: 1.875 - panda_joint3: + $(arg arm_id)_joint3: has_velocity_limits: true max_velocity: 2.1750 has_acceleration_limits: true max_acceleration: 2.5 - panda_joint4: + $(arg arm_id)_joint4: has_velocity_limits: true max_velocity: 2.1750 has_acceleration_limits: true max_acceleration: 3.125 - panda_joint5: + $(arg arm_id)_joint5: has_velocity_limits: true max_velocity: 2.6100 has_acceleration_limits: true max_acceleration: 3.75 - panda_joint6: + $(arg arm_id)_joint6: has_velocity_limits: true max_velocity: 2.6100 has_acceleration_limits: true max_acceleration: 5 - panda_joint7: + $(arg arm_id)_joint7: has_velocity_limits: true max_velocity: 2.6100 has_acceleration_limits: true diff --git a/config/kinematics.yaml b/config/kinematics.yaml index 9bbfb6d..ffeb7ae 100644 --- a/config/kinematics.yaml +++ b/config/kinematics.yaml @@ -1,4 +1,4 @@ -panda_arm: &arm_config +$(arg arm_id)_arm: &arm_config kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin kinematics_solver_search_resolution: 0.005 kinematics_solver_timeout: 0.05 diff --git a/config/ompl_planning.yaml b/config/ompl_planning.yaml index b556110..69f40b0 100644 --- a/config/ompl_planning.yaml +++ b/config/ompl_planning.yaml @@ -127,7 +127,7 @@ planner_configs: sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 max_failures: 5000 # maximum consecutive failure limit. default: 5000 -panda_arm: &arm_config +$(arg arm_id)_arm: &arm_config planner_configs: - AnytimePathShortening - SBL @@ -153,7 +153,7 @@ panda_arm: &arm_config - LazyPRMstar - SPARS - SPARStwo - projection_evaluator: joints(panda_joint1,panda_joint2) + projection_evaluator: joints($(arg arm_id)_joint1,$(arg arm_id)_joint2) longest_valid_segment_fraction: 0.005 manipulator: *arm_config hand: diff --git a/config/panda.srdf.xacro b/config/panda.srdf.xacro index 4fa5062..99307dc 100644 --- a/config/panda.srdf.xacro +++ b/config/panda.srdf.xacro @@ -5,22 +5,23 @@ --> + - + - + - + - + diff --git a/config/simple_moveit_controllers.yaml b/config/simple_moveit_controllers.yaml index 454ca42..19a874b 100644 --- a/config/simple_moveit_controllers.yaml +++ b/config/simple_moveit_controllers.yaml @@ -4,16 +4,16 @@ controller_list: type: FollowJointTrajectory default: True joints: - - panda_joint1 - - panda_joint2 - - panda_joint3 - - panda_joint4 - - panda_joint5 - - panda_joint6 - - panda_joint7 + - $(arg arm_id)_joint1 + - $(arg arm_id)_joint2 + - $(arg arm_id)_joint3 + - $(arg arm_id)_joint4 + - $(arg arm_id)_joint5 + - $(arg arm_id)_joint6 + - $(arg arm_id)_joint7 - name: franka_gripper action_ns: gripper_action type: GripperCommand default: True joints: - - panda_finger_joint1 + - $(arg arm_id)_finger_joint1 diff --git a/launch/demo.launch b/launch/demo.launch index 3a6db41..543cb19 100644 --- a/launch/demo.launch +++ b/launch/demo.launch @@ -1,4 +1,5 @@ + @@ -31,7 +32,7 @@ - + diff --git a/launch/move_group.launch b/launch/move_group.launch index 7cb7e8e..7d511f3 100644 --- a/launch/move_group.launch +++ b/launch/move_group.launch @@ -24,6 +24,8 @@ + + @@ -54,22 +57,26 @@ + + + + diff --git a/launch/ompl_planning_pipeline.launch.xml b/launch/ompl_planning_pipeline.launch.xml index 00f8e4e..af9d56e 100644 --- a/launch/ompl_planning_pipeline.launch.xml +++ b/launch/ompl_planning_pipeline.launch.xml @@ -12,6 +12,7 @@ + @@ -21,6 +22,6 @@ - + diff --git a/launch/planning_context.launch b/launch/planning_context.launch index 27d5a3a..d32922f 100644 --- a/launch/planning_context.launch +++ b/launch/planning_context.launch @@ -2,25 +2,26 @@ + - + - + - - + + - + diff --git a/launch/planning_pipeline.launch.xml b/launch/planning_pipeline.launch.xml index 4b4d0d6..250e743 100644 --- a/launch/planning_pipeline.launch.xml +++ b/launch/planning_pipeline.launch.xml @@ -4,7 +4,8 @@ It is assumed that all planning pipelines are named XXX_planning_pipeline.launch --> + - + diff --git a/launch/ros_controllers.launch b/launch/ros_controllers.launch index 3d3b1f4..8fd5760 100644 --- a/launch/ros_controllers.launch +++ b/launch/ros_controllers.launch @@ -2,9 +2,9 @@ - + - diff --git a/launch/stomp_planning_pipeline.launch.xml b/launch/stomp_planning_pipeline.launch.xml index 0f4b967..cbff8df 100644 --- a/launch/stomp_planning_pipeline.launch.xml +++ b/launch/stomp_planning_pipeline.launch.xml @@ -22,9 +22,9 @@ - + - +