jros wrote:
> Hello!.
> 
> We are implementing a 6 dgf kinematics for a parallel manipulator.
> 
> (see http://imac/parallel/images/argazkiak/img_4336.jpg for a photograph
> of the machine without the head)
> 
> We are using as a template genhexkins.c file so that compiling and
> launching is not a problem.
> 
> We have provided new implementations for forward and inverse kinematics.
> 
> And we are continuously hanging ./scripts/emc hexapod-sim. Well, the
> computers gets frozen, and we have to reset it!!!!!.
> 
> I've compiled the kinematics outside emc providing a main, and it seems
> that we have done a correct programing.
> 
> Forwardkinematics requires a newton raphson iteration, much longer to
> compute compared with Inverse kinematics.
> 
> A 9 newton raphson iteration calculation requires on a 100000 iteration
> average a calculation time of 0.000797 secs
> in our computer.
> 
> As emc hangs we've tried to use trivkins to replace the forward and
> inverse kins in genhexkins.c and it works ok, it does not hangs.
> 
> As a last try, we have forced our kinematics to output the trivkins
> kinematics, but forcing it to internaly deal with all the computations
> of our model (we are forcing 9 newton-raphson iterations), in order to
> see if it is a "too time consuming subrutine" problem.
> 
> It works, it seems it works slower that with the surplus of
> computations.
> 
> But we are eye blinded to to see what is happening in fact within our
> subrutine, how many iterations? output values? and input values?.
> 
> Being the kinematics a real time module, I presume that printf debuging
> will not work, more if the aplication freezes the computer.
> 
> I presume the only posibility is to use dmesg, but I don't know how to
> send output so that I can see what is happening with dmesg
> 
> What can I do?, or where can I read about dealing with this type of real
> time subrutine debugging?.
> 
> I think I can try to debug using dmesg approach, using a working
> kinematics -so the computer does not get freezed- (as the trivkins
> approach mentioned before) to see what are the subrutines called and the
> values of the variables passed to them, and hopefully discover what is
> going on.
> 
> Thanks in advance

There are several approaches that you can use.

rtapi_print_msg() can be used to print messages to the kernel log 
(dmesg).  I'm pretty sure there is a man page for it.  Keep in mind
that your code is being called 1000 times a second, so printing 
something every time is probably not a good idea.  Also, 
rtapi_print_msg() can't print floating point values.

One very handy troubleshooting technique is to export a few extra HAL 
parameters.  You can then observe their values with halmeter and/or 
halscope.

If your kins calculations take 0.000797 seconds, you might simply be
overwhelming the PC.  The default period for the servo thread is 0.0001 
seconds.  Your kins code will use almost 80% of the CPU, which doesn't 
leave much at all for other realtime code or the operating system.

You could try changing the servo period from 1mS to 2mS or more to see
if that helps.

Regards,

John Kasunich


-------------------------------------------------------------------------
This SF.net email is sponsored by: Microsoft
Defy all challenges. Microsoft(R) Visual Studio 2005.
http://clk.atdmt.com/MRT/go/vse0120000070mrt/direct/01/
_______________________________________________
Emc-users mailing list
Emc-users@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/emc-users

Reply via email to