Hi everyone,
I have a 6DOF robot. So far I have manage to generate the ikfast Transformation6D and the 6D kinematic reachability. ![]() Following the recommendation from this anwser I have tried --iktests=100000 and the result is 99.5%. So everything looks fine. When I ran the kinematicreachability generator: openrave.py --database kinematicreachability --robot=MYROBOT --numthreads=8 The console shows: openravepy.databases.kinematicreachability: generatepcg, radius: 1.524719, xyzsamples: 231690, quatdelta: 0.513496 But in the resulting file (reachability.pp) I have the following (I used hdfview to check the file): * reachability3d (7529448): 64-bit floating-point, 76 x 76 x 76 * reachabilitydensity3d (1672): 64-bit floating-point, 76 x 76 x 76 * reachabilitystats (1400): 64-bit floating-point, 62742 x 8 1) Shouldn't xyzsamples (231690) be equal to reachabilitystats (62742)? 2) How are these values related? I mean, I assume that each pose in reachabilitystats should have a corresponding value in reachability3d but the size of the datasets doesn't match. 3) What do the colors (red, blue, green, yellow, etc) in mayivi (above figure) stand for? Thanks in advance |
Administrator
|
these are excellent questions! First, you should take a look at the kinematicreachability source:http://www.openrave.org/docs/latest_stable/_modules/openravepy/databases/kinematicreachability/#ReachabilityModel reachabilitystats - Nx8 array of all the poses that are reachable. The first 7 columns are the quaternion and translation, the last column is the number of IK solutions present reachability3d - a KxKxK voxelized map that repsents the density of solutions for each XYZ point. The higher the density, the more rotations the arm can be solved for. Use xyzdelta to from 3D point to voxel index. rosen, 2013/8/15 fsuarez6 <[hidden email]> Hi everyone, ------------------------------------------------------------------------------ Get 100% visibility into Java/.NET code with AppDynamics Lite! It's a free troubleshooting tool designed for production. Get down to code-level detail for bottlenecks, with <2% overhead. Download for free and get started troubleshooting in minutes. http://pubads.g.doubleclick.net/gampad/clk?id=48897031&iu=/4140/ostg.clktrk _______________________________________________ Openrave-users mailing list [hidden email] https://lists.sourceforge.net/lists/listinfo/openrave-users |
Free forum by Nabble | Edit this page |