Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 12 additions & 3 deletions nextage_moveit_config/config/NextageOpen.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,18 @@
<joint name="LARM_JOINT5" />
</group>
<group name="botharms">
<group name="right_arm" />
<group name="left_arm" />
<group name="torso" />
<joint name="LARM_JOINT0" />
<joint name="LARM_JOINT1" />
<joint name="LARM_JOINT2" />
<joint name="LARM_JOINT3" />
<joint name="LARM_JOINT4" />
<joint name="LARM_JOINT5" />
<joint name="RARM_JOINT0" />
<joint name="RARM_JOINT1" />
<joint name="RARM_JOINT2" />
<joint name="RARM_JOINT3" />
<joint name="RARM_JOINT4" />
<joint name="RARM_JOINT5" />
</group>
<group name="head">
<joint name="HEAD_JOINT0" />
Expand Down
16 changes: 16 additions & 0 deletions nextage_moveit_config/config/controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,22 @@ controller_list:
- LARM_JOINT3
- LARM_JOINT4
- LARM_JOINT5
- name: botharms_controller
action_ns: follow_joint_trajectory_action
default: true
joints:
- LARM_JOINT0
- LARM_JOINT1
- LARM_JOINT2
- LARM_JOINT3
- LARM_JOINT4
- LARM_JOINT5
- RARM_JOINT0
- RARM_JOINT1
- RARM_JOINT2
- RARM_JOINT3
- RARM_JOINT4
- RARM_JOINT5
- name: head_controller
action_ns: follow_joint_trajectory_action
joints:
Expand Down
5 changes: 5 additions & 0 deletions nextage_moveit_config/config/kinematics_ikfast.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,11 @@ left_arm:
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
botharms:
kinematics_solver: nextage_right_arm_kinematics/IKFastKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
head:
kinematics_solver: nextage_right_arm_kinematics/IKFastKinematicsPlugin
kinematics_solver_search_resolution: 0.005
Expand Down
5 changes: 5 additions & 0 deletions nextage_moveit_config/config/kinematics_kdl.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,11 @@ left_arm:
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
botharms:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
kinematics_solver_timeout: 0.005
kinematics_solver_attempts: 3
head:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005
Expand Down
2 changes: 1 addition & 1 deletion nextage_moveit_config/config/ompl_planning.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ botharms:
- TRRTkConfigDefault
- PRMkConfigDefault
- PRMstarkConfigDefault
projection_evaluator: joints(LARM_JOINT0,LARM_JOINT1)
projection_evaluator: joints(LARM_JOINT0,RARM_JOINT0)
longest_valid_segment_fraction: 0.05
head:
planner_configs:
Expand Down