|
From: <mr...@us...> - 2009-07-30 04:07:09
|
Revision: 20133
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=20133&view=rev
Author: mrinal
Date: 2009-07-30 04:06:52 +0000 (Thu, 30 Jul 2009)
Log Message:
-----------
We use the spline smoothed controller for move arm now.
Also moved some launch files to 3dnav_pr2
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/launch/move_larm.launch
pkg/trunk/highlevel/move_arm/launch/move_rarm.launch
pkg/trunk/sandbox/joint_waypoint_controller/launch/filters.xml
Added Paths:
-----------
pkg/trunk/sandbox/3dnav_pr2/launch/actions/
pkg/trunk/sandbox/3dnav_pr2/launch/actions/left_arm.launch
pkg/trunk/sandbox/3dnav_pr2/launch/actions/right_arm.launch
pkg/trunk/sandbox/joint_waypoint_controller/launch/l_arm_joint_waypoint_controller.launch
pkg/trunk/sandbox/joint_waypoint_controller/launch/r_arm_joint_waypoint_controller.launch
pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.yaml
pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.yaml
Removed Paths:
-------------
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/larm.launch
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm.launch
pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm_splines.launch
pkg/trunk/highlevel/move_arm/launch/move_rarm_splines.launch
pkg/trunk/sandbox/joint_waypoint_controller/launch/joint_waypoint_controller.launch
pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.xml
pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.yaml
Deleted: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/larm.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/larm.launch 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/larm.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,6 +0,0 @@
-<launch>
- <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
- <include file="$(find pr2_ik)/pr2_ik_larm_node.launch"/>
- <include file="$(find move_arm)/launch/move_larm.launch"/>
- <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/l_arm_joint_trajectory_controller.xml" />
-</launch>
Deleted: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm.launch 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,25 +0,0 @@
-<launch>
-
- <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
- <include file="$(find pr2_ik)/pr2_ik_rarm_node.launch"/>
- <include file="$(find move_arm)/launch/move_rarm.launch"/>
-
- <param name="r_arm_joint_trajectory_controller/r_shoulder_pan_joint/goal_reached_threshold" value="0.001" />
- <param name="r_arm_joint_trajectory_controller/r_shoulder_lift_joint/goal_reached_threshold" value="0.001" />
- <param name="r_arm_joint_trajectory_controller/r_upper_arm_roll_joint/goal_reached_threshold" value="0.001" />
- <param name="r_arm_joint_trajectory_controller/r_elbow_flex_joint/goal_reached_threshold" value="0.001" />
- <param name="r_arm_joint_trajectory_controller/r_forearm_roll_joint/goal_reached_threshold" value="0.001" />
- <param name="r_arm_joint_trajectory_controller/r_wrist_flex_joint/goal_reached_threshold" value="0.001" />
- <param name="r_arm_joint_trajectory_controller/r_wrist_roll_joint/goal_reached_threshold" value="0.001" />
-
- <param name="r_arm_joint_trajectory_controller/r_shoulder_pan_joint/joint_error_threshold" value="0.1" />
- <param name="r_arm_joint_trajectory_controller/r_shoulder_lift_joint/joint_error_threshold" value="0.1" />
- <param name="r_arm_joint_trajectory_controller/r_upper_arm_roll_joint/joint_error_threshold" value="0.1" />
- <param name="r_arm_joint_trajectory_controller/r_elbow_flex_joint/joint_error_threshold" value="0.1" />
- <param name="r_arm_joint_trajectory_controller/r_forearm_roll_joint/joint_error_threshold" value="0.1" />
- <param name="r_arm_joint_trajectory_controller/r_wrist_flex_joint/joint_error_threshold" value="0.1" />
- <param name="r_arm_joint_trajectory_controller/r_wrist_roll_joint/joint_error_threshold" value="0.1" />
-
- <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/r_arm_joint_trajectory_controller.xml" />
-
-</launch>
Deleted: pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm_splines.launch
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm_splines.launch 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/demos/tabletop_manipulation/tabletop_scripts/launch/rarm_splines.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,15 +0,0 @@
-<launch>
-
- <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
- <include file="$(find pr2_ik)/pr2_ik_rarm_node.launch"/>
-
- <rosparam file="$(find pr2_default_controllers)/trajectory_controller.yaml" command="load" ns="trajectory_controller"/>
-
- <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/trajectory_controller.xml" output="screen"/>
-
-
- <include file="$(find move_arm)/launch/move_rarm_splines.launch"/>
-
- <include file="$(find joint_waypoint_controller)/launch/joint_waypoint_controller.launch"/>
-
-</launch>
Modified: pkg/trunk/highlevel/move_arm/launch/move_larm.launch
===================================================================
--- pkg/trunk/highlevel/move_arm/launch/move_larm.launch 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/highlevel/move_arm/launch/move_larm.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -9,16 +9,16 @@
<remap from="get_valid_state" to="find_valid_state" />
- <remap from="controller_start" to="l_arm_joint_trajectory_controller/TrajectoryStart" />
- <remap from="controller_query" to="l_arm_joint_trajectory_controller/TrajectoryQuery" />
- <remap from="controller_cancel" to="l_arm_joint_trajectory_controller/TrajectoryCancel" />
+ <remap from="controller_start" to="/l_arm_joint_waypoint_controller/TrajectoryStart" />
+ <remap from="controller_query" to="/l_arm_joint_waypoint_controller/TrajectoryQuery" />
+ <remap from="controller_cancel" to="/l_arm_joint_waypoint_controller/TrajectoryCancel" />
<remap from="get_motion_plan" to="plan_kinematic_path" />
<param name="arm" type="string" value="left_arm" />
<param name="show_collisions" type="bool" value="true" />
- <param name="refresh_interval_collision_map" type="double" value="5.0" />
+ <param name="refresh_interval_collision_map" type="double" value="20.0" />
<param name="refresh_interval_kinematic_state" type="double" value="1.0" />
<param name="bounding_planes" type="string" value="0 0 1 -0.01" />
Modified: pkg/trunk/highlevel/move_arm/launch/move_rarm.launch
===================================================================
--- pkg/trunk/highlevel/move_arm/launch/move_rarm.launch 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/highlevel/move_arm/launch/move_rarm.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -9,16 +9,16 @@
<remap from="get_valid_state" to="find_valid_state" />
- <remap from="controller_start" to="r_arm_joint_trajectory_controller/TrajectoryStart" />
- <remap from="controller_query" to="r_arm_joint_trajectory_controller/TrajectoryQuery" />
- <remap from="controller_cancel" to="r_arm_joint_trajectory_controller/TrajectoryCancel" />
+ <remap from="controller_start" to="/r_arm_joint_waypoint_controller/TrajectoryStart" />
+ <remap from="controller_query" to="/r_arm_joint_waypoint_controller/TrajectoryQuery" />
+ <remap from="controller_cancel" to="/r_arm_joint_waypoint_controller/TrajectoryCancel" />
<remap from="get_motion_plan" to="plan_kinematic_path" />
<param name="arm" type="string" value="right_arm" />
<param name="show_collisions" type="bool" value="true" />
- <param name="refresh_interval_collision_map" type="double" value="5.0" />
+ <param name="refresh_interval_collision_map" type="double" value="20.0" />
<param name="refresh_interval_kinematic_state" type="double" value="1.0" />
<param name="bounding_planes" type="string" value="0 0 1 -0.01" />
</node>
Deleted: pkg/trunk/highlevel/move_arm/launch/move_rarm_splines.launch
===================================================================
--- pkg/trunk/highlevel/move_arm/launch/move_rarm_splines.launch 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/highlevel/move_arm/launch/move_rarm_splines.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,28 +0,0 @@
-<launch>
- <node pkg="move_arm" type="move_arm_action" output="screen">
-
- <remap from="robot_description" to="robot_description" />
- <remap from="collision_map" to="collision_map_occ" />
- <remap from="collision_map_update" to="collision_map_occ_update" />
-
- <remap from="arm_ik" to="pr2_ik_right_arm/ik_service" />
-
- <remap from="get_valid_state" to="find_valid_state" />
-
- <remap from="controller_start" to="/joint_waypoint_controller/TrajectoryStart" />
- <remap from="controller_query" to="/joint_waypoint_controller/TrajectoryQuery" />
- <remap from="controller_cancel" to="/joint_waypoint_controller/TrajectoryCancel" />
-
- <remap from="get_motion_plan" to="plan_kinematic_path" />
-
- <param name="arm" type="string" value="right_arm" />
- <param name="show_collisions" type="bool" value="true" />
-
- <param name="refresh_interval_collision_map" type="double" value="20.0" />
- <param name="refresh_interval_kinematic_state" type="double" value="1.0" />
- <param name="bounding_planes" type="string" value="0 0 1 -0.01" />
- </node>
-
- <include file="$(find move_arm)/launch/gripper_rarm.launch" />
-
-</launch>
Added: pkg/trunk/sandbox/3dnav_pr2/launch/actions/left_arm.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/actions/left_arm.launch (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/actions/left_arm.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,13 @@
+<launch>
+
+ <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+ <include file="$(find pr2_ik)/pr2_ik_larm_node.launch"/>
+
+ <rosparam file="$(find pr2_default_controllers)/l_arm_trajectory_controller.yaml" command="load" ns="l_arm_trajectory_controller"/>
+
+ <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/l_arm_trajectory_controller.xml" output="screen"/>
+
+ <include file="$(find joint_waypoint_controller)/launch/l_arm_joint_waypoint_controller.launch"/>
+
+ <include file="$(find move_arm)/launch/move_larm.launch"/>
+</launch>
Added: pkg/trunk/sandbox/3dnav_pr2/launch/actions/right_arm.launch
===================================================================
--- pkg/trunk/sandbox/3dnav_pr2/launch/actions/right_arm.launch (rev 0)
+++ pkg/trunk/sandbox/3dnav_pr2/launch/actions/right_arm.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,13 @@
+<launch>
+
+ <include file="$(find 3dnav_pr2)/launch/pr2_planning_environment.launch" />
+ <include file="$(find pr2_ik)/pr2_ik_rarm_node.launch"/>
+
+ <rosparam file="$(find pr2_default_controllers)/r_arm_trajectory_controller.yaml" command="load" ns="r_arm_trajectory_controller"/>
+
+ <node pkg="mechanism_control" type="spawner.py" args="$(find pr2_default_controllers)/r_arm_trajectory_controller.xml" output="screen"/>
+
+ <include file="$(find joint_waypoint_controller)/launch/r_arm_joint_waypoint_controller.launch"/>
+
+ <include file="$(find move_arm)/launch/move_rarm.launch"/>
+</launch>
Modified: pkg/trunk/sandbox/joint_waypoint_controller/launch/filters.xml
===================================================================
--- pkg/trunk/sandbox/joint_waypoint_controller/launch/filters.xml 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/sandbox/joint_waypoint_controller/launch/filters.xml 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,5 +1,6 @@
<filters>
<filter type="FixWraparoundJoints" name="fix_wraparound_joints"/>
<filter type="ClampedCubicSplineSmoother" name="clamped_cubic_spline_smoother"/>
+<!-- <filter type="NumericalDifferentiationSplineSmoother" name="clamped_cubic_spline_smoother"/> -->
</filters>
Deleted: pkg/trunk/sandbox/joint_waypoint_controller/launch/joint_waypoint_controller.launch
===================================================================
--- pkg/trunk/sandbox/joint_waypoint_controller/launch/joint_waypoint_controller.launch 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/sandbox/joint_waypoint_controller/launch/joint_waypoint_controller.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,7 +0,0 @@
-<launch>
- <node pkg="joint_waypoint_controller" name="joint_waypoint_controller" type="joint_waypoint_controller" output="screen" clear_params="true">
- <param name="filters" textfile="$(find joint_waypoint_controller)/launch/filters.xml"/>
- <param name="trajectory_type" value="cubic"/>
- <param name="spline_controller_prefix" value="/trajectory_controller/"/>
- </node>
-</launch>
Added: pkg/trunk/sandbox/joint_waypoint_controller/launch/l_arm_joint_waypoint_controller.launch
===================================================================
--- pkg/trunk/sandbox/joint_waypoint_controller/launch/l_arm_joint_waypoint_controller.launch (rev 0)
+++ pkg/trunk/sandbox/joint_waypoint_controller/launch/l_arm_joint_waypoint_controller.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,7 @@
+<launch>
+ <node pkg="joint_waypoint_controller" name="l_arm_joint_waypoint_controller" type="joint_waypoint_controller" output="screen" clear_params="true">
+ <param name="filters" textfile="$(find joint_waypoint_controller)/launch/filters.xml"/>
+ <param name="trajectory_type" value="cubic"/>
+ <param name="spline_controller_prefix" value="/l_arm_trajectory_controller/"/>
+ </node>
+</launch>
Copied: pkg/trunk/sandbox/joint_waypoint_controller/launch/r_arm_joint_waypoint_controller.launch (from rev 20100, pkg/trunk/sandbox/joint_waypoint_controller/launch/joint_waypoint_controller.launch)
===================================================================
--- pkg/trunk/sandbox/joint_waypoint_controller/launch/r_arm_joint_waypoint_controller.launch (rev 0)
+++ pkg/trunk/sandbox/joint_waypoint_controller/launch/r_arm_joint_waypoint_controller.launch 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,7 @@
+<launch>
+ <node pkg="joint_waypoint_controller" name="r_arm_joint_waypoint_controller" type="joint_waypoint_controller" output="screen" clear_params="true">
+ <param name="filters" textfile="$(find joint_waypoint_controller)/launch/filters.xml"/>
+ <param name="trajectory_type" value="cubic"/>
+ <param name="spline_controller_prefix" value="/r_arm_trajectory_controller/"/>
+ </node>
+</launch>
Property changes on: pkg/trunk/sandbox/joint_waypoint_controller/launch/r_arm_joint_waypoint_controller.launch
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/sandbox/joint_waypoint_controller/launch/joint_waypoint_controller.launch:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Added: pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.xml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.xml 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,7 @@
+<?xml version="1.0"?>
+<controller name="dynamic_loader" type="DynamicLoaderController"
+ package="experimental_controllers" lib="libexperimental_controllers">
+<controllers>
+ <controller name="l_arm_trajectory_controller" type="TrajectoryController"/>
+</controllers>
+</controller>
Added: pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.yaml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.yaml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/l_arm_trajectory_controller.yaml 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,58 @@
+joint_names: l_shoulder_pan_joint l_shoulder_lift_joint l_upper_arm_roll_joint l_elbow_flex_joint l_forearm_roll_joint l_wrist_flex_joint l_wrist_roll_joint
+
+l_shoulder_pan_joint:
+ joint: l_shoulder_pan_joint
+ p: 140.0
+ d: 30.0
+ i: 100.0
+ i_clamp: 3.0
+ goal_reached_threshold: 0.01
+
+l_shoulder_lift_joint:
+ joint: l_shoulder_lift_joint
+ p: 70.0
+ d: 20.0
+ i: 300.0
+ i_clamp: 3.0
+ goal_reached_threshold: 0.01
+
+l_upper_arm_roll_joint:
+ joint: l_upper_arm_roll_joint
+ p: 50.0
+ d: 5.0
+ i: 100.0
+ i_clamp: 3.0
+ goal_reached_threshold: 0.01
+
+l_elbow_flex_joint:
+ joint: l_elbow_flex_joint
+ p: 100.0
+ d: 5.0
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
+l_forearm_roll_joint:
+ joint: l_forearm_roll_joint
+ p: 10.0
+ d: 2.0
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
+l_wrist_flex_joint:
+ joint: l_wrist_flex_joint
+ p: 20.0
+ d: 0.5
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
+l_wrist_roll_joint:
+ joint: l_wrist_roll_joint
+ p: 10.0
+ d: 0.5
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
Copied: pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.xml (from rev 20100, pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.xml)
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.xml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.xml 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,7 @@
+<?xml version="1.0"?>
+<controller name="dynamic_loader" type="DynamicLoaderController"
+ package="experimental_controllers" lib="libexperimental_controllers">
+<controllers>
+ <controller name="r_arm_trajectory_controller" type="TrajectoryController"/>
+</controllers>
+</controller>
Property changes on: pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.xml
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/robot_descriptions/pr2/pr2_default_controllers/trajectory_controller.xml:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
Copied: pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.yaml (from rev 20113, pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.yaml)
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.yaml (rev 0)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.yaml 2009-07-30 04:06:52 UTC (rev 20133)
@@ -0,0 +1,58 @@
+joint_names: r_shoulder_pan_joint r_shoulder_lift_joint r_upper_arm_roll_joint r_elbow_flex_joint r_forearm_roll_joint r_wrist_flex_joint r_wrist_roll_joint
+
+r_shoulder_pan_joint:
+ joint: r_shoulder_pan_joint
+ p: 140.0
+ d: 30.0
+ i: 100.0
+ i_clamp: 3.0
+ goal_reached_threshold: 0.01
+
+r_shoulder_lift_joint:
+ joint: r_shoulder_lift_joint
+ p: 70.0
+ d: 20.0
+ i: 300.0
+ i_clamp: 3.0
+ goal_reached_threshold: 0.01
+
+r_upper_arm_roll_joint:
+ joint: r_upper_arm_roll_joint
+ p: 50.0
+ d: 5.0
+ i: 100.0
+ i_clamp: 3.0
+ goal_reached_threshold: 0.01
+
+r_elbow_flex_joint:
+ joint: r_elbow_flex_joint
+ p: 100.0
+ d: 5.0
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
+r_forearm_roll_joint:
+ joint: r_forearm_roll_joint
+ p: 10.0
+ d: 2.0
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
+r_wrist_flex_joint:
+ joint: r_wrist_flex_joint
+ p: 20.0
+ d: 0.5
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
+r_wrist_roll_joint:
+ joint: r_wrist_roll_joint
+ p: 10.0
+ d: 0.5
+ i: 100.0
+ i_clamp: 1.0
+ goal_reached_threshold: 0.01
+
Property changes on: pkg/trunk/stacks/pr2/pr2_default_controllers/r_arm_trajectory_controller.yaml
___________________________________________________________________
Added: svn:mergeinfo
+
Deleted: pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.xml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.xml 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.xml 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,7 +0,0 @@
-<?xml version="1.0"?>
-<controller name="dynamic_loader" type="DynamicLoaderController"
- package="experimental_controllers" lib="libexperimental_controllers">
-<controllers>
- <controller name="trajectory_controller" type="TrajectoryController"/>
-</controllers>
-</controller>
\ No newline at end of file
Deleted: pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.yaml
===================================================================
--- pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.yaml 2009-07-30 04:05:47 UTC (rev 20132)
+++ pkg/trunk/stacks/pr2/pr2_default_controllers/trajectory_controller.yaml 2009-07-30 04:06:52 UTC (rev 20133)
@@ -1,58 +0,0 @@
-joint_names: r_shoulder_pan_joint r_shoulder_lift_joint r_upper_arm_roll_joint r_elbow_flex_joint r_forearm_roll_joint r_wrist_flex_joint r_wrist_roll_joint
-
-r_shoulder_pan_joint:
- joint: r_shoulder_pan_joint
- p: 140.0
- d: 30.0
- i: 100.0
- i_clamp: 3.0
- goal_reached_threshold: 0.1
-
-r_shoulder_lift_joint:
- joint: r_shoulder_lift_joint
- p: 70.0
- d: 20.0
- i: 300.0
- i_clamp: 3.0
- goal_reached_threshold: 0.1
-
-r_upper_arm_roll_joint:
- joint: r_upper_arm_roll_joint
- p: 50.0
- d: 5.0
- i: 100.0
- i_clamp: 3.0
- goal_reached_threshold: 0.1
-
-r_elbow_flex_joint:
- joint: r_elbow_flex_joint
- p: 100.0
- d: 5.0
- i: 100.0
- i_clamp: 1.0
- goal_reached_threshold: 0.1
-
-r_forearm_roll_joint:
- joint: r_forearm_roll_joint
- p: 10.0
- d: 2.0
- i: 100.0
- i_clamp: 1.0
- goal_reached_threshold: 0.1
-
-r_wrist_flex_joint:
- joint: r_wrist_flex_joint
- p: 20.0
- d: 0.5
- i: 100.0
- i_clamp: 1.0
- goal_reached_threshold: 0.1
-
-r_wrist_roll_joint:
- joint: r_wrist_roll_joint
- p: 10.0
- d: 0.5
- i: 100.0
- i_clamp: 1.0
- goal_reached_threshold: 0.1
-
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|