osrf / drcsim

Repository for the DRC project.
16 stars 6 forks source link

Atlas V1 falls when put in user mode. DRCSIM 4.2 #471

Closed osrf-migration closed 9 years ago

osrf-migration commented 9 years ago

Original report (archived issue) by Hugo Boyer (Bitbucket: hugomatic, GitHub: hugomatic).


As per the tutorial: Atlas control over ROS with python

When putting Atlas in User mode using:

#!c++
rostopic pub /atlas/control_mode std_msgs/String -- "User"

The robot falls on its face

osrf-migration commented 9 years ago

Original comment by Hugo Boyer (Bitbucket: hugomatic, GitHub: hugomatic).


Also happens with Atlas V5 link to tutorial

osrf-migration commented 9 years ago

Original comment by Nate Koenig (Bitbucket: Nathan Koenig).


Duplicate of #472.

osrf-migration commented 9 years ago

Original comment by Nate Koenig (Bitbucket: Nathan Koenig).


osrf-migration commented 9 years ago

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


I'm guessing that the BDI controller is actively keeping the robot standing. So if we want to switch to User mode, then we need to set the PID gains and target positions before the switch.

Just my guess.

osrf-migration commented 9 years ago

Original comment by Nate Koenig (Bitbucket: Nathan Koenig).


Without BDI controller

  1. Atlas v5: Stands on start, and doesn't fall over when switching to User mode
  2. Atlas v4: Stands on start, and doesn't fall over when switching to User mode
  3. Atlas v3: Does not stand on start
  4. Atlas v1: Stands on start, and falls over when switching to User mode

With BDI controller

  1. Atlas v5: Stands on start, and falls over when switching to User mode
  2. Atlas v4: Stands on start, and falls over when switching to User mode
  3. Atlas v3: Does not stand on start
  4. Atlas v1: Stands on start, and falls over when switching to User mode

Here are the problems in order of priority

  1. With BDI controller, Atlas v5 & v4: Stands on start, and falls over when switching to User mode
  2. With and without BDI controller, Atlas v3 does not stand.
  3. With and without BDI controller, Atlas v1 falls over when switching to User mode.
osrf-migration commented 9 years ago

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


I think the relevant code is in VRCPlugin::SetPIDStand, specifically updating the target joint positions. Each model may need a unique set of target joint positions.

osrf-migration commented 9 years ago

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


The following keeps the v5 atlas from jumping, but it still falls over. I'm guessing we need to fix the controller gains and feed-forward effort in addition to the joint targets:

diff -r 8cab0ccbc9a3f0aff98e3300c1110b0998dd895c drcsim_gazebo_ros_plugins/src/VRCPlugin.cpp
--- a/drcsim_gazebo_ros_plugins/src/VRCPlugin.cpp   Fri Jan 09 13:50:47 2015 -0800
+++ b/drcsim_gazebo_ros_plugins/src/VRCPlugin.cpp   Fri Jan 09 17:23:43 2015 -0800
@@ -1903,16 +1903,16 @@

   int index = 0;
   this->ac.position[index++]  =  0.0; //back_bkz
-  this->ac.position[index++]  =  0.0015186156379058957; //back_bky
+  this->ac.position[index++]  =  0.0023; //back_bky
   this->ac.position[index++]  =  0.0; //back_bkx
-  this->ac.position[index++]  =  -0.0010675729718059301; //neck_ry
+  this->ac.position[index++]  =  -0.1106; //neck_ry

-  this->ac.position[index++]  =  -0.0003740221436601132; //l_hpz
-  this->ac.position[index++]  =  0.06201673671603203; //l_hpx
-  this->ac.position[index++]  = -0.1533149015903473;    // l_hpy
-  this->ac.position[index++]  =  0.5181407332420349; //l_kny
-  this->ac.position[index++]  = -0.35610817551612854;   // l_aky
-  this->ac.position[index++]  =  -0.06201673671603203; //l_akx
+  this->ac.position[index++]  =  -0.0013; //l_hpz
+  this->ac.position[index++]  =  0.0650; //l_hpx
+  this->ac.position[index++]  = -0.4739;    // l_hpy
+  this->ac.position[index++]  =  0.9319; //l_kny
+  this->ac.position[index++]  = -0.4401;   // l_aky
+  this->ac.position[index++]  =  -0.0652; //l_akx

   this->ac.position[index++] = -this->ac.position[4]; //r_hpz
   this->ac.position[index++] = -this->ac.position[5]; //r_hpx
@@ -1921,12 +1921,12 @@
   this->ac.position[index++] = this->ac.position[8]; //r_aky
   this->ac.position[index++] = -this->ac.position[9]; //r_akx

-  this->ac.position[index++] =  0.29983898997306824;  // l_shy || shz
-  this->ac.position[index++] =  -1.303462266921997; //l_shx
-  this->ac.position[index++] =  2.0; //l_ely
-  this->ac.position[index++] =  0.49823325872421265; //l_elx
-  this->ac.position[index++] =  0.0003098883025813848; //l_wry
-  this->ac.position[index++] =  -0.0044272784143686295; //l_wrx
+  this->ac.position[index++] =  -0.2997;  // l_shy || shz
+  this->ac.position[index++] =  -1.3066; //l_shx
+  this->ac.position[index++] =  1.853; //l_ely
+  this->ac.position[index++] =  0.4930; //l_elx
+  this->ac.position[index++] =  0.0079; //l_wry
+  this->ac.position[index++] =  -0.0010; //l_wrx

   if (this->atlasVersion >= 4)  // v4 / v5
     this->ac.position[index++] =  0;  // l_arm_wry2
osrf-migration commented 9 years ago

Original comment by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


I've updated that previous patch and committed it in 65c8c1adc4ab07594ee98400e2b958cf195acdc9 to branch issue_471_v5_hack. It seems to keep the atlas_v5 from falling over, though it's ugly.

osrf-migration commented 9 years ago

Original comment by Nate Koenig (Bitbucket: Nathan Koenig).


These values seem to work only with BDI's library. Still testing...

Update: I should clarify that these values will work if Atlas transitions from Stand to User using BDI's library. Without BDI's library, Atlas will fall over on start.

osrf-migration commented 9 years ago

Original comment by Nate Koenig (Bitbucket: Nathan Koenig).


Hacked the hack, if that's possible, to make it work with atlas version 1.

osrf-migration commented 9 years ago

Original comment by Bill Blank (Bitbucket: BillBlank).


Steve's change is fine. I did not make an effort to have the stand pose statically balance...just needed a pose close enough that we could dynamically balance from it. And yes, due to the extra arm dofs, users wishing to simulate Atlas 3 or earlier should use pre version 3.0.x atlassiminterface.

osrf-migration commented 9 years ago

Original comment by Nate Koenig (Bitbucket: Nathan Koenig).


See pull request #515

osrf-migration commented 9 years ago

Original comment by Nate Koenig (Bitbucket: Nathan Koenig).


Resolved in pull request #515