|
From: <is...@us...> - 2009-06-07 21:59:33
|
Revision: 16826
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=16826&view=rev
Author: isucan
Date: 2009-06-07 21:59:26 +0000 (Sun, 07 Jun 2009)
Log Message:
-----------
moved configuration for pr2 collision checking & planning
Modified Paths:
--------------
pkg/trunk/motion_planning/ompl_planning/motion_planning.launch
pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
Added Paths:
-----------
pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/
pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_both_arms.yaml
pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_left_arm.yaml
pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_right_arm.yaml
pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/
pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml
pkg/trunk/robot_descriptions/pr2/pr2_defs/pr2_description.launch
Removed Paths:
-------------
pkg/trunk/motion_planning/planning_environment/collision_checks.yaml
pkg/trunk/motion_planning/planning_environment/planning.yaml
pkg/trunk/motion_planning/planning_environment/planning_environment.launch
Modified: pkg/trunk/motion_planning/ompl_planning/motion_planning.launch
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/motion_planning.launch 2009-06-07 20:12:31 UTC (rev 16825)
+++ pkg/trunk/motion_planning/ompl_planning/motion_planning.launch 2009-06-07 21:59:26 UTC (rev 16826)
@@ -2,9 +2,9 @@
<launch>
<!--
<param name="robotdesc/pr2" command="$(find xacro)/xacro.py '$(find pr2_defs)/robots/pr2.xacro.xml'" />
--->
<rosparam command="load" ns="robotdesc/pr2_planning" file="$(find planning_environment)/planning.yaml" />
<rosparam command="load" ns="robotdesc/pr2_collision" file="$(find planning_environment)/collision_checks.yaml" />
+-->
<node pkg="ompl_planning" type="motion_planner" args="robot_description:=robotdesc/pr2 collision_map:=collision_map_buffer" respawn="true" output="screen">
<param name="refresh_interval_collision_map" type="double" value="0.0" />
<param name="refresh_interval_kinematic_state" type="double" value="0.0" />
Deleted: pkg/trunk/motion_planning/planning_environment/collision_checks.yaml
===================================================================
--- pkg/trunk/motion_planning/planning_environment/collision_checks.yaml 2009-06-07 20:12:31 UTC (rev 16825)
+++ pkg/trunk/motion_planning/planning_environment/collision_checks.yaml 2009-06-07 21:59:26 UTC (rev 16826)
@@ -1,90 +0,0 @@
-## This file should be loaded under <robot description>_collision
-
-
-## links for which collision checking with the environment should be performed
-collision_links:
- base_link
- torso_lift_link
- head_pan_link
- head_tilt_link
- r_shoulder_pan_link
- r_shoulder_lift_link
- r_upper_arm_roll_link
- r_upper_arm_link
- r_elbow_flex_link
- r_forearm_roll_link
- r_forearm_link
- r_wrist_flex_link
- r_wrist_roll_link
- r_gripper_palm_link
- r_gripper_l_finger_link
- r_gripper_r_finger_link
- r_gripper_l_finger_tip_link
- r_gripper_r_finger_tip_link
-
-## self collision is performed between groups of links, usually pairs
-self_collision_groups: scg1 scg2 scg3 scg4 scg5 scg6
-
-scg1:
- r_forearm_link
- base_link
-
-scg2:
- r_gripper_palm_link
- base_link
-
-scg3:
- r_gripper_l_finger_link
- base_link
-
-scg4:
- r_gripper_r_finger_link
- base_link
-
-scg5:
- r_gripper_l_finger_tip_link
- base_link
-
-scg6:
- r_gripper_r_finger_tip_link
- base_link
-
-
-## list of links that the robot can see with its sensors (used to remove
-## parts of the robot from scanned data)
-self_see:
- r_upper_arm_link
- l_upper_arm_link
- l_upper_arm_roll_link
- r_upper_arm_roll_link
- l_elbow_flex_link
- r_elbow_flex_link
- r_forearm_link
- l_forearm_link
- l_forearm_roll_link
- r_forearm_roll_link
- l_wrist_flex_link
- r_wrist_flex_link
- l_wrist_roll_link
- r_wrist_roll_link
- l_gripper_l_finger_link
- l_gripper_l_finger_tip_link
- l_gripper_r_finger_link
- l_gripper_r_finger_tip_link
- r_gripper_l_finger_link
- r_gripper_l_finger_tip_link
- r_gripper_r_finger_link
- r_gripper_r_finger_tip_link
- r_shoulder_pan_link
- r_shoulder_lift_link
- l_shoulder_pan_link
- l_shoulder_lift_link
- torso_lift_link
- base_link
-
-
-## The padding to be added for the body parts the robot can see
-self_see_padd: 0.0
-
-## The scaling to be considered for the body parts the robot can see
-self_see_scale: 1.0
Modified: pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h
===================================================================
--- pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-06-07 20:12:31 UTC (rev 16825)
+++ pkg/trunk/motion_planning/planning_environment/include/planning_environment/robot_models.h 2009-06-07 21:59:26 UTC (rev 16826)
@@ -124,7 +124,7 @@
return self_see_links_;
}
- const std::vector< std::vector<std::string> > &getSelfCollisionGroups(void) const
+ const std::vector< std::pair < std::vector<std::string>, std::vector<std::string> > > &getSelfCollisionGroups(void) const
{
return self_collision_check_groups_;
}
@@ -153,7 +153,7 @@
void getSelfSeeLinks(std::vector<std::string> &links);
void getCollisionCheckLinks(std::vector<std::string> &links);
- void getSelfCollisionGroups(std::vector< std::vector<std::string> > &groups);
+ void getSelfCollisionGroups(std::vector< std::pair < std::vector<std::string>, std::vector<std::string> > > &groups);
ros::NodeHandle nh_;
@@ -166,7 +166,8 @@
std::map< std::string, std::vector<std::string> > planning_groups_;
std::vector<std::string> self_see_links_;
std::vector<std::string> collision_check_links_;
- std::vector< std::vector<std::string> > self_collision_check_groups_;
+ std::vector< std::pair < std::vector<std::string>, std::vector<std::string> > >
+ self_collision_check_groups_;
};
Deleted: pkg/trunk/motion_planning/planning_environment/planning.yaml
===================================================================
--- pkg/trunk/motion_planning/planning_environment/planning.yaml 2009-06-07 20:12:31 UTC (rev 16825)
+++ pkg/trunk/motion_planning/planning_environment/planning.yaml 2009-06-07 21:59:26 UTC (rev 16826)
@@ -1,74 +0,0 @@
-## This file should be loaded under <robot description>_planning
-
-## the list of groups for which motion planning can be performed
-group_list:
- base
- left_arm
- right_arm
- arms
- base_left_arm
- base_right_arm
- base_arms
-
-## the definition of each group
-groups:
-
- base:
- links:
- base_link
- planner_configs:
- RRTConfig1 SBLConfig1
-
- left_arm:
- links:
- l_shoulder_pan_link
- l_shoulder_lift_link
- l_upper_arm_roll_link
- l_upper_arm_link
- l_elbow_flex_link
- l_forearm_roll_link
- l_forearm_link
- l_wrist_flex_link
- l_wrist_roll_link
- planner_configs:
- RRTConfig2 SBLConfig2
-
- right_arm:
- links:
- r_shoulder_pan_link
- r_shoulder_lift_link
- r_upper_arm_roll_link
- r_upper_arm_link
- r_elbow_flex_link
- r_forearm_roll_link
- r_forearm_link
- r_wrist_flex_link
- r_wrist_roll_link
- planner_configs:
- RRTConfig2 SBLConfig2
-
-## the planner configurations; each config must have a type, which specifies
-## the planner to be used; other parameters can be specified as well
-
-planner_configs:
-
- RRTConfig1:
- type: RRT
- range: 0.75
-
- SBLConfig1:
- type: SBL
- projection: 0 1
- celldim: 1 1
- range: 0.5
-
- RRTConfig2:
- type: RRT
- range: 0.75
-
- SBLConfig2:
- type: SBL
- projection: 5 6
- celldim: 0.1 0.1
-
-
\ No newline at end of file
Deleted: pkg/trunk/motion_planning/planning_environment/planning_environment.launch
===================================================================
--- pkg/trunk/motion_planning/planning_environment/planning_environment.launch 2009-06-07 20:12:31 UTC (rev 16825)
+++ pkg/trunk/motion_planning/planning_environment/planning_environment.launch 2009-06-07 21:59:26 UTC (rev 16826)
@@ -1,8 +0,0 @@
-
-<launch>
-
- <param name="robotdesc/pr2" command="$(find xacro)/xacro.py '$(find pr2_defs)/robots/pr2.xacro.xml'" />
- <rosparam command="load" ns="robotdesc/pr2_planning" file="$(find planning_environment)/planning.yaml" />
- <rosparam command="load" ns="robotdesc/pr2_collision" file="$(find planning_environment)/collision_checks.yaml" />
-
-</launch>
Modified: pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-06-07 20:12:31 UTC (rev 16825)
+++ pkg/trunk/motion_planning/planning_environment/src/collision_models.cpp 2009-06-07 21:59:26 UTC (rev 16826)
@@ -45,8 +45,17 @@
{
ode_collision_model_->lock();
ode_collision_model_->addRobotModel(kmodel_, collision_check_links_, scale_, padd_);
+
+ // form all pairs of links that can collide and add them as self-collision groups
for (unsigned int i = 0 ; i < self_collision_check_groups_.size() ; ++i)
- ode_collision_model_->addSelfCollisionGroup(self_collision_check_groups_[i]);
+ for (unsigned int g1 = 0 ; g1 < self_collision_check_groups_[i].first.size() ; ++g1)
+ for (unsigned int g2 = 0 ; g2 < self_collision_check_groups_[i].second.size() ; ++g2)
+ {
+ std::vector<std::string> scg;
+ scg.push_back(self_collision_check_groups_[i].first[g1]);
+ scg.push_back(self_collision_check_groups_[i].second[g2]);
+ ode_collision_model_->addSelfCollisionGroup(scg);
+ }
ode_collision_model_->updateRobotModel();
ode_collision_model_->unlock();
}
Modified: pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-07 20:12:31 UTC (rev 16825)
+++ pkg/trunk/motion_planning/planning_environment/src/robot_models.cpp 2009-06-07 21:59:26 UTC (rev 16826)
@@ -167,7 +167,7 @@
}
}
-void planning_environment::RobotModels::getSelfCollisionGroups(std::vector< std::vector<std::string> > &groups)
+void planning_environment::RobotModels::getSelfCollisionGroups(std::vector< std::pair < std::vector<std::string>, std::vector<std::string> > > &groups)
{
std::string group_list;
nh_.param(description_ + "_collision/self_collision_groups", group_list, std::string(""));
@@ -179,21 +179,40 @@
group_list_stream >> name;
if (name.size() == 0)
continue;
- nh_.param(description_ + "_collision/" + name, group_elems, std::string(""));
- std::stringstream group_elems_stream(group_elems);
- std::vector<std::string> this_group;
- while (group_elems_stream.good() && !group_elems_stream.eof())
+
+ std::pair < std::vector<std::string>, std::vector<std::string> > this_group;
+
+ // read part 'a'
+ nh_.param(description_ + "_collision/" + name + "/a", group_elems, std::string(""));
+ std::stringstream group_elems_stream_a(group_elems);
+ while (group_elems_stream_a.good() && !group_elems_stream_a.eof())
{
std::string link_name;
- group_elems_stream >> link_name;
+ group_elems_stream_a >> link_name;
if (link_name.size() == 0)
continue;
if (urdf_->getLink(link_name))
- this_group.push_back(link_name);
+ this_group.first.push_back(link_name);
else
ROS_ERROR("Unknown link: '%s'", link_name.c_str());
}
- if (this_group.size() > 0)
+
+ // read part 'b'
+ nh_.param(description_ + "_collision/" + name + "/b", group_elems, std::string(""));
+ std::stringstream group_elems_stream_b(group_elems);
+ while (group_elems_stream_b.good() && !group_elems_stream_b.eof())
+ {
+ std::string link_name;
+ group_elems_stream_b >> link_name;
+ if (link_name.size() == 0)
+ continue;
+ if (urdf_->getLink(link_name))
+ this_group.second.push_back(link_name);
+ else
+ ROS_ERROR("Unknown link: '%s'", link_name.c_str());
+ }
+
+ if (this_group.first.size() > 0 && this_group.second.size() > 0)
groups.push_back(this_group);
}
}
Added: pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_both_arms.yaml
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_both_arms.yaml (rev 0)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_both_arms.yaml 2009-06-07 21:59:26 UTC (rev 16826)
@@ -0,0 +1,94 @@
+## This file should be loaded under <robot description>_collision
+
+
+## links for which collision checking with the environment should be performed
+collision_links:
+ base_link
+ torso_lift_link
+ head_pan_link
+ head_tilt_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ r_upper_arm_roll_link
+ r_upper_arm_link
+ r_elbow_flex_link
+ r_forearm_roll_link
+ r_forearm_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_palm_link
+ r_gripper_l_finger_link
+ r_gripper_r_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ l_upper_arm_roll_link
+ l_upper_arm_link
+ l_elbow_flex_link
+ l_forearm_roll_link
+ l_forearm_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_palm_link
+ l_gripper_l_finger_link
+ l_gripper_r_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_tip_link
+
+## self collision is performed between groups of links
+self_collision_groups: scg_r scg_l scg_lr
+
+## -- for right arm; self-collision if any link in 'a' collides with some link in 'b'
+scg_r:
+ a: r_forearm_link r_gripper_palm_link r_gripper_l_finger_link r_gripper_r_finger_link r_gripper_l_finger_tip_link r_gripper_r_finger_tip_link
+ b: base_link torso_lift_link laser_tilt_mount_link head_tilt_link
+
+## -- for left arm; self-collision if any link in 'a' collides with some link in 'b'
+scg_l:
+ a: l_forearm_link l_gripper_palm_link l_gripper_l_finger_link l_gripper_r_finger_link l_gripper_l_finger_tip_link l_gripper_r_finger_tip_link
+ b: base_link torso_lift_link laser_tilt_mount_link head_tilt_link
+
+## for arms with each other; self-collision if any link in 'a' collides with some link in 'b'
+scg_lr:
+ a: r_forearm_link r_gripper_palm_link r_gripper_l_finger_link r_gripper_r_finger_link r_gripper_l_finger_tip_link r_gripper_r_finger_tip_link
+ b: l_forearm_link l_gripper_palm_link l_gripper_l_finger_link l_gripper_r_finger_link l_gripper_l_finger_tip_link l_gripper_r_finger_tip_link
+
+## list of links that the robot can see with its sensors (used to remove
+## parts of the robot from scanned data)
+self_see:
+ l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ torso_lift_link
+ base_link
+
+
+## The padding to be added for the body parts the robot can see
+self_see_padd: 0.1
+
+## The scaling to be considered for the body parts the robot can see
+self_see_scale: 1.0
Added: pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_left_arm.yaml
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_left_arm.yaml (rev 0)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_left_arm.yaml 2009-06-07 21:59:26 UTC (rev 16826)
@@ -0,0 +1,57 @@
+## This file should be loaded under <robot description>_collision
+
+
+## links for which collision checking with the environment should be performed
+collision_links:
+ base_link
+ torso_lift_link
+ head_pan_link
+ head_tilt_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ l_upper_arm_roll_link
+ l_upper_arm_link
+ l_elbow_flex_link
+ l_forearm_roll_link
+ l_forearm_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_palm_link
+ l_gripper_l_finger_link
+ l_gripper_r_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_tip_link
+
+## self collision is performed between groups of links
+self_collision_groups: scg_l
+
+## -- for left arm; self-collision if any link in 'a' collides with some link in 'b'
+scg_l:
+ a: l_forearm_link l_gripper_palm_link l_gripper_l_finger_link l_gripper_r_finger_link l_gripper_l_finger_tip_link l_gripper_r_finger_tip_link
+ b: base_link torso_lift_link laser_tilt_mount_link head_tilt_link
+
+## list of links that the robot can see with its sensors (used to remove
+## parts of the robot from scanned data)
+self_see:
+ l_upper_arm_link
+ l_upper_arm_roll_link
+ l_elbow_flex_link
+ l_forearm_link
+ l_forearm_roll_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ l_gripper_l_finger_link
+ l_gripper_l_finger_tip_link
+ l_gripper_r_finger_link
+ l_gripper_r_finger_tip_link
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ torso_lift_link
+ base_link
+
+
+## The padding to be added for the body parts the robot can see
+self_see_padd: 0.1
+
+## The scaling to be considered for the body parts the robot can see
+self_see_scale: 1.0
Added: pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_right_arm.yaml
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_right_arm.yaml (rev 0)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/collision/collision_checks_right_arm.yaml 2009-06-07 21:59:26 UTC (rev 16826)
@@ -0,0 +1,57 @@
+## This file should be loaded under <robot description>_collision
+
+
+## links for which collision checking with the environment should be performed
+collision_links:
+ base_link
+ torso_lift_link
+ head_pan_link
+ head_tilt_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ r_upper_arm_roll_link
+ r_upper_arm_link
+ r_elbow_flex_link
+ r_forearm_roll_link
+ r_forearm_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_palm_link
+ r_gripper_l_finger_link
+ r_gripper_r_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_tip_link
+
+## self collision is performed between groups of links
+self_collision_groups: scg_r
+
+## -- for right arm; self-collision if any link in 'a' collides with some link in 'b'
+scg_r:
+ a: r_forearm_link r_gripper_palm_link r_gripper_l_finger_link r_gripper_r_finger_link r_gripper_l_finger_tip_link r_gripper_r_finger_tip_link
+ b: base_link torso_lift_link laser_tilt_mount_link head_tilt_link
+
+## list of links that the robot can see with its sensors (used to remove
+## parts of the robot from scanned data)
+self_see:
+ r_upper_arm_link
+ r_upper_arm_roll_link
+ r_elbow_flex_link
+ r_forearm_link
+ r_forearm_roll_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ r_gripper_l_finger_link
+ r_gripper_l_finger_tip_link
+ r_gripper_r_finger_link
+ r_gripper_r_finger_tip_link
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ torso_lift_link
+ base_link
+
+
+## The padding to be added for the body parts the robot can see
+self_see_padd: 0.1
+
+## The scaling to be considered for the body parts the robot can see
+self_see_scale: 1.0
Copied: pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml (from rev 16825, pkg/trunk/motion_planning/planning_environment/planning.yaml)
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml (rev 0)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/planning/planning.yaml 2009-06-07 21:59:26 UTC (rev 16826)
@@ -0,0 +1,90 @@
+## This file should be loaded under <robot description>_planning
+
+## the list of groups for which motion planning can be performed
+group_list:
+ base
+ left_arm
+ right_arm
+
+## the definition of each group
+groups:
+
+ base:
+ links:
+ base_link
+ planner_configs:
+ RRTConfig1 LazyRRTConfig1 SBLConfig1 KPIECEConfig1
+
+ left_arm:
+ links:
+ l_shoulder_pan_link
+ l_shoulder_lift_link
+ l_upper_arm_roll_link
+ l_upper_arm_link
+ l_elbow_flex_link
+ l_forearm_roll_link
+ l_forearm_link
+ l_wrist_flex_link
+ l_wrist_roll_link
+ planner_configs:
+ RRTConfig2 SBLConfig2 KPIECEConfig2l
+
+ right_arm:
+ links:
+ r_shoulder_pan_link
+ r_shoulder_lift_link
+ r_upper_arm_roll_link
+ r_upper_arm_link
+ r_elbow_flex_link
+ r_forearm_roll_link
+ r_forearm_link
+ r_wrist_flex_link
+ r_wrist_roll_link
+ planner_configs:
+ RRTConfig2 SBLConfig2 KPIECEConfig2r
+
+## the planner configurations; each config must have a type, which specifies
+## the planner to be used; other parameters can be specified as well, depending
+## on the planner
+
+planner_configs:
+
+ RRTConfig1:
+ type: RRT
+ range: 0.75
+
+ LazyRRTConfig1:
+ type: LazyRRT
+ range: 0.75
+
+ SBLConfig1:
+ type: SBL
+ projection: 0 1
+ celldim: 1 1
+ range: 0.5
+
+ KPIECEConfig1:
+ type: KPIECE
+ projection: 0 1
+ celldim: 1 1
+ range: 0.5
+
+ RRTConfig2:
+ type: RRT
+ range: 0.75
+
+ SBLConfig2:
+ type: SBL
+ projection: 5 6
+ celldim: 0.1 0.1
+
+ KPIECEConfig2l:
+ type: KPIECE
+ projection: link l_wrist_roll_link
+ celldim: 0.1 0.1 0.1
+
+ KPIECEConfig2r:
+ type: KPIECE
+ projection: link r_wrist_roll_link
+ celldim: 0.1 0.1 0.1
+
\ No newline at end of file
Added: pkg/trunk/robot_descriptions/pr2/pr2_defs/pr2_description.launch
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_defs/pr2_description.launch (rev 0)
+++ pkg/trunk/robot_descriptions/pr2/pr2_defs/pr2_description.launch 2009-06-07 21:59:26 UTC (rev 16826)
@@ -0,0 +1,11 @@
+
+<launch>
+ <!-- send pr2.xml to param server -->
+ <param name="robotdesc/pr2" command="$(find xacro)/xacro.py '$(find pr2_defs)/robots/pr2.xacro.xml'" />
+
+ <!-- send parameters for collision checking for PR2; this includes parameters for the self filter -->
+ <rosparam command="load" ns="robotdesc/pr2_collision" file="$(find pr2_defs)/collision/collision_checks_both_arms.yaml" />
+
+ <!-- send parameters needed for motion planning -->
+ <rosparam command="load" ns="robotdesc/pr2_planning" file="$(find pr2_defs)/planning/planning.yaml" />
+</launch>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|