Closed robotdelta closed 3 years ago
This hasn't been integrated yet into the URDF parser, but Klamp't has a notion of an "affine driver" that links together several DOFs in the .rob file. Maybe the easiest way to see how this works is with an example, like the PR2 gripper. You can convert the URDF to .rob and then add the affine driver in using a line "driver affine NUM_LINKS LINK1 ... LINKn SCALE1 ... SCALEn OFFSET1 ... OFFSETn MIN MAX VMIN VMAX AMIN AMAX". Other joints should have lines "driver normal LINK" stating that they are driven normally.
I'll put handling "mimic" joints on the TODO list for the next release!
Actually, I quickly wrote a parser that seems to work for your model (although I can't see the geometry). If you have built from source, could you try a "git pull" and rebuilding the RobotTest program to see if this solves your problem?
I just did a test with your new code, now it takes in account the mimic joint of the arm and the mimic joint of the gripper in URDF. I also tried to turn my URDF into rob and it work too. however when I try test the URDF or rob in SimTest it act very weird. maybe it's my file which is not very well created i will joint you my arm folder if you want to take a look but i think the subject is resolved.
thank you for your help and for this amazing job! robotic arm.zip
Cool robot!
I observed three issues: first, your URDF doesn't have any velocity limits or effort limits set. Setting them to effort="10" and velocity="2" helped somewhat.
Second, the simulated motors' PID constants need to be tuned, with later joints scaled lower. Adding this near the end of your file will help the simulation stability:
<klampt package_root="../../" freeze_root_link="1" defaultAccMax="10">
<noselfcollision group1="backpack_base liaison_moteur_1" group2="liaison_moteur_3 liaison_moteur_4 liaison_moteur_5"/>
<noselfcollision group1="liaison_moteur_2" group2="liaison_moteur_4 liaison_moteur_5" />
<noselfcollision group1="liaison_moteur_4 liaison_moteur_5" group2="liaison_moteur_62" />
<noselfcollision group1="liaison_doigt_1 liaison_doigt_2 liaison_doigt_3" />
<link name="liaison_moteur_1" servoP="100" servoI="0" servoD="5" dryFriction="0" viscousFriction="4" />
<link name="liaison_moteur_2" servoP="100" servoI="0" servoD="5" dryFriction="0" viscousFriction="4" />
<link name="liaison_moteur_3" servoP="100" servoI="0" servoD="5" dryFriction="0" viscousFriction="4" />
<link name="liaison_moteur_4" servoP="50" servoI="0" servoD="2.5" dryFriction="0" viscousFriction="3" />
<link name="liaison_moteur_5" servoP="25" servoI="0" servoD="1" dryFriction="0" viscousFriction="3" />
<link name="liaison_moteur_61" servoP="25" servoI="0" servoD="1" dryFriction="0" viscousFriction="2" />
<link name="liaison_poignet" servoP="10" servoI="0" servoD="0.5" dryFriction="0" viscousFriction="1" />
<link name="liaison_doigt_1" servoP="4" servoI="0" servoD=".2" dryFriction="0" viscousFriction="10" />
</klampt>
Third, I noticed a problem with the way Klamp't was interpreting angles from ODE in the mimic joint (in Klamp't terminology, the affine driver) simulation. Specifically, when an angle went negative, it would go to 2pi, and then the simulator would try to enforce the constraint that the angles should meet at the average: close to pi! I have fixed this in the latest version (master branch). Please pull and rebuild to see if this fixes the problem for you.
https://user-images.githubusercontent.com/4614220/106696551-f7225480-65aa-11eb-879d-578fccbd4591.mp4
I guess that video didn't go through. Let's try again
https://user-images.githubusercontent.com/4614220/106697322-83814700-65ac-11eb-9197-c3ff6787a113.mp4
I made a git pull as suggested and it doesn't act as weird as it used to but it's still not good in my case.
I added the modification you suggested to me and it seems that there are errors with the parser.
When I try to import the URDF file in SimTest, for example, it says:
KrisLibrary::logger(): URDFParser configured as default
URDFParser: Error, robot/klampt/noselfcollision does not contain pairs, or group1 and group2 attributes
URDFParser: Link size: 17
URDFParser: Joint size: 17
and it seams that the torque is automatically set at 0 for each driver making it impossible to maintain the goal position in the simulation.
after correcting these problems, I already get an error when I tried to do a goto in Simtest and the arm dos not move. I get : AppendRamp: Warning, DynamicPath::SetMilestones failed!
do you know what can cause this error ? did you use an app like SimTest or a custom code? Can you give me the URDF file you used for these videos and if you use the converter can you give me the .rob too?
I'm not sure what the remaining issue is, but it sounds like not all of the joints had efforts and velocities set in your URDF. Those videos were taken with SimTest. Here's the version I used.
hello, effectively, I forgot to set up the velocity in some links set to 0 by the URDF creator. Now it's working and it seems to take in count the noselfcollision even if he says the opposite.
I think this issue is resolved. Thank you.
Hello!
I'm new with this library and i try to migrate from ROS to this, because it seams more adapted to a real time motion planning for teleoperation.
I'm trying to use my robot with this but it have a mimic joint (2 joint rolling on each other and only one is actuated) I managed to create a functional file for ROS but it can't seams to work here. can we use this kind of joint with this? because I noticed that there was a function that contained this option:
in "urdf_joint.h"
or have I misconfigured my file? here my URDF bras_robotise_v3_8.txt