Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Floating base robot q and v #1137

Closed
xinsongyan opened this issue Apr 3, 2020 · 3 comments
Closed

Floating base robot q and v #1137

xinsongyan opened this issue Apr 3, 2020 · 3 comments

Comments

@xinsongyan
Copy link

Hi,

I am using pinocchio to calculate a floating base robot kinematics and dynamics, but I am not sure about the convention of q and v?

I used RBDL before, the q and v in RBDL are defined as:

q = [global_base_position, global_base_quaternion_x, global_base_quaternion_y, global_base_quaternion_z, joint_positions, global_base_quaternion_w]
v = [global_base_velocity_linear, local_base_velocity_angular, joint_velocities]

I tried a little bit pinocchio, it seems that it takes:

q = [global_base_position, global_base_quaternion, joint_positions]
v = [local_base_velocity_linear, local_base_velocity_angular, joint_velocities]

I didn't find any documentation about this. Anyone can confirm this?
Thanks a lot!

@jcarpent
Copy link
Contributor

jcarpent commented Apr 3, 2020

You're correct. The base translation part is expressed in the parent frame (here the world coordinate system) while its velocity is expressed in the body coordinate system.

@edward9503
Copy link

You're correct. The base translation part is expressed in the parent frame (here the world coordinate system) while its velocity is expressed in the body coordinate system.

Hi @jcarpent ,

as you mentioned here, for the floating base robot, the first 6 elements of the generalized velocity vector v are always the linear and angular velocity of the robot's base represented in the floating base frame for the pinocchio's convention.

Then, I have following two questions:

  1. For instance, I want to use the pinocchio::ccrba to compute the centroidal momentum matrix. This function expects a joint velocity vector v as input. So for the first 6 elements of this vector, I always need to change the 6d spatial velocity of robot's base to be represented in the base frame, right? That's what I understand from this section.
  2. I've learned that the centroidal momenta h_com in the CoM frame which is aligned with the world frame can be computed by pinocchio::computeCentroidalMomentum. And, pinocchio::ccrba computes the centroidal momentum matrix A. If I had a velocity vector v as mentioned in the first question, where the first 6 elements of v are always the linear and angular velocity of the robot's base represented in the base frame, then is "h_com = A * v" correct?

Many thanks in advance.

@FenglongSong
Copy link

Hi Justin @jcarpent , thanks for your nice explanation. I'd like to ask about the case when the orientation of the floating-base frame is expressed by ZYX Euler angle.

  1. By my understanding, when creating the PinocchioInterface, if I use a free flyer joint, the base orientation will be automatically represented by a quaternion, because I found model.nq = model.nv+1. But if I use a JointModelTranslation() and a JointModelSphericalZYX() as the 6-DOF root joint rather than using a free flyer joint, I got model.nq=model.nv. So I guess now the Pinocchio model orientation is represented by ZYX Euler angles. In this case, are the following interpretation of q and v correct?
    q = [global_base_position, global_base_ZYX_euler_angles, joint_positions]
    v = [local_base_velocity_linear, local_base_velocity_angular, joint_velocities]
  2. If I use aba() to calculate the forward dynamics, how is the returned acceleration vector defined? Is it qdd=[local_base_acceleration_linear, local_base_acceleration_angular, joint_accelerations] (nothing but the time derivative of velocity vector) ?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants