Skip to content

Commit

Permalink
Place ompl_planning.yaml to each robot
Browse files Browse the repository at this point in the history
  • Loading branch information
pazeshun committed Jan 19, 2018
1 parent d3e9ccd commit 522b16f
Show file tree
Hide file tree
Showing 8 changed files with 90 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,9 @@
<arg name="publish_monitored_planning_scene" default="true"/>

<!-- Planning Functionality -->
<include ns="move_group" file="$(find jsk_arc2017_baxter)/launch/setup/include/moveit/common/ompl_planning_pipeline.launch" />
<include ns="move_group" file="$(find jsk_arc2017_baxter)/launch/setup/include/moveit/common/ompl_planning_pipeline.launch">
<arg name="robot" value="$(arg robot)"/>
</include>

<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(find jsk_arc2017_baxter)/launch/setup/include/moveit/$(arg robot)/$(arg robot)_trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
<launch>

<arg name="robot" dafault="baxter"/>

<!-- OMPL Plugin for MoveIt! -->
<arg name="planning_plugin" value="ompl_interface/OMPLPlanner" />

Expand All @@ -18,6 +20,6 @@
<param name="start_state_max_bounds_error" value="$(arg start_state_max_bounds_error)" />

<rosparam command="load" file="$(find baxter_moveit_config)/config/kinematics.yaml"/>
<rosparam command="load" file="$(find jsk_arc2017_baxter)/robots/moveit_config/common/ompl_planning.yaml"/>
<rosparam command="load" file="$(find jsk_arc2017_baxter)/robots/moveit_config/$(robot)/ompl_planning.yaml"/>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/baxter/baxter_base.srdf.xacro" />
<xacro:baxter_base left_tip_name="$(arg left_tip_name)" right_tip_name="$(arg right_tip_name)"/>
<!--Left End Effector Collisions-->
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/common/gripper_v6.srdf.xacro" />
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/grippers/gripper_v6.srdf.xacro" />
<xacro:vacuum_gripper side="left"/>
<!--Right End Effector Collisions-->
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/common/gripper_v6.srdf.xacro" />
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/grippers/gripper_v6.srdf.xacro" />
<xacro:vacuum_gripper side="right"/>
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/baxterlgv7/baxterlgv7_base.srdf.xacro" />
<xacro:baxterlgv7_base left_tip_name="$(arg left_tip_name)" right_tip_name="$(arg right_tip_name)"/>
<!--Left End Effector Collisions-->
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/common/gripper_v7.srdf.xacro" />
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/grippers/gripper_v7.srdf.xacro" />
<xacro:vacuum_gripper side="left"/>
<!--Right End Effector Collisions-->
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/common/gripper_v6.srdf.xacro" />
<xacro:include filename="$(find jsk_arc2017_baxter)/robots/moveit_config/grippers/gripper_v6.srdf.xacro" />
<xacro:vacuum_gripper side="right"/>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
planner_configs:
SBLkConfigDefault:
type: geometric::SBL
LBKPIECEkConfigDefault:
type: geometric::LBKPIECE
RRTkConfigDefault:
type: geometric::RRT
RRTConnectkConfigDefault:
type: geometric::RRTConnect
LazyRRTkConfigDefault:
type: geometric::LazyRRT
ESTkConfigDefault:
type: geometric::EST
KPIECEkConfigDefault:
type: geometric::KPIECE
RRTStarkConfigDefault:
type: geometric::RRTstar
BKPIECEkConfigDefault:
type: geometric::BKPIECE
left_arm:
default_planner_config: RRTConnectkConfigDefault
planner_configs:
- SBLkConfigDefault
- LBKPIECEkConfigDefault
- RRTkConfigDefault
- RRTConnectkConfigDefault
- ESTkConfigDefault
- KPIECEkConfigDefault
- BKPIECEkConfigDefault
- RRTStarkConfigDefault
projection_evaluator: joints(left_s0,left_s1)
longest_valid_segment_fraction: 0.01
right_arm:
default_planner_config: RRTConnectkConfigDefault
planner_configs:
- SBLkConfigDefault
- LBKPIECEkConfigDefault
- RRTkConfigDefault
- RRTConnectkConfigDefault
- ESTkConfigDefault
- KPIECEkConfigDefault
- BKPIECEkConfigDefault
- RRTStarkConfigDefault
projection_evaluator: joints(right_s0,right_s1)
longest_valid_segment_fraction: 0.01
both_arms:
default_planner_config: RRTConnectkConfigDefault
planner_configs:
- SBLkConfigDefault
- LBKPIECEkConfigDefault
- RRTkConfigDefault
- RRTConnectkConfigDefault
- ESTkConfigDefault
- KPIECEkConfigDefault
- BKPIECEkConfigDefault
- RRTStarkConfigDefault
projection_evaluator: joints(right_s0,right_s1)
longest_valid_segment_fraction: 0.01
left_hand:
default_planner_config: RRTConnectkConfigDefault
planner_configs:
- SBLkConfigDefault
- LBKPIECEkConfigDefault
- RRTkConfigDefault
- RRTConnectkConfigDefault
- ESTkConfigDefault
- KPIECEkConfigDefault
- BKPIECEkConfigDefault
- RRTStarkConfigDefault
right_hand:
default_planner_config: RRTConnectkConfigDefault
planner_configs:
- SBLkConfigDefault
- LBKPIECEkConfigDefault
- RRTkConfigDefault
- RRTConnectkConfigDefault
- ESTkConfigDefault
- KPIECEkConfigDefault
- BKPIECEkConfigDefault
- RRTStarkConfigDefault

0 comments on commit 522b16f

Please sign in to comment.