Closed ahundt closed 8 years ago
The URDF for the 14kg model comes from here. I never had a 14kg to play with for long, so I never had the chance to test how accurate those numbers are. What I noticed is that those made some sense when loading the robot onto Gazebo.
The inertia values are not there for the 7kg model and for various reasons I feel I have to step back from that duty, but the smartest idea would probably be to use the same approximation used in the Universal Robot stack using that _cylinderinertial macro for each link.
Thanks for the info!
@SalvoVirga to clarify, step back meaning you won't be able to do much development on iiwa_stack on an ongoing basis?
In case you are interested or someone comes across this question while googling I also came across this interesting looking paper about reverse engineering the inertia params on the previous lbr: http://www.dis.uniroma1.it/~labrob/pub/papers/ICRA14_LWR_RevMod.pdf
Oh no, I meant only about the inertia parameters. I have some professional/legal reasons that might clash with me working on that publicly.
Thanks for the link, I was aware of the good work of those Italian guys. The approximation done with the UR robots could be an easy first step to at least check if it is any good.
ok thanks that makes sense, I totally understand you need to fulfill those obligations. Though as an aside to me it seems very silly that inertia parameters are considered a trade secret! What will an adversary do, write code that runs on your hardware, making it easier to use, so you sell more units of very expensive robots??!? oh my, what a loss! :-)
added this in the wiki
The appendix of the following paper gives identified dynamic parameters for the IIWA 14 (R820): https://www.sciencedirect.com/science/article/pii/S2405896317317147?via%3Dihub
I wish the same experiment was made with the IIWA 7 version... The parameters currently used come from the following paper, as discussed in #35: http://www.inacomm2015.ammindia.org/img/94.pdf The values picked from this paper are the values estimated from CAD files, and do not come from identification. The authors clearly show at the end that they found a better set of parameters through identification, but do not provide them in the paper.
I have a student currently working on that. If he succeeds we should have parameters for the 7kg version. Timeline says about 6 weeks.
Awesome! Please keep me posted.
Just have a try rosdyn and rosdyn_examples which can calibrate the robot dynamics model.
Thank you so much @jacknlliu. This seems life-changing
@matthiashh Did your student managed to do this during this difficult time period?
[I separated work and private Github accounts now]
We have some parameters, but the thesis project ended before they could be properly evaluated.
Here are some points about the procedure:
Regarding the validation:
Before releasing values I think the following things should be done:
Maybe @SalvoVirga or somebody else knows something about those issues.
We experienced very jiggly execution of the robot with small accelerations and decelerations when executing some of the generated trajectories (stage 2 in ROSdyn, fyi) . We do not know the reason for this. It does not appear when using MoveIT from RViz and does not appear in some other trajectories (stage 1) ROSdyn creates. We noticed that we can circumvent the jiggles when executing the trajectories in T1.
I had the same issues with iiwa_stack
. It has been discussed a little bit with @jacknlliu in https://github.com/IFL-CAMP/iiwa_stack/issues/212
Apparently, there is a random delay introduced by SmartServo.
People from KUKA advised me to perform a “warm-up” and command the current position for about 200ms before starting to command the first motion.
Which is a problem when using MoveIt or ros_control in general, because we stop sending commands between trajectories so SmartServo gets into "nap mode"...
iiwa_stack only updates joint states at 50Hz. The developers of ROSdyn have their doubts that this is enough for a good estimation of the parameters
For those reasons I switched to iiwa_ros, which uses the FRI channel but allows for realtime control, from 200Hz to 1kHz.
Thanks @matthias-mayr. Keep us posted. I mostly need better gravity compensation, so mass and center of mass for each link
I think there is definitely something wrong in the IIWA7 model. On the left the IIWA14 model, on the right the IIWA7 model, showing the center of masses for each link in Gazebo 9.
I know there can be multiple working solutions with identification, but this one seems quite strange to me. Especially with link_6
The model parameters seem to come from this paper.
I didn't get the time to transform the identification coming from this paper using the DH convention, to the URDF convention. @ahundt @SalvoVirga, do one of you know the "ROS way" to convert the DH params to URDF style easily? How did you come up with this URDF for the IIWA7?
Many thanks !
I noticed you have inertia parameters: https://github.com/SalvoVirga/iiwa_stack/blob/master/iiwa_description/urdf/iiwa14.urdf#L51
Are they ballpark estimates, or very accurate ones? Thanks!