diff --git a/air_dual_arm_config/.setup_assistant b/air_dual_arm_config/.setup_assistant
new file mode 100644
index 0000000..a164981
--- /dev/null
+++ b/air_dual_arm_config/.setup_assistant
@@ -0,0 +1,11 @@
+moveit_setup_assistant_config:
+ URDF:
+ package: air_dual_arm_description
+ relative_path: urdf/air_dual_arm.urdf
+ xacro_args: ""
+ SRDF:
+ relative_path: config/air_dual_arm_description.srdf
+ CONFIG:
+ author_name: Cenk Çetin
+ author_email: cenkcetix@gmail.com
+ generated_timestamp: 1683207922
\ No newline at end of file
diff --git a/air_dual_arm_config/CMakeLists.txt b/air_dual_arm_config/CMakeLists.txt
new file mode 100644
index 0000000..6638081
--- /dev/null
+++ b/air_dual_arm_config/CMakeLists.txt
@@ -0,0 +1,10 @@
+cmake_minimum_required(VERSION 3.1.3)
+project(air_dual_arm_config)
+
+find_package(catkin REQUIRED)
+
+catkin_package()
+
+install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+ PATTERN "setup_assistant.launch" EXCLUDE)
+install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
diff --git a/air_dual_arm_config/config/air_dual_arm_description.srdf b/air_dual_arm_config/config/air_dual_arm_description.srdf
new file mode 100644
index 0000000..51616d7
--- /dev/null
+++ b/air_dual_arm_config/config/air_dual_arm_description.srdf
@@ -0,0 +1,554 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/config/cartesian_limits.yaml b/air_dual_arm_config/config/cartesian_limits.yaml
new file mode 100644
index 0000000..7df72f6
--- /dev/null
+++ b/air_dual_arm_config/config/cartesian_limits.yaml
@@ -0,0 +1,5 @@
+cartesian_limits:
+ max_trans_vel: 1
+ max_trans_acc: 2.25
+ max_trans_dec: -5
+ max_rot_vel: 1.57
diff --git a/air_dual_arm_config/config/chomp_planning.yaml b/air_dual_arm_config/config/chomp_planning.yaml
new file mode 100644
index 0000000..eb9c912
--- /dev/null
+++ b/air_dual_arm_config/config/chomp_planning.yaml
@@ -0,0 +1,18 @@
+planning_time_limit: 10.0
+max_iterations: 200
+max_iterations_after_collision_free: 5
+smoothness_cost_weight: 0.1
+obstacle_cost_weight: 1.0
+learning_rate: 0.01
+smoothness_cost_velocity: 0.0
+smoothness_cost_acceleration: 1.0
+smoothness_cost_jerk: 0.0
+ridge_factor: 0.0
+use_pseudo_inverse: false
+pseudo_inverse_ridge_factor: 1e-4
+joint_update_limit: 0.1
+collision_clearance: 0.2
+collision_threshold: 0.07
+use_stochastic_descent: true
+enable_failure_recovery: false
+max_recovery_attempts: 5
diff --git a/air_dual_arm_config/config/fake_controllers.yaml b/air_dual_arm_config/config/fake_controllers.yaml
new file mode 100644
index 0000000..2146c60
--- /dev/null
+++ b/air_dual_arm_config/config/fake_controllers.yaml
@@ -0,0 +1,29 @@
+controller_list:
+ - name: fake_air_right_arm_controller
+ type: $(arg fake_execution_type)
+ joints:
+ - s1j
+ - s2j
+ - s3j
+ - ej
+ - rollj
+ - pitchj
+ - yawj
+ - name: fake_air_left_arm_controller
+ type: $(arg fake_execution_type)
+ joints:
+ - s1_2j
+ - s2_2j
+ - s3_2j
+ - e_2j
+ - roll_2j
+ - pitch_2j
+ - name: fake_gripper_controller
+ type: $(arg fake_execution_type)
+ joints:
+ - qbhand_synergy_joint
+initial: # Define initial robot poses per group
+ - group: air_right_arm
+ pose: right_home
+ - group: air_left_arm
+ pose: left_home
\ No newline at end of file
diff --git a/air_dual_arm_config/config/gazebo_air_dual_arm_description.urdf b/air_dual_arm_config/config/gazebo_air_dual_arm_description.urdf
new file mode 100644
index 0000000..0dd446f
--- /dev/null
+++ b/air_dual_arm_config/config/gazebo_air_dual_arm_description.urdf
@@ -0,0 +1,2551 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+ /
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+ transmission_interface/SimpleTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+ 1
+
+
+
+
diff --git a/air_dual_arm_config/config/gazebo_controllers.yaml b/air_dual_arm_config/config/gazebo_controllers.yaml
new file mode 100644
index 0000000..e4d2eb0
--- /dev/null
+++ b/air_dual_arm_config/config/gazebo_controllers.yaml
@@ -0,0 +1,4 @@
+# Publish joint_states
+joint_state_controller:
+ type: joint_state_controller/JointStateController
+ publish_rate: 50
diff --git a/air_dual_arm_config/config/joint_limits.yaml b/air_dual_arm_config/config/joint_limits.yaml
new file mode 100644
index 0000000..fe5a232
--- /dev/null
+++ b/air_dual_arm_config/config/joint_limits.yaml
@@ -0,0 +1,245 @@
+# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed
+
+# For beginners, we downscale velocity and acceleration limits.
+# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed.
+default_velocity_scaling_factor: 0.1
+default_acceleration_scaling_factor: 0.1
+
+# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
+# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
+joint_limits:
+ e_2j:
+ has_velocity_limits: false
+ max_velocity: 0
+ has_acceleration_limits: false
+ max_acceleration: 0
+ ej:
+ has_velocity_limits: true
+ max_velocity: 0.13
+ has_acceleration_limits: false
+ max_acceleration: 0
+ pitch_2j:
+ has_velocity_limits: false
+ max_velocity: 0
+ has_acceleration_limits: false
+ max_acceleration: 0
+ pitchj:
+ has_velocity_limits: true
+ max_velocity: 0.09
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_index_distal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_index_distal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_index_knuckle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_index_middle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_index_middle_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_index_proximal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_index_proximal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_little_distal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_little_distal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_little_knuckle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_little_middle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_little_middle_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_little_proximal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_little_proximal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_middle_distal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_middle_distal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_middle_knuckle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_middle_middle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_middle_middle_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_middle_proximal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_middle_proximal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_ring_distal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_ring_distal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_ring_knuckle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_ring_middle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_ring_middle_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_ring_proximal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_ring_proximal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_synergy_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_thumb_distal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_thumb_distal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_thumb_knuckle_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_thumb_proximal_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ qbhand_thumb_proximal_virtual_joint:
+ has_velocity_limits: true
+ max_velocity: 100
+ has_acceleration_limits: false
+ max_acceleration: 0
+ roll_2j:
+ has_velocity_limits: false
+ max_velocity: 0
+ has_acceleration_limits: false
+ max_acceleration: 0
+ rollj:
+ has_velocity_limits: true
+ max_velocity: 0.09
+ has_acceleration_limits: false
+ max_acceleration: 0
+ s1_2j:
+ has_velocity_limits: false
+ max_velocity: 0
+ has_acceleration_limits: false
+ max_acceleration: 0
+ s1j:
+ has_velocity_limits: true
+ max_velocity: 0.35
+ has_acceleration_limits: false
+ max_acceleration: 0
+ s2_2j:
+ has_velocity_limits: false
+ max_velocity: 0
+ has_acceleration_limits: false
+ max_acceleration: 0
+ s2j:
+ has_velocity_limits: true
+ max_velocity: 0.35
+ has_acceleration_limits: false
+ max_acceleration: 0
+ s3_2j:
+ has_velocity_limits: false
+ max_velocity: 0
+ has_acceleration_limits: false
+ max_acceleration: 0
+ s3j:
+ has_velocity_limits: true
+ max_velocity: 0.35
+ has_acceleration_limits: false
+ max_acceleration: 0
+ yawj:
+ has_velocity_limits: true
+ max_velocity: 1.75
+ has_acceleration_limits: false
+ max_acceleration: 0
\ No newline at end of file
diff --git a/air_dual_arm_config/config/kinematics.yaml b/air_dual_arm_config/config/kinematics.yaml
new file mode 100644
index 0000000..eb6d168
--- /dev/null
+++ b/air_dual_arm_config/config/kinematics.yaml
@@ -0,0 +1,8 @@
+air_right_arm:
+ kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
+ kinematics_solver_search_resolution: 0.005
+ kinematics_solver_timeout: 0.005
+air_left_arm:
+ kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
+ kinematics_solver_search_resolution: 0.005
+ kinematics_solver_timeout: 0.005
\ No newline at end of file
diff --git a/air_dual_arm_config/config/ompl_planning.yaml b/air_dual_arm_config/config/ompl_planning.yaml
new file mode 100644
index 0000000..030e776
--- /dev/null
+++ b/air_dual_arm_config/config/ompl_planning.yaml
@@ -0,0 +1,213 @@
+planner_configs:
+ AnytimePathShortening:
+ type: geometric::AnytimePathShortening
+ shortcut: true # Attempt to shortcut all new solution paths
+ hybridize: true # Compute hybrid solution trajectories
+ max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
+ num_planners: 4 # The number of default planners to use for planning
+ planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
+ SBL:
+ type: geometric::SBL
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ EST:
+ type: geometric::EST
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ LBKPIECE:
+ type: geometric::LBKPIECE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
+ min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
+ BKPIECE:
+ type: geometric::BKPIECE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
+ failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
+ min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
+ KPIECE:
+ type: geometric::KPIECE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
+ failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
+ min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
+ RRT:
+ type: geometric::RRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
+ RRTConnect:
+ type: geometric::RRTConnect
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ RRTstar:
+ type: geometric::RRTstar
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
+ delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
+ TRRT:
+ type: geometric::TRRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
+ max_states_failed: 10 # when to start increasing temp. default: 10
+ temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
+ min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
+ init_temperature: 10e-6 # initial temperature. default: 10e-6
+ frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
+ frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
+ k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
+ PRM:
+ type: geometric::PRM
+ max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
+ PRMstar:
+ type: geometric::PRMstar
+ FMT:
+ type: geometric::FMT
+ num_samples: 1000 # number of states that the planner should sample. default: 1000
+ radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
+ nearest_k: 1 # use Knearest strategy. default: 1
+ cache_cc: 1 # use collision checking cache. default: 1
+ heuristics: 0 # activate cost to go heuristics. default: 0
+ extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
+ BFMT:
+ type: geometric::BFMT
+ num_samples: 1000 # number of states that the planner should sample. default: 1000
+ radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
+ nearest_k: 1 # use the Knearest strategy. default: 1
+ balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
+ optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
+ heuristics: 1 # activates cost to go heuristics. default: 1
+ cache_cc: 1 # use the collision checking cache. default: 1
+ extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
+ PDST:
+ type: geometric::PDST
+ STRIDE:
+ type: geometric::STRIDE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
+ degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
+ max_degree: 18 # max degree of a node in the GNAT. default: 12
+ min_degree: 12 # min degree of a node in the GNAT. default: 12
+ max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
+ estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
+ min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
+ BiTRRT:
+ type: geometric::BiTRRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
+ init_temperature: 100 # initial temperature. default: 100
+ frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
+ frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
+ cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
+ LBTRRT:
+ type: geometric::LBTRRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ epsilon: 0.4 # optimality approximation factor. default: 0.4
+ BiEST:
+ type: geometric::BiEST
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ ProjEST:
+ type: geometric::ProjEST
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ LazyPRM:
+ type: geometric::LazyPRM
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ LazyPRMstar:
+ type: geometric::LazyPRMstar
+ SPARS:
+ type: geometric::SPARS
+ stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
+ 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: 1000 # maximum consecutive failure limit. default: 1000
+ SPARStwo:
+ type: geometric::SPARStwo
+ stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
+ 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
+air_right_arm:
+ default_planner_config: RRTConnect
+ planner_configs:
+ - AnytimePathShortening
+ - SBL
+ - EST
+ - LBKPIECE
+ - BKPIECE
+ - KPIECE
+ - RRT
+ - RRTConnect
+ - RRTstar
+ - TRRT
+ - PRM
+ - PRMstar
+ - FMT
+ - BFMT
+ - PDST
+ - STRIDE
+ - BiTRRT
+ - LBTRRT
+ - BiEST
+ - ProjEST
+ - LazyPRM
+ - LazyPRMstar
+ - SPARS
+ - SPARStwo
+ projection_evaluator: joints(s1j,s2j)
+ longest_valid_segment_fraction: 0.005
+air_left_arm:
+ default_planner_config: RRTConnect
+ planner_configs:
+ - AnytimePathShortening
+ - SBL
+ - EST
+ - LBKPIECE
+ - BKPIECE
+ - KPIECE
+ - RRT
+ - RRTConnect
+ - RRTstar
+ - TRRT
+ - PRM
+ - PRMstar
+ - FMT
+ - BFMT
+ - PDST
+ - STRIDE
+ - BiTRRT
+ - LBTRRT
+ - BiEST
+ - ProjEST
+ - LazyPRM
+ - LazyPRMstar
+ - SPARS
+ - SPARStwo
+ projection_evaluator: joints(s1_2j,s2_2j)
+ longest_valid_segment_fraction: 0.005
+gripper:
+ planner_configs:
+ - AnytimePathShortening
+ - SBL
+ - EST
+ - LBKPIECE
+ - BKPIECE
+ - KPIECE
+ - RRT
+ - RRTConnect
+ - RRTstar
+ - TRRT
+ - PRM
+ - PRMstar
+ - FMT
+ - BFMT
+ - PDST
+ - STRIDE
+ - BiTRRT
+ - LBTRRT
+ - BiEST
+ - ProjEST
+ - LazyPRM
+ - LazyPRMstar
+ - SPARS
+ - SPARStwo
diff --git a/air_dual_arm_config/config/ros_controllers.yaml b/air_dual_arm_config/config/ros_controllers.yaml
new file mode 100644
index 0000000..f5afb65
--- /dev/null
+++ b/air_dual_arm_config/config/ros_controllers.yaml
@@ -0,0 +1,96 @@
+air_right_arm_controller:
+ type: effort_controllers/JointTrajectoryController
+ joints:
+ - s1j
+ - s2j
+ - s3j
+ - ej
+ - rollj
+ - pitchj
+ - yawj
+ gains:
+ s1j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ s2j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ s3j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ ej:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ rollj:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ pitchj:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ yawj:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+air_left_arm_controller:
+ type: effort_controllers/JointTrajectoryController
+ joints:
+ - s1_2j
+ - s2_2j
+ - s3_2j
+ - e_2j
+ - roll_2j
+ - pitch_2j
+ gains:
+ s1_2j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ s2_2j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ s3_2j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ e_2j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ roll_2j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ pitch_2j:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+gripper_controller:
+ type: effort_controllers/JointTrajectoryController
+ joints:
+ - qbhand_synergy_joint
+ gains:
+ qbhand_synergy_joint:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
\ No newline at end of file
diff --git a/air_dual_arm_config/config/sensors_3d.yaml b/air_dual_arm_config/config/sensors_3d.yaml
new file mode 100644
index 0000000..51010a3
--- /dev/null
+++ b/air_dual_arm_config/config/sensors_3d.yaml
@@ -0,0 +1,2 @@
+sensors:
+ []
\ No newline at end of file
diff --git a/air_dual_arm_config/config/simple_moveit_controllers.yaml b/air_dual_arm_config/config/simple_moveit_controllers.yaml
new file mode 100644
index 0000000..e213e05
--- /dev/null
+++ b/air_dual_arm_config/config/simple_moveit_controllers.yaml
@@ -0,0 +1,30 @@
+controller_list:
+ - name: air_right_arm_controller
+ action_ns: follow_joint_trajectory
+ type: FollowJointTrajectory
+ default: True
+ joints:
+ - s1j
+ - s2j
+ - s3j
+ - ej
+ - rollj
+ - pitchj
+ - yawj
+ - name: air_left_arm_controller
+ action_ns: follow_joint_trajectory
+ type: FollowJointTrajectory
+ default: True
+ joints:
+ - s1_2j
+ - s2_2j
+ - s3_2j
+ - e_2j
+ - roll_2j
+ - pitch_2j
+ - name: gripper_controller
+ action_ns: follow_joint_trajectory
+ type: FollowJointTrajectory
+ default: True
+ joints:
+ - qbhand_synergy_joint
\ No newline at end of file
diff --git a/air_dual_arm_config/config/stomp_planning.yaml b/air_dual_arm_config/config/stomp_planning.yaml
new file mode 100644
index 0000000..3e15aec
--- /dev/null
+++ b/air_dual_arm_config/config/stomp_planning.yaml
@@ -0,0 +1,117 @@
+stomp/air_right_arm:
+ group_name: air_right_arm
+ optimization:
+ num_timesteps: 60
+ num_iterations: 40
+ num_iterations_after_valid: 0
+ num_rollouts: 30
+ max_rollouts: 30
+ initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
+ control_cost_weight: 0.0
+ task:
+ noise_generator:
+ - class: stomp_moveit/NormalDistributionSampling
+ stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05]
+ cost_functions:
+ - class: stomp_moveit/CollisionCheck
+ collision_penalty: 1.0
+ cost_weight: 1.0
+ kernel_window_percentage: 0.2
+ longest_valid_joint_move: 0.05
+ noisy_filters:
+ - class: stomp_moveit/JointLimits
+ lock_start: True
+ lock_goal: True
+ - class: stomp_moveit/MultiTrajectoryVisualization
+ line_width: 0.02
+ rgb: [255, 255, 0]
+ marker_array_topic: stomp_trajectories
+ marker_namespace: noisy
+ update_filters:
+ - class: stomp_moveit/PolynomialSmoother
+ poly_order: 6
+ - class: stomp_moveit/TrajectoryVisualization
+ line_width: 0.05
+ rgb: [0, 191, 255]
+ error_rgb: [255, 0, 0]
+ publish_intermediate: True
+ marker_topic: stomp_trajectory
+ marker_namespace: optimized
+stomp/air_left_arm:
+ group_name: air_left_arm
+ optimization:
+ num_timesteps: 60
+ num_iterations: 40
+ num_iterations_after_valid: 0
+ num_rollouts: 30
+ max_rollouts: 30
+ initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
+ control_cost_weight: 0.0
+ task:
+ noise_generator:
+ - class: stomp_moveit/NormalDistributionSampling
+ stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05]
+ cost_functions:
+ - class: stomp_moveit/CollisionCheck
+ collision_penalty: 1.0
+ cost_weight: 1.0
+ kernel_window_percentage: 0.2
+ longest_valid_joint_move: 0.05
+ noisy_filters:
+ - class: stomp_moveit/JointLimits
+ lock_start: True
+ lock_goal: True
+ - class: stomp_moveit/MultiTrajectoryVisualization
+ line_width: 0.02
+ rgb: [255, 255, 0]
+ marker_array_topic: stomp_trajectories
+ marker_namespace: noisy
+ update_filters:
+ - class: stomp_moveit/PolynomialSmoother
+ poly_order: 6
+ - class: stomp_moveit/TrajectoryVisualization
+ line_width: 0.05
+ rgb: [0, 191, 255]
+ error_rgb: [255, 0, 0]
+ publish_intermediate: True
+ marker_topic: stomp_trajectory
+ marker_namespace: optimized
+stomp/gripper:
+ group_name: gripper
+ optimization:
+ num_timesteps: 60
+ num_iterations: 40
+ num_iterations_after_valid: 0
+ num_rollouts: 30
+ max_rollouts: 30
+ initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
+ control_cost_weight: 0.0
+ task:
+ noise_generator:
+ - class: stomp_moveit/NormalDistributionSampling
+ stddev: [0.05]
+ cost_functions:
+ - class: stomp_moveit/CollisionCheck
+ collision_penalty: 1.0
+ cost_weight: 1.0
+ kernel_window_percentage: 0.2
+ longest_valid_joint_move: 0.05
+ noisy_filters:
+ - class: stomp_moveit/JointLimits
+ lock_start: True
+ lock_goal: True
+ - class: stomp_moveit/MultiTrajectoryVisualization
+ line_width: 0.02
+ rgb: [255, 255, 0]
+ marker_array_topic: stomp_trajectories
+ marker_namespace: noisy
+ update_filters:
+ - class: stomp_moveit/PolynomialSmoother
+ poly_order: 6
+ - class: stomp_moveit/TrajectoryVisualization
+ line_width: 0.05
+ rgb: [0, 191, 255]
+ error_rgb: [255, 0, 0]
+ publish_intermediate: True
+ marker_topic: stomp_trajectory
+ marker_namespace: optimized
\ No newline at end of file
diff --git a/air_dual_arm_config/launch/air_dual_arm_description_moveit_sensor_manager.launch.xml b/air_dual_arm_config/launch/air_dual_arm_description_moveit_sensor_manager.launch.xml
new file mode 100644
index 0000000..5d02698
--- /dev/null
+++ b/air_dual_arm_config/launch/air_dual_arm_description_moveit_sensor_manager.launch.xml
@@ -0,0 +1,3 @@
+
+
+
diff --git a/air_dual_arm_config/launch/chomp_planning_pipeline.launch.xml b/air_dual_arm_config/launch/chomp_planning_pipeline.launch.xml
new file mode 100644
index 0000000..490bb05
--- /dev/null
+++ b/air_dual_arm_config/launch/chomp_planning_pipeline.launch.xml
@@ -0,0 +1,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/default_warehouse_db.launch b/air_dual_arm_config/launch/default_warehouse_db.launch
new file mode 100644
index 0000000..87ca767
--- /dev/null
+++ b/air_dual_arm_config/launch/default_warehouse_db.launch
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/demo.launch b/air_dual_arm_config/launch/demo.launch
new file mode 100644
index 0000000..eb5426b
--- /dev/null
+++ b/air_dual_arm_config/launch/demo.launch
@@ -0,0 +1,67 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ [move_group/fake_controller_joint_states]
+
+
+
+ [move_group/fake_controller_joint_states]
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/demo_gazebo.launch b/air_dual_arm_config/launch/demo_gazebo.launch
new file mode 100644
index 0000000..0ef8f95
--- /dev/null
+++ b/air_dual_arm_config/launch/demo_gazebo.launch
@@ -0,0 +1,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/fake_moveit_controller_manager.launch.xml b/air_dual_arm_config/launch/fake_moveit_controller_manager.launch.xml
new file mode 100644
index 0000000..ab3ee7c
--- /dev/null
+++ b/air_dual_arm_config/launch/fake_moveit_controller_manager.launch.xml
@@ -0,0 +1,12 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/gazebo.launch b/air_dual_arm_config/launch/gazebo.launch
new file mode 100644
index 0000000..0ad83fe
--- /dev/null
+++ b/air_dual_arm_config/launch/gazebo.launch
@@ -0,0 +1,34 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/joystick_control.launch b/air_dual_arm_config/launch/joystick_control.launch
new file mode 100644
index 0000000..9411f6e
--- /dev/null
+++ b/air_dual_arm_config/launch/joystick_control.launch
@@ -0,0 +1,17 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/move_group.launch b/air_dual_arm_config/launch/move_group.launch
new file mode 100644
index 0000000..6342755
--- /dev/null
+++ b/air_dual_arm_config/launch/move_group.launch
@@ -0,0 +1,105 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/moveit.rviz b/air_dual_arm_config/launch/moveit.rviz
new file mode 100644
index 0000000..79dd0cd
--- /dev/null
+++ b/air_dual_arm_config/launch/moveit.rviz
@@ -0,0 +1,672 @@
+Panels:
+ - Class: rviz/Displays
+ Help Height: 84
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /MotionPlanning1
+ - /MotionPlanning1/Planning Request1
+ - /MotionPlanning1/Planning Metrics1
+ - /MotionPlanning1/Planned Path1
+ Splitter Ratio: 0.5
+ Tree Height: 215
+ - Class: rviz/Help
+ Name: Help
+ - Class: rviz/Views
+ Expanded:
+ - /Current View1
+ Name: Views
+ Splitter Ratio: 0.5
+Preferences:
+ PromptSaveOnExit: true
+Toolbars:
+ toolButtonStyle: 2
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Alpha: 0.5
+ Cell Size: 1
+ Class: rviz/Grid
+ Color: 160; 160; 164
+ Enabled: true
+ Line Style:
+ Line Width: 0.029999999329447746
+ Value: Lines
+ Name: Grid
+ Normal Cell Count: 0
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Plane: XY
+ Plane Cell Count: 10
+ Reference Frame:
+ Value: true
+ - Acceleration_Scaling_Factor: 0.1
+ Class: moveit_rviz_plugin/MotionPlanning
+ Enabled: true
+ Move Group Namespace: ""
+ MoveIt_Allow_Approximate_IK: false
+ MoveIt_Allow_External_Program: false
+ MoveIt_Allow_Replanning: false
+ MoveIt_Allow_Sensor_Positioning: false
+ MoveIt_Planning_Attempts: 10
+ MoveIt_Planning_Time: 5
+ MoveIt_Use_Cartesian_Path: false
+ MoveIt_Use_Constraint_Aware_IK: false
+ MoveIt_Workspace:
+ Center:
+ X: 0
+ Y: 0
+ Z: 0
+ Size:
+ X: 2
+ Y: 2
+ Z: 2
+ Name: MotionPlanning
+ Planned Path:
+ Color Enabled: false
+ Interrupt Display: false
+ Links:
+ All Links Enabled: true
+ Expand Joint Details: false
+ Expand Link Details: false
+ Expand Tree: false
+ Link Tree Style: Links in Alphabetic Order
+ base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ e:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ e_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ pitch:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ pitch_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_end_effector_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_index_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_index_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_index_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_little_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_little_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_little_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_middle_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_middle_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_middle_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_palm_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_ring_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_ring_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_synergy_tendon_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_thumb_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_thumb_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_thumb_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_thumb_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_thumb_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ roll:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ roll_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ root_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ s1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s1_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s2_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s3_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ tool0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Loop Animation: false
+ Robot Alpha: 0.5
+ Robot Color: 150; 50; 150
+ Show Robot Collision: false
+ Show Robot Visual: true
+ Show Trail: false
+ State Display Time: 0.05 s
+ Trail Step Size: 1
+ Trajectory Topic: move_group/display_planned_path
+ Use Sim Time: false
+ Planning Metrics:
+ Payload: 1
+ Show Joint Torques: false
+ Show Manipulability: false
+ Show Manipulability Index: false
+ Show Weight Limit: false
+ TextHeight: 0.07999999821186066
+ Planning Request:
+ Colliding Link Color: 255; 0; 0
+ Goal State Alpha: 1
+ Goal State Color: 250; 128; 0
+ Interactive Marker Size: 0
+ Joint Violation Color: 255; 0; 255
+ Planning Group: air_right_arm
+ Query Goal State: true
+ Query Start State: false
+ Show Workspace: false
+ Start State Alpha: 1
+ Start State Color: 0; 255; 0
+ Planning Scene Topic: move_group/monitored_planning_scene
+ Robot Description: robot_description
+ Scene Geometry:
+ Scene Alpha: 1
+ Scene Color: 50; 230; 50
+ Scene Display Time: 0.009999999776482582
+ Show Scene Geometry: true
+ Voxel Coloring: Z-Axis
+ Voxel Rendering: Occupied Voxels
+ Scene Robot:
+ Attached Body Color: 150; 50; 150
+ Links:
+ All Links Enabled: true
+ Expand Joint Details: false
+ Expand Link Details: false
+ Expand Tree: false
+ Link Tree Style: Links in Alphabetic Order
+ base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ camera_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ e:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ e_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ pitch:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ pitch_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_base_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_end_effector_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_index_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_index_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_index_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_index_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_little_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_little_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_little_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_little_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_middle_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_middle_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_middle_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_middle_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_palm_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_ring_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_middle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_middle_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_ring_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_ring_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_synergy_tendon_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_thumb_distal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_thumb_distal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ qbhand_thumb_knuckle_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_thumb_proximal_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ qbhand_thumb_proximal_virtual_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ roll:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ roll_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ root_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ s1:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s1_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s2_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s3:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ s3_2:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ tool0:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Robot Alpha: 0.5
+ Show Robot Collision: false
+ Show Robot Visual: true
+ Value: true
+ Velocity_Scaling_Factor: 0.1
+ Enabled: true
+ Global Options:
+ Background Color: 48; 48; 48
+ Default Light: true
+ Fixed Frame: base_link
+ Frame Rate: 30
+ Name: root
+ Tools:
+ - Class: rviz/Interact
+ Hide Inactive Objects: true
+ - Class: rviz/MoveCamera
+ - Class: rviz/Select
+ Value: true
+ Views:
+ Current:
+ Class: rviz/Orbit
+ Distance: 2.1047396659851074
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Field of View: 0.75
+ Focal Point:
+ X: -0.38282260298728943
+ Y: -0.12503071129322052
+ Z: 0.5546161532402039
+ Focal Shape Fixed Size: true
+ Focal Shape Size: 0.05000000074505806
+ Invert Z Axis: false
+ Name: Current View
+ Near Clip Distance: 0.009999999776482582
+ Pitch: 0.5649999380111694
+ Target Frame: base_link
+ Yaw: 6.1649580001831055
+ Saved: ~
+Window Geometry:
+ Displays:
+ collapsed: false
+ Height: 848
+ Help:
+ collapsed: false
+ Hide Left Dock: false
+ Hide Right Dock: false
+ MotionPlanning:
+ collapsed: false
+ MotionPlanning - Trajectory Slider:
+ collapsed: false
+ QMainWindow State: 000000ff00000000fd0000000100000000000001f3000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000168000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001ab000001880000017d00ffffff00000312000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+ Views:
+ collapsed: false
+ Width: 1291
+ X: 454
+ Y: 27
diff --git a/air_dual_arm_config/launch/moveit_rviz.launch b/air_dual_arm_config/launch/moveit_rviz.launch
new file mode 100644
index 0000000..a4605c0
--- /dev/null
+++ b/air_dual_arm_config/launch/moveit_rviz.launch
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/ompl-chomp_planning_pipeline.launch.xml b/air_dual_arm_config/launch/ompl-chomp_planning_pipeline.launch.xml
new file mode 100644
index 0000000..7c94c90
--- /dev/null
+++ b/air_dual_arm_config/launch/ompl-chomp_planning_pipeline.launch.xml
@@ -0,0 +1,20 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/ompl_planning_pipeline.launch.xml b/air_dual_arm_config/launch/ompl_planning_pipeline.launch.xml
new file mode 100644
index 0000000..9e58d11
--- /dev/null
+++ b/air_dual_arm_config/launch/ompl_planning_pipeline.launch.xml
@@ -0,0 +1,24 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/air_dual_arm_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
new file mode 100644
index 0000000..c7c4cf5
--- /dev/null
+++ b/air_dual_arm_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/planning_context.launch b/air_dual_arm_config/launch/planning_context.launch
new file mode 100644
index 0000000..fc65a53
--- /dev/null
+++ b/air_dual_arm_config/launch/planning_context.launch
@@ -0,0 +1,26 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/planning_pipeline.launch.xml b/air_dual_arm_config/launch/planning_pipeline.launch.xml
new file mode 100644
index 0000000..4b4d0d6
--- /dev/null
+++ b/air_dual_arm_config/launch/planning_pipeline.launch.xml
@@ -0,0 +1,10 @@
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/ros_control_moveit_controller_manager.launch.xml b/air_dual_arm_config/launch/ros_control_moveit_controller_manager.launch.xml
new file mode 100644
index 0000000..9ebc91c
--- /dev/null
+++ b/air_dual_arm_config/launch/ros_control_moveit_controller_manager.launch.xml
@@ -0,0 +1,4 @@
+
+
+
+
diff --git a/air_dual_arm_config/launch/ros_controllers.launch b/air_dual_arm_config/launch/ros_controllers.launch
new file mode 100644
index 0000000..b8e0a54
--- /dev/null
+++ b/air_dual_arm_config/launch/ros_controllers.launch
@@ -0,0 +1,11 @@
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/run_benchmark_ompl.launch b/air_dual_arm_config/launch/run_benchmark_ompl.launch
new file mode 100644
index 0000000..7caebc1
--- /dev/null
+++ b/air_dual_arm_config/launch/run_benchmark_ompl.launch
@@ -0,0 +1,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/sensor_manager.launch.xml b/air_dual_arm_config/launch/sensor_manager.launch.xml
new file mode 100644
index 0000000..90ea339
--- /dev/null
+++ b/air_dual_arm_config/launch/sensor_manager.launch.xml
@@ -0,0 +1,17 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/setup_assistant.launch b/air_dual_arm_config/launch/setup_assistant.launch
new file mode 100644
index 0000000..2ac39dc
--- /dev/null
+++ b/air_dual_arm_config/launch/setup_assistant.launch
@@ -0,0 +1,16 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/simple_moveit_controller_manager.launch.xml b/air_dual_arm_config/launch/simple_moveit_controller_manager.launch.xml
new file mode 100644
index 0000000..00ad41e
--- /dev/null
+++ b/air_dual_arm_config/launch/simple_moveit_controller_manager.launch.xml
@@ -0,0 +1,8 @@
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/stomp_planning_pipeline.launch.xml b/air_dual_arm_config/launch/stomp_planning_pipeline.launch.xml
new file mode 100644
index 0000000..ee30a9e
--- /dev/null
+++ b/air_dual_arm_config/launch/stomp_planning_pipeline.launch.xml
@@ -0,0 +1,23 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/trajectory_execution.launch.xml b/air_dual_arm_config/launch/trajectory_execution.launch.xml
new file mode 100644
index 0000000..20c3dfc
--- /dev/null
+++ b/air_dual_arm_config/launch/trajectory_execution.launch.xml
@@ -0,0 +1,23 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/warehouse.launch b/air_dual_arm_config/launch/warehouse.launch
new file mode 100644
index 0000000..0712e67
--- /dev/null
+++ b/air_dual_arm_config/launch/warehouse.launch
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/launch/warehouse_settings.launch.xml b/air_dual_arm_config/launch/warehouse_settings.launch.xml
new file mode 100644
index 0000000..e473b08
--- /dev/null
+++ b/air_dual_arm_config/launch/warehouse_settings.launch.xml
@@ -0,0 +1,16 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/air_dual_arm_config/package.xml b/air_dual_arm_config/package.xml
new file mode 100644
index 0000000..806b4ae
--- /dev/null
+++ b/air_dual_arm_config/package.xml
@@ -0,0 +1,41 @@
+
+
+ air_dual_arm_config
+ 0.3.0
+
+ An automatically generated package with all the configuration and launch files for using the air_dual_arm_description with the MoveIt Motion Planning Framework
+
+ Cenk Çetin
+ Cenk Çetin
+
+ BSD
+
+ http://moveit.ros.org/
+ https://github.com/ros-planning/moveit/issues
+ https://github.com/ros-planning/moveit
+
+ catkin
+
+ moveit_ros_move_group
+ moveit_fake_controller_manager
+ moveit_kinematics
+ moveit_planners
+ moveit_ros_visualization
+ moveit_setup_assistant
+ moveit_simple_controller_manager
+ joint_state_publisher
+ joint_state_publisher_gui
+ robot_state_publisher
+ rviz
+ tf2_ros
+ xacro
+
+
+
+
+
+ air_dual_arm_description
+
+
+
diff --git a/air_dual_arm_description/config/joint_names_ARL1_00.yaml b/air_dual_arm_description/config/joint_names_ARL1_00.yaml
new file mode 100644
index 0000000..ec26e96
--- /dev/null
+++ b/air_dual_arm_description/config/joint_names_ARL1_00.yaml
@@ -0,0 +1 @@
+controller_joint_names: ['', 's1_2j', 's2_2j', 's3_2j', 'e_2j', 'roll_2j', 'pitch_2j', 'yaw_2j', ]
diff --git a/air_dual_arm_description/launch/gazebo.launch b/air_dual_arm_description/launch/gazebo.launch
index 0fab05b..2d0ca95 100644
--- a/air_dual_arm_description/launch/gazebo.launch
+++ b/air_dual_arm_description/launch/gazebo.launch
@@ -10,7 +10,7 @@
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
- args="-file $(find air_dual_arm_description)/urdf/air_dual_arm.urdf -urdf -model air_dual_arm"
+ args="-file $(find ARL1_00)/urdf/ARL1_00.urdf -urdf -model ARL1_00"
output="screen" />
air_dual_arm_description
1.0.0
- URDF Description package for air_dual_arm_description
+ URDF Description package for ARL1_00
This package contains configuration data, 3D models and launch files
-for air_dual_arm_description robot
+for ARL1_00 robot
TODO
diff --git a/air_dual_arm_description/urdf/air_dual_arm.urdf b/air_dual_arm_description/urdf/air_dual_arm.urdf
new file mode 100644
index 0000000..827e743
--- /dev/null
+++ b/air_dual_arm_description/urdf/air_dual_arm.urdf
@@ -0,0 +1,2520 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ transmission_interface/qbMoveTransmission
+
+ hardware_interface/EffortJointInterface
+
+
+ hardware_interface/EffortJointInterface
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file