legged_control icon indicating copy to clipboard operation
legged_control copied to clipboard

Some convention questions

Open edward9503 opened this issue 2 years ago • 6 comments

Hi @qiayuanliao ,

Thanks for sharing the code!

When I use the code and go through it, I find some questions about the convention of some vectors. More specifically:

  1. For the state vector in the Kalman filter (which is called "rbd_state_" in your code), if I understand correctly, it looks like this:
Base_orient_z_global
Base_orient_y_global
Base_orient_x_global
Base_posi_x_global
Base_posi_y_global
Base_posi_z_global
LF_HAA_posi
LF_HFE_posi
LF_KFE_posi
LH_HAA_posi
LH_HFE_posi
LH_KFE_posi
RF_HAA_posi
RF_HFE_posi
RF_KFE_posi
RH_HAA_posi
RH_HFE_posi
RH_KFE_posi
angular_vel_z_global
angular_vel_y_global
angular_vel_x_global
linear_vel_x_global
linear_vel_y_global
linear_vel_z_global
LF_HAA_vel
LF_HFE_vel
LF_KFE_vel
LH_HAA_vel
LH_HFE_vel
LH_KFE_vel
RF_HAA_vel
RF_HFE_vel
RF_KFE_vel
RH_HAA_vel
RH_HFE_vel
RH_KFE_vel

Is this order/convention correct?

  1. For the foot contact measurement, is the order like this? "LF_FOOT", "RF_FOOT", "LH_FOOT", "RH_FOOT"

  2. When you do the pinocchio::forwardKinematics in "wbc.cpp", I found that the convention of expected measured_v_ is different, as you are using global linear velocity as the linear part, and Euler angle ZYX's derivatives as the angular part. However, as you can see here, a local base linear and angular velocity are expected as the first six elements. So I wonder why you can do that in a different way?

  3. Following the idea from 3., previously when I used Pinocchio to load the URDF file of Anymal C, the dimension of model.nq is 18 + 1 = 19, because it uses quaternion to express the orientation. But I notice that you can use Euler angle to present the orientation and model.nq in your case returns 18. I was wondering what did you do to achieve it?

  4. Again following the idea from 3. and 4., let's say I use pinocchio::getFrameJacobian(model, data, info_.endEffectorFrameIndices, pinocchio::LOCAL_WORLD_ALIGNED, jac) to get the jacobian jac of the FL_Foot in the global frame. If I wanna calculate the global velocity of the FL_Foot, I need to use xdot = jac * v for the calculation. Then, what is the convention of the v in this case? Is it v = [local_base_velocity_linear, local_base_velocity_angular, joint_velocities] as described here, or v = [global_base_velocity_linear, global_base_ZYX_derivatives, joint_velocities] followed by your convention?

Thanks in advance.

edward9503 avatar Oct 14 '22 01:10 edward9503

Hi @qiayuanliao , is there any feedback on this? Thanks

edward9503 avatar Oct 24 '22 08:10 edward9503

Hi @qiayuanliao , is there any feedback on this? Thanks

Sorry for the delay. I will answer these questions after October 29.

qiayuanl avatar Oct 24 '22 08:10 qiayuanl

Ok no worry

edward9503 avatar Oct 24 '22 08:10 edward9503

Hi @qiayuanliao ,

is there any feedback on this? Many thanks in advance.

edward9503 avatar Nov 01 '22 04:11 edward9503

Very sorry for the delay. My TOEFL test was rescheduled to Nov. 1st (yesterday) cause of COVID-19.

Since there are no drafts in the GitHub issue comments. I posted this comment before I finished, and I will update this comment gradually. I suggest that you ask questions after I am finished.

Overall, there are three different representations of state and input in the legged_control which are all brought by OCS2 (not my fault).

  • OCS2 centroidal dynamics system input and output defined can be found in the comments of task.info
  • Pinocchio generalize coordinate
  • Rigid body state following the definition you mentioned.

Answers to your questions:

  1. The convention is correct.
  2. Defined by OCS2
  3. What your are saying is correct. Thank you so much for finding this bug! I will fix it within two days.
  4. Check this code

qiayuanl avatar Nov 02 '22 02:11 qiayuanl

Hi @qiayuanliao,

I hope you do well in your exam.

According to your reply, I suppose you are answering question 1. 3. and 4. I asked before. But I need to confirm two things:

  1. For the variable "rbd_state_" in state estimator, is the convention correct?
 Base_orient_z_global
Base_orient_y_global
Base_orient_x_global
Base_posi_x_global
Base_posi_y_global
Base_posi_z_global
LF_HAA_posi
LF_HFE_posi
LF_KFE_posi
LH_HAA_posi
LH_HFE_posi
LH_KFE_posi
RF_HAA_posi
RF_HFE_posi
RF_KFE_posi
RH_HAA_posi
RH_HFE_posi
RH_KFE_posi
angular_vel_z_global
angular_vel_y_global
angular_vel_x_global
linear_vel_x_global
linear_vel_y_global
linear_vel_z_global
LF_HAA_vel
LF_HFE_vel
LF_KFE_vel
LH_HAA_vel
LH_HFE_vel
LH_KFE_vel
RF_HAA_vel
RF_HFE_vel
RF_KFE_vel
RH_HAA_vel
RH_HFE_vel
RH_KFE_vel
  1. For the statement I mentioned in 2.: "When you do the pinocchio::forwardKinematics in "wbc.cpp", I found that the convention of expected measured_v_ is different, as you are using global linear velocity as the linear part, and Euler angle ZYX's derivatives as the angular part.". Is it also correct?

Thanks

edward9503 avatar Nov 02 '22 03:11 edward9503

Hello, has this problem been fixed in the code? I can't find the relevant commit, thank you! @qiayuanliao

ImFroooost avatar Jan 12 '23 13:01 ImFroooost

Hello, has this problem been fixed in the code? I can't find the relevant commit, thank you! @qiayuanliao

Hello, I am sure that the original code is correct after checking the code and having a private conversation with @edward9503.

qiayuanl avatar Jan 12 '23 13:01 qiayuanl

Hello, could anyone tell me legs order ?? I made front right/front left/rear right and rear left. (and it doesn't work as expected !) Can anyone confirm @qiayuanliao @ImFroooost @edward9503 @LoveThinkinghard Thanks friends Vincent

elpimous avatar Sep 18 '23 14:09 elpimous