From 353c6d9f870bf7b589d346f2235cb95d78dff10b Mon Sep 17 00:00:00 2001
From: Olivier Stasse <ostasse@laas.fr>
Date: Fri, 9 Mar 2018 09:54:14 +0100
Subject: [PATCH] Fix parameters based on robot feedback.

---
 .../config/sot_talos_params_effort.yaml       | 244 ++++++++++--------
 .../launch/sot_talos_controller_effort.launch |   2 +
 2 files changed, 132 insertions(+), 114 deletions(-)

diff --git a/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml b/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml
index b0df471..4eaa7e5 100644
--- a/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml
+++ b/talos_roscontrol_sot_talos/config/sot_talos_params_effort.yaml
@@ -9,117 +9,133 @@ sot_controller:
   map_rc_to_sot_device: { motor-angles: motor-angles ,
   joint-angles: joint-angles, velocities: velocities, forces: forces, currents: currents,
   torques: torques, cmd-joints: control, cmd-effort: control, accelerometer_0: accelerometer_0, gyrometer_0: gyrometer_0 }
-    effort_control_pd_motor_init:
-	- name: leg_left_1_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_left_2_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_left_3_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_left_4_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_left_5_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_left_6_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0	  
-	- name: leg_right_1_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_right_2_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_right_3_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_right_4_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_right_5_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: leg_right_6_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0	  
-	- name: torso_1_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: torso_2_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_left_1_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_left_2_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_left_3_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_left_4_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_left_5_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_left_6_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_left_7_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0	  
-	- name: arm_right_1_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_right_2_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_right_3_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_right_4_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_right_5_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0
-	- name: arm_right_6_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0	  
-	- name: arm_right_7_joint
-	  p_gain: 0.0
-	  d_gain: 0.0
-	  des_pos: 0.0	  
-  control_mode: EFFORT 
+  effort_control_pd_motor_init:
+    - name: leg_left_1_joint
+      p_gain: 100.0
+      d_gain: 0.0
+      des_pos: 0.0
+    - name: leg_left_2_joint
+      p_gain: 120.0
+      d_gain: 0.0
+      des_pos: 0.0
+    - name: leg_left_3_joint
+      p_gain: 100.0
+      d_gain: 0.0
+      des_pos: -0.411354
+    - name: leg_left_4_joint
+      p_gain: 130.0
+      d_gain: 0.0
+      des_pos: 0.859395
+    - name: leg_left_5_joint
+      p_gain: 75.0
+      d_gain: 0.0
+      des_pos: -0.448041
+    - name: leg_left_6_joint
+      p_gain: 75.0
+      d_gain: 0.0
+      des_pos: -0.001708
+    - name: leg_right_1_joint
+      p_gain: 100.0
+      d_gain: 0.0
+      des_pos: 0.0
+    - name: leg_right_2_joint
+      p_gain: 120.0
+      d_gain: 0.0
+      des_pos: 0.0
+    - name: leg_right_3_joint
+      p_gain: 100.0
+      d_gain: 0.0
+      des_pos: -0.411354
+    - name: leg_right_4_joint
+      p_gain: 130.0
+      d_gain: 0.0
+      des_pos: 0.859395
+    - name: leg_right_5_joint
+      p_gain: 75.0
+      d_gain: 0.0
+      des_pos: -0.448041
+    - name: leg_right_6_joint
+      p_gain: 75.0
+      d_gain: 0.0
+      des_pos: -0.001708
+    - name: torso_1_joint
+      p_gain: 30.0
+      d_gain: 0.0
+      des_pos: 0.0
+    - name: torso_2_joint
+      p_gain: 30.0
+      d_gain: 0.0
+      des_pos: 0.006761
+    - name: arm_left_1_joint
+      p_gain: 20.0
+      d_gain: 0.0
+      des_pos: 0.25847
+    - name: arm_left_2_joint
+      p_gain: 100.0
+      d_gain: 0.0
+      des_pos: 0.173046
+    - name: arm_left_3_joint
+      p_gain: 50.0
+      d_gain: 0.0
+      des_pos: 0.0002
+    - name: arm_left_4_joint
+      p_gain: 50.0
+      d_gain: 0.0
+      des_pos: -0.525366
+    - name: arm_left_5_joint
+      p_gain: 50.0
+      d_gain: 0.0
+      des_pos: 0.0
+    - name: arm_left_6_joint
+      p_gain: 30.0
+      d_gain: 0.0
+      des_pos: 0.1
+    - name: arm_left_7_joint
+      p_gain: 30.0
+      d_gain: 0.0
+      des_pos: 0.1
+    - name: gripper_left_joint
+      p_gain: 0.002
+      d_gain: 0.0
+      des_pos: -0.005
+    - name: arm_right_1_joint
+      p_gain: 20.0
+      d_gain: 0.0
+      des_pos: -0.25847
+    - name: arm_right_2_joint
+      p_gain: 100.0
+      d_gain: 0.0
+      des_pos: -0.173046
+    - name: arm_right_3_joint
+      p_gain: 50.0
+      d_gain: 0.0
+      des_pos: 0.0002
+    - name: arm_right_4_joint
+      p_gain: 50.0
+      d_gain: 0.0
+      des_pos: -0.525366
+    - name: arm_right_5_joint
+      p_gain: 50.0
+      d_gain: 0.0
+      des_pos: 0.0
+    - name: arm_right_6_joint
+      p_gain: 30.0
+      d_gain: 0.0
+      des_pos: 0.1
+    - name: arm_right_7_joint
+      p_gain: 30.0
+      d_gain: 0.0
+      des_pos: 0.1
+    - name: gripper_right_joint
+      p_gain: 0.002
+      d_gain: 0.0
+      des_pos: -0.005 
+    - name: head_1_joint
+      p_gain: 1.0
+      d_gain: 0.0
+      des_pos:: 0.0
+    - name: head_2_joint
+      p_gain: 1.0
+      d_gain: 0.0
+      des_pos:: 0.0      
+  control_mode: EFFORT
diff --git a/talos_roscontrol_sot_talos/launch/sot_talos_controller_effort.launch b/talos_roscontrol_sot_talos/launch/sot_talos_controller_effort.launch
index 7343f9e..3930105 100644
--- a/talos_roscontrol_sot_talos/launch/sot_talos_controller_effort.launch
+++ b/talos_roscontrol_sot_talos/launch/sot_talos_controller_effort.launch
@@ -3,7 +3,9 @@
   <!-- Sot Controller configuration -->
   <rosparam command="load" file="$(find talos_roscontrol_sot_talos)/config/sot_talos_params_effort.yaml"/>
   <rosparam command="load" file="$(find talos_roscontrol_sot_talos)/config/sot_talos_controller.yaml" />
+  <rosparam command="load" file="$(find talos_roscontrol_sot_talos)/config/pids.yaml" />
   
+  <env name="PYTHONPATH" value="/opt/pal/dubnium/lib/python2.7/dist-packages:/opt/ros/indigo/lib/python2.7/dist-packages:/opt/openrobots/lib/python2.7/dist-packages:/opt/openrobots/lib/python2.7/site-packages" />
   <!-- Spawn walking controller -->
   <node name="sot_controller_spawner"
         pkg="controller_manager" type="spawner" output="screen"
-- 
GitLab