softbankrobotics-research / qibullet

Bullet simulation for SoftBank Robotics robots
Apache License 2.0
145 stars 38 forks source link

Inverse Kinematics #44

Closed Famosi closed 4 years ago

Famosi commented 4 years ago

Is there a way to enable Inverse Kinematics?

issue-label-bot[bot] commented 4 years ago

Issue Label Bot is not confident enough to auto-label this issue. See dashboard for more details.

mbusy commented 4 years ago

Hi, you could directly use the calculateInverseKinematics method form the pybullet API (see the doc here).

I believe that the method will return articular coordinates, you can use the setAngles method to control the robot

Famosi commented 4 years ago

Thank you @mbusy! I managed to calculateInverseKinematics using this snippet:

# Get Robot Info
bodyUniqueId = pepper.getRobotModel()
endEffectorLinkIndex = pepper.link_dict["r_hand"].getIndex()

# This is the (random) target position of the end-effector
pos = [0.1, 0.2, 0.1]

ik = p.calculateInverseKinematics(bodyUniqueId, endEffectorLinkIndex, pos)

According with the documentation, calculateInverseKinematics "returns a list of joint positions for each degree of freedom". Thus, I've an array like this:

(-1.474085674906577, -1.4844357913663873, 0.04486723386730852, -5.496345165136124e-05, 0.07537907489489408, -0.0003723378908280802, 0.0051549125182370585, 0.008979399275344108, -0.014666386280464905, -0.004953011341898082, 0.00879055175984655, 0.022946787673324816, -0.010184529012474873, -0.027202783784677706, 0.021224111419988784, -0.008571043759656932, -0.03752837902953518, -0.0014436705943825824, 0.002102722869505602, -0.00017534845292913374, 0.0009418055971807989, 0.0005322461581582625, 0.0005666829758810678, -0.0029624243067073305, 0.022198287283984593, 0.4951957579029603, 0.785444306061011, -0.0133625064228351, 0.2072241628159427, 0.0006243669582267051, 0.009190171500332517, 8.716910302713072e-05, -0.0011604897402534991, 0.004083571002748031, 0.002467825382847382, -0.0022580905539191067, 0.0021721508398546744, 0.023983284434820513, -0.01329549938356328, -0.017211004622897395, 0.02169084226552172, -0.010370895810222925, -0.029959239459141068, 0.010978844415562308, -0.007691225584195273, 0.0, 0.0, 0.0)

where, I think, each 3 values correspond to one joint: if I have n joints, the array format is (x_1, y_1, z_1, x_2, y_2, z_2, ..., x_n, y_n, z_n). Is this intuition right?

The setAngles method takes as arguments joint_names, joint_values and percentage_speeds where joint_values is a "List of values corresponding to the angles in radians to be applied". Since I have, for each joint, the correspondent coordinates in 3D space, is there a method to setCoordinates instead of setAngles?. Otherwise, can you suggest me how I can map these coordinates to the angle in radians?

Thanks :)

mbusy commented 4 years ago

where, I think, each 3 values correspond to one joint: if I have n joints, the array format is (x_1, y_1, z_1, x_2, y_2, z_2, ..., x_n, y_n, z_n). Is this intuition right?

Mmmh I don't think so. It would make more sense for the method to return one articular position per dof, so the returned list would actually be composed of articular positions for each dof. Looking at the values of your array, it would make sense, the values are much more similar to articular positions in radians than cartesian coordinated in meters

mbusy commented 4 years ago

@FaMoSi did you manage to get it to work ? If so I'll close the issue

Famosi commented 4 years ago

Yes @mbusy! Thanks 😃

RaspberryPicardBox commented 2 years ago

@Famosi would you possibly be able to share your solution to this, or extend as to what values are represented by the return of calculateInverseKinematics in context?

Famosi commented 2 years ago

Unfortunately this issue was for an old project and I don't remember what the values represent.

Are you sure the last @mbusy answer is not correct?

RaspberryPicardBox commented 2 years ago

@Famosi sorry for the late reply. I believe my error was not realising the kinematic model started from the tibia. Thank you for your reply though, I should be able to get it working.

stdcout42 commented 2 years ago

@RaspberryPicardBox, I'm also having some trouble getting the IK working. Could you perhaps elaborate on what you mean with the kinematic model starting fromt he tibia? See my issue here

RaspberryPicardBox commented 2 years ago

@stdcout42 sorry for the delay. I'm making reference to this excerpt here: "The kinematic chains start at the Tibia link and respectively end at the right and left gripper links."

This is from the paper by SoftBankRobotics which can be found here https://arxiv.org/abs/1909.00779

stdcout42 commented 2 years ago

@stdcout42 sorry for the delay. I'm making reference to this excerpt here: "The kinematic chains start at the Tibia link and respectively end at the right and left gripper links."

This is from the paper by SoftBankRobotics which can be found here https://arxiv.org/abs/1909.00779

Thanks for your reply, I've solved the issue I was having by using setAngles (for future readers, see aforementioned issue 82 )