Dynomotion

Group: DynoMotion Message: 7044 From: Jad Rizk Date: 3/19/2013
Subject: MsgBox
Hello Tom,

I was using C program Kfloptopccmdexamples.c in version 4.29
I only kept the part of the program that gives the msgbox hello world.

When i switched to version 4.30 the message box only works the first time I initiate the program. If i run the program again the thread will keep running without showing me the message.

If I close kmotionCNC and open it again the messagebox shows.

So in the new version the msgbox only works the first time i use it after running kmotioncnc

Thank you,
Jad

Group: DynoMotion Message: 7045 From: Jad Rizk Date: 3/19/2013
Subject: Re: MsgBox
Please advise. Is it something I am doing wrong?


On Tue, Mar 19, 2013 at 2:40 PM, Jad Rizk <jadrizk89@...> wrote:
Hello Tom,

I was using C program Kfloptopccmdexamples.c in version 4.29
I only kept the part of the program that gives the msgbox hello world.

When i switched to version 4.30 the message box only works the first time I initiate the program. If i run the program again the thread will keep running without showing me the message.

If I close kmotionCNC and open it again the messagebox shows.

So in the new version the msgbox only works the first time i use it after running kmotioncnc

Thank you,
Jad


Group: DynoMotion Message: 7049 From: Tom Kerekes Date: 3/19/2013
Subject: Re: MsgBox
Hi Jad,

I'm not sure.  Please post the code you are using.  Or preferably a simple example that shows the problem.

Regards
TK

Group: DynoMotion Message: 7069 From: Jad Rizk Date: 3/19/2013
Subject: Re: MsgBox
Hello Tom,


The program I am using is the same. When I run this program in version 4.29 The msgbox shows every time. In version 4.30, the first time I run the c program the msg box shows, then if I run it again the msgbox does not show unless I exit kmotionCNC and enter it again.

Thank you,
Jad



#include "KMotionDef.h"

int DoPC(int cmd);
int DoPCFloat(int cmd, float f);
int DoPCInt(int cmd, int i);
int MsgBox(char *s, int Flags);
int SetVars(int poff, int varoff, int n);
int GetVars(int varoff, int n, int poff);


main()
{
int Answer;
double *pD = (double *)persist.UserData;

Answer = MsgBox("Hello World",MB_YESNO|MB_ICONEXCLAMATION);
if (Answer == IDYES)
printf("Answer is Yes\n");
else
printf("Answer is No\n");
}

int SetVars(int varoff, int n, int poff)
{
persist.UserData[PC_COMM_PERSIST+2] = n;       // number of elements
persist.UserData[PC_COMM_PERSIST+3] = poff;    // persist offset (doubles)
return DoPCInt(PC_COMM_SET_VARS,varoff);       // Var index and Cmd
}

int GetVars(int varoff, int n, int poff)
{
persist.UserData[PC_COMM_PERSIST+2] = n;       // number of elements
persist.UserData[PC_COMM_PERSIST+3] = poff;    // persist offset (doubles)
return DoPCInt(PC_COMM_GET_VARS,varoff);       // Var index and Cmd
}


#define GATH_OFF 0  // define the offset into the Gather buffer where strings are passed

// Trigger a message box on the PC to be displayed
// defines for MS Windows message box styles and Operator
// response IDs are defined in the KMotionDef.h file 
int MsgBox(char *s, int Flags)
{
char *p=(char *)gather_buffer+GATH_OFF*sizeof(int);
int i;
do // copy to gather buffer w offset 0
{
*p++ = *s++;
}while (s[-1]);
persist.UserData[PC_COMM_PERSIST+2] = Flags;  // set options
DoPCInt(PC_COMM_MSG,GATH_OFF);
return persist.UserData[PC_COMM_PERSIST+3];
}

// put the MDI string (Manual Data Input - GCode) in the 
// gather buffer and tell the App where it is
int MDI(char *s)
{
char *p=(char *)gather_buffer+GATH_OFF*sizeof(int);
int i;
do // copy to gather buffer w offset 0
{
*p++ = *s++;
}while (s[-1]);
// issue the command an wait till it is complete
// (or an error - such as busy)
return DoPCInt(PC_COMM_MDI,GATH_OFF);
}

// Put a Float as a parameter and pass the command to the App
int DoPCFloat(int cmd, float f)
{
int result;
persist.UserData[PC_COMM_PERSIST+1] = *(int*)&f;
return DoPC(cmd);
}

// Put an integer as a parameter and pass the command to the App
int DoPCInt(int cmd, int i)
{
int result;
persist.UserData[PC_COMM_PERSIST+1] = i;
return DoPC(cmd);
}

// Pass a command to the PC and wait for it to handshake
// that it was received by either clearing the command
// or changing it to a negative error code
int DoPC(int cmd)
{
int result;
persist.UserData[PC_COMM_PERSIST]=cmd;
do
{
WaitNextTimeSlice();
}while (result=persist.UserData[PC_COMM_PERSIST]>0);
printf("Result = %d\n",result);

return result;
}



On Tue, Mar 19, 2013 at 7:16 PM, Tom Kerekes <tk@...> wrote:
 

Hi Jad,

I'm not sure.  Please post the code you are using.  Or preferably a simple example that shows the problem.

Regards
TK

Group: DynoMotion Message: 7070 From: Tom Kerekes Date: 3/20/2013
Subject: Re: MsgBox
Hi Jad,

You are correct a bug was introduced.  Here is a Patch.  Copy to your <Install>\KMotion\Release directory.

http://dynomotion.com/Software/Patch/FixKFLOPtoKMotionCNCMsgBox/KMotionCNC.exe

Thanks
TK

Group: DynoMotion Message: 7072 From: Jad Rizk Date: 3/20/2013
Subject: Re: MsgBox
Thank you Tom.

I need some more help if possible.
I am changing Kinematics.c and using a kinematic transformation in the source code. I am not a professional programmer but I managed to change what I want in Kinematics.c and it worked.
So I guess the patch will not work if I am rebuilding KmotionCNC.
 Any thoughts?

Thank you,
Jad



On Wed, Mar 20, 2013 at 9:19 AM, Tom Kerekes <tk@...> wrote:
 

Hi Jad,

You are correct a bug was introduced.  Here is a Patch.  Copy to your <Install>\KMotion\Release directory.

http://dynomotion.com/Software/Patch/FixKFLOPtoKMotionCNCMsgBox/KMotionCNC.exe

Thanks
TK

Group: DynoMotion Message: 7074 From: Tom Kerekes Date: 3/20/2013
Subject: Re: MsgBox
Hi Jad,

Can you share what you have done with the kinematics?

But The Kinematics is compiled as part of the GCodeInterpreter.dll which is compiled separate from the KMotionCNC.exe application where the fix was made.  So the patch should work for you.

But anyways I've attached the file I changed.  There is just 2 lines changed if you wish to merge or make the change.  See this area:

void CKMotionCNCDlg::OnTimer(UINT nIDEvent)
{
    static int Entry=0;
    int result;

    if (Entry>0) return;  // do not allow re-entries

    Entry++;

Regards
TK

Group: DynoMotion Message: 7076 From: Jad Rizk Date: 3/21/2013
Subject: Re: MsgBox [1 Attachment]
Hello Tom,

Thank you for your help. I also changed in the KmotionCNC UI.
I removed the EStop and execute button by disabling them and rearranged the rest of the buttons. I will be only using hard buttons for Estop, execute and halt cycle.
As for the kinematics file.

I added a limit for B which I am using as angular axes:

In CKinematics::TransformCADtoActuators, I added at the beginning:

if(b<-60)    //In degrees
b=-60;
if(b>60)    //In degrees
b=60;

and I added a correction for X Y, and Z caused by the B angle:

I calculated  corrX, corrY and corrZ from the kinematic transformation matrix of my machine

Acts[0] = (x)*m_MotionParams.CountsPerInchX-corrX;
Acts[1] = (y)*m_MotionParams.CountsPerInchY-corrY;
Acts[2] = (z)*m_MotionParams.CountsPerInchZ-corrZ;

And In CKinematics::TransformActuatorstoCAD

I have:

*x = Acts[0] / m_MotionParams.CountsPerInchX+corrX;
*y = Acts[1] / m_MotionParams.CountsPerInchY+corrY;
*z = Acts[2] / m_MotionParams.CountsPerInchZ+corrZ;


The machine is not finished yet but I already tested the program using the board only and comparing the values to excel sheets.
So far everything is going well but I wont be sure until I test the program on the machine so I make sure everything is coordinated and the speeds are correct.

Sincerely,
Jad




On Thu, Mar 21, 2013 at 1:37 AM, Tom Kerekes <tk@...> wrote:
 
[Attachment(s) from Tom Kerekes included below]

Hi Jad,

Can you share what you have done with the kinematics?

But The Kinematics is compiled as part of the GCodeInterpreter.dll which is compiled separate from the KMotionCNC.exe application where the fix was made.  So the patch should work for you.

But anyways I've attached the file I changed.  There is just 2 lines changed if you wish to merge or make the change.  See this area:

void CKMotionCNCDlg::OnTimer(UINT nIDEvent)
{
    static int Entry=0;
    int result;

    if (Entry>0) return;  // do not allow re-entries

    Entry++;

Regards
TK

Group: DynoMotion Message: 7077 From: michaelthomasn Date: 3/21/2013
Subject: Re: MsgBox [1 Attachment]
Hi Jad,

Your project sounds interesting to me.

What is your machine configuration, and what does it do?

I have to modify the kinematics file for a 5 axis arm I'm working on.

I'm still staring at the kinematics3rod example trying to figure out exactly what is going on there....so having extra examples like yours is helpful in getting a better picture.

I'm guessing that the file examines the requested destination g code(TransformCADTOActuators), then applies the supplied machine specific formulas to get angular outputs(in my case)to use....TransformActuatorsToCAD.

I made a spreadsheet for my inverse kinematics as well....but currently I haven't figured out how to implement it, yet. I type in a x,y,z,a,c destination, and the spreadsheet calculates the needed arm angles. Is this what your sheet, does as well?

My spreadsheet is rather complex (to me anyway :-)) since none of my 5 axis' are linear. It was a bit fickle, too.....I had to add a fair amount of IF statements because the 4th and 5th axis' (wrist) would often display complementary angles.


Mike


--- In DynoMotion@yahoogroups.com, Jad Rizk <jadrizk89@...> wrote:
>
> Hello Tom,
>
> Thank you for your help. I also changed in the KmotionCNC UI.
> I removed the EStop and execute button by disabling them and rearranged the
> rest of the buttons. I will be only using hard buttons for Estop, execute
> and halt cycle.
> As for the kinematics file.
>
> I added a limit for B which I am using as angular axes:
>
> In CKinematics::TransformCADtoActuators, I added at the beginning:
>
> if(b<-60) //In degrees
> b=-60;
> if(b>60) //In degrees
> b=60;
>
> and I added a correction for X Y, and Z caused by the B angle:
>
> I calculated corrX, corrY and corrZ from the kinematic transformation
> matrix of my machine
>
> Acts[0] = (x)*m_MotionParams.CountsPerInchX-corrX;
> Acts[1] = (y)*m_MotionParams.CountsPerInchY-corrY;
> Acts[2] = (z)*m_MotionParams.CountsPerInchZ-corrZ;
>
> And In CKinematics::TransformActuatorstoCAD
>
> I have:
>
> *x = Acts[0] / m_MotionParams.CountsPerInchX+corrX;
> *y = Acts[1] / m_MotionParams.CountsPerInchY+corrY;
> *z = Acts[2] / m_MotionParams.CountsPerInchZ+corrZ;
>
>
> The machine is not finished yet but I already tested the program using the
> board only and comparing the values to excel sheets.
> So far everything is going well but I wont be sure until I test the program
> on the machine so I make sure everything is coordinated and the speeds are
> correct.
>
> Sincerely,
> Jad
>
>
>
>
> On Thu, Mar 21, 2013 at 1:37 AM, Tom Kerekes <tk@...> wrote:
>
> > **
> >
> > [Attachment(s) <#13d8a2b01ef77d19_TopText> from Tom Kerekes included
> > below]
> >
> > Hi Jad,
> >
> > Can you share what you have done with the kinematics?
> >
> > But The Kinematics is compiled as part of the GCodeInterpreter.dll which
> > is compiled separate from the KMotionCNC.exe application where the fix was
> > made. So the patch should work for you.
> >
> > But anyways I've attached the file I changed. There is just 2 lines
> > changed if you wish to merge or make the change. See this area:
> >
> > void CKMotionCNCDlg::OnTimer(UINT nIDEvent)
> > {
> > static int Entry=0;
> > int result;
> >
> > if (Entry>0) return; // do not allow re-entries
> >
> > Entry++;
> >
> > Regards
> > TK
> >
> > ------------------------------
> > *From:* Jad Rizk <jadrizk89@...>
> > *To:* DynoMotion@yahoogroups.com
> > *Sent:* Wednesday, March 20, 2013 3:15 AM
> > *Subject:* Re: [DynoMotion] Re: MsgBox
> >
> >
> > Thank you Tom.
> >
> > I need some more help if possible.
> > I am changing Kinematics.c and using a kinematic transformation in the
> > source code. I am not a professional programmer but I managed to change
> > what I want in Kinematics.c and it worked.
> > So I guess the patch will not work if I am rebuilding KmotionCNC.
> > Any thoughts?
> >
> > Thank you,
> > Jad
> >
> >
> >
> > On Wed, Mar 20, 2013 at 9:19 AM, Tom Kerekes <tk@...> wrote:
> >
> > **
> >
> > Hi Jad,
> >
> > You are correct a bug was introduced. Here is a Patch. Copy to your
> > <Install>\KMotion\Release directory.
> >
> >
> > http://dynomotion.com/Software/Patch/FixKFLOPtoKMotionCNCMsgBox/KMotionCNC.exe
> >
> > Thanks
> > TK
> >
> > ------------------------------
> > *From:* Jad Rizk <jadrizk89@...>
> > *To:* DynoMotion@yahoogroups.com
> > *Sent:* Tuesday, March 19, 2013 11:43 PM
> > *Subject:* Re: [DynoMotion] Re: MsgBox
> >
> >
> > Hello Tom,
> >
> >
> > The program I am using is the same. When I run this program in version
> > 4.29 The msgbox shows every time. In version 4.30, the first time I run the
> > c program the msg box shows, then if I run it again the msgbox does not
> > show unless I exit kmotionCNC and enter it again.
> >
> > Thank you,
> > Jad
> >
> >
> >
> > #include "KMotionDef.h"
> >
> > int DoPC(int cmd);
> > int DoPCFloat(int cmd, float f);
> > int DoPCInt(int cmd, int i);
> > int MsgBox(char *s, int Flags);
> > int SetVars(int poff, int varoff, int n);
> > int GetVars(int varoff, int n, int poff);
> >
> >
> > main()
> > {
> > int Answer;
> > double *pD = (double *)persist.UserData;
> >
> > Answer = MsgBox("Hello World",MB_YESNO|MB_ICONEXCLAMATION);
> > if (Answer == IDYES)
> > printf("Answer is Yes\n");
> > else
> > printf("Answer is No\n");
> > }
> >
> > int SetVars(int varoff, int n, int poff)
> > {
> > persist.UserData[PC_COMM_PERSIST+2] = n; // number of elements
> > persist.UserData[PC_COMM_PERSIST+3] = poff; // persist offset
> > (doubles)
> > return DoPCInt(PC_COMM_SET_VARS,varoff); // Var index and Cmd
> > }
> >
> > int GetVars(int varoff, int n, int poff)
> > {
> > persist.UserData[PC_COMM_PERSIST+2] = n; // number of elements
> > persist.UserData[PC_COMM_PERSIST+3] = poff; // persist offset
> > (doubles)
> > return DoPCInt(PC_COMM_GET_VARS,varoff); // Var index and Cmd
> > }
> >
> >
> > #define GATH_OFF 0 // define the offset into the Gather buffer where
> > strings are passed
> >
> > // Trigger a message box on the PC to be displayed
> > // defines for MS Windows message box styles and Operator
> > // response IDs are defined in the KMotionDef.h file
> > int MsgBox(char *s, int Flags)
> > {
> > char *p=(char *)gather_buffer+GATH_OFF*sizeof(int);
> > int i;
> > do // copy to gather buffer w offset 0
> > {
> > *p++ = *s++;
> > }while (s[-1]);
> > persist.UserData[PC_COMM_PERSIST+2] = Flags; // set options
> > DoPCInt(PC_COMM_MSG,GATH_OFF);
> > return persist.UserData[PC_COMM_PERSIST+3];
> > }
> >
> > // put the MDI string (Manual Data Input - GCode) in the
> > // gather buffer and tell the App where it is
> > int MDI(char *s)
> > {
> > char *p=(char *)gather_buffer+GATH_OFF*sizeof(int);
> > int i;
> > do // copy to gather buffer w offset 0
> > {
> > *p++ = *s++;
> > }while (s[-1]);
> > // issue the command an wait till it is complete
> > // (or an error - such as busy)
> > return DoPCInt(PC_COMM_MDI,GATH_OFF);
> > }
> >
> > // Put a Float as a parameter and pass the command to the App
> > int DoPCFloat(int cmd, float f)
> > {
> > int result;
> > persist.UserData[PC_COMM_PERSIST+1] = *(int*)&f;
> > return DoPC(cmd);
> > }
> >
> > // Put an integer as a parameter and pass the command to the App
> > int DoPCInt(int cmd, int i)
> > {
> > int result;
> > persist.UserData[PC_COMM_PERSIST+1] = i;
> > return DoPC(cmd);
> > }
> >
> > // Pass a command to the PC and wait for it to handshake
> > // that it was received by either clearing the command
> > // or changing it to a negative error code
> > int DoPC(int cmd)
> > {
> > int result;
> > persist.UserData[PC_COMM_PERSIST]=cmd;
> > do
> > {
> > WaitNextTimeSlice();
> > }while (result=persist.UserData[PC_COMM_PERSIST]>0);
> > printf("Result = %d\n",result);
> >
> > return result;
> > }
> >
> >
> >
> > On Tue, Mar 19, 2013 at 7:16 PM, Tom Kerekes <tk@...> wrote:
> >
> > **
> >
> > Hi Jad,
> >
> > I'm not sure. Please post the code you are using. Or preferably a simple
> > example that shows the problem.
> >
> > Regards
> > TK
> >
> > ------------------------------
> > *From:* Jad Rizk <jadrizk89@...>
> > *To:* DynoMotion@yahoogroups.com
> > *Sent:* Tuesday, March 19, 2013 5:45 AM
> > *Subject:* [DynoMotion] Re: MsgBox
> >
> >
> > Please advise. Is it something I am doing wrong?
> >
> >
> > On Tue, Mar 19, 2013 at 2:40 PM, Jad Rizk <jadrizk89@...> wrote:
> >
> > Hello Tom,
> >
> > I was using C program Kfloptopccmdexamples.c in version 4.29
> > I only kept the part of the program that gives the msgbox hello world.
> >
> > When i switched to version 4.30 the message box only works the first time
> > I initiate the program. If i run the program again the thread will keep
> > running without showing me the message.
> >
> > If I close kmotionCNC and open it again the messagebox shows.
> >
> > So in the new version the msgbox only works the first time i use it after
> > running kmotioncnc
> >
> > Thank you,
> > Jad
> >
> >
> >
> >
> >
> >
> >
> >
> >
> >
> >
> >
>
Group: DynoMotion Message: 7101 From: Jad Rizk Date: 3/23/2013
Subject: Re: MsgBox

Hello Mike,

Ill tell you what i did hopefully it will help.

First I got the kinematics and inverse kinematics , I used them both in kinematics.cpp

I made a spreadsheet to make sure everything is correct with both transformations:
I can give x,y,z,a and b and get all 5 motor displacement (inverse kinematics), or i can give the 5 motor displacement and get the tool coordinates(x,y,z,a,b)(forward kinematics).

In kinematics.cpp, i put the inverse kinematic transformation in transformcadtoactuators and the forward kinematic in transformactuatorstocad.

Kmotioncnc takes the coordinates taken from the g code, runs them through transformcadtoactuators and turns the motors.
Transformactuatorstocad reads where the motors are supposed to be (motors channel destination) and returns x,y,z,a,b on the screen of kmotioncnc.

My transformation is also not linear. So the first thing i did was to solve all singular points in my transformation(so like you I used a lot of if statements)
Right now i think its working, but as i said, its just "on paper" i need to test it on the machine to make sure it really is.

I hope this helps, let me know what you think.

Sincerely,

Jad

Group: DynoMotion Message: 7103 From: michaelthomasn Date: 3/23/2013
Subject: Re: MsgBox
Jad,

Thanks for the response.

I'm confused by the need of a forward kinematics solver. I see it as being inverse kinematics = g code to actuator angles, and forward kinematics = actuator angles to g code.....as you have said. It seems to me that the variables that forward kinematics would solve for are already know from the input g code.....x,y,z,a,c(destination).

What am I missing?

Also, where are you putting you actual formulas?

Mike
Group: DynoMotion Message: 7104 From: Tom Kerekes Date: 3/23/2013
Subject: Re: MsgBox
Hi Mike,

The GCode coordinate is only the theoretical final destination.  It isn't absolutely required but if you wish to display where the tool actually is moment by moment the forward kinematics is required.   Actually the CKinematics class has code such that if you specify one direction for the kinematics the other direction can be automatically be solved for numerically.

Regards
TK

Group: DynoMotion Message: 7106 From: michaelthomasn Date: 3/23/2013
Subject: Re: MsgBox
Thanks, Tom

I was thinking that the code would be broken down to very small linear movements anyway(depending on the smallest segment setting). Are you saying that only the input gcode final destination would be displayed.....or would the endpoints of all of the small segments that the move was broken into be displayed?

"Actually the CKinematics class has code such that if you specify one direction for the kinematics the other direction can be automatically be solved for numerically"

Are you meaning that I actually would not have to specify the forward kinematics if I supplied the inverse kinematics?

I ran across this site today, and haven't had a lot of time to explore it yet....but it appears to be an open site that has inverse kinematics solvers available in C++.....amongst many other cool things for robotics.

It looks as though I need VS 2008 to be able to use the core program....which I don't have, yet.

I wonder if you have ever browsed this site?

http://openrave.org/docs/latest_stable/

Mike




--- In DynoMotion@yahoogroups.com, Tom Kerekes <tk@...> wrote:
>
> Hi Mike,
>
> The GCode coordinate is only the theoretical final destination.  It isn't absolutely required but if you wish to display where the tool actually is moment by moment the forward kinematics is required.   Actually the CKinematics class has code such that if you specify one direction for the kinematics the other direction can be automatically be solved for numerically.
>
> Regards
> TK
>
>
>
> ________________________________
> From: michaelthomasn <michaelniksch@...>
> To: DynoMotion@yahoogroups.com
> Sent: Saturday, March 23, 2013 7:57 AM
> Subject: [DynoMotion] Re: MsgBox
>
>
>  
> Jad,
>
> Thanks for the response.
>
> I'm confused by the need of a forward kinematics solver. I see it as being inverse kinematics = g code to actuator angles, and forward kinematics = actuator angles to g code.....as you have said. It seems to me that the variables that forward kinematics would solve for are already know from the input g code.....x,y,z,a,c(destination).
>
> What am I missing?
>
> Also, where are you putting you actual formulas?
>
> Mike
>
Group: DynoMotion Message: 7108 From: Tom Kerekes Date: 3/23/2013
Subject: Re: MsgBox
Hi Mike,

Even though a big movement is in fact broken down into smaller linear segments you still might wish to know exactly where the tool is rather than some closest segment.  Furthermore segments are computed, buffered, and downloaded in advance so associating which segment is even associated with the current tool position would be difficult.

In the Kinematics3Rod example we only provide the CAD space to Actuator transformation which is fairly straightforward.  Then solve the inverse numerically.  Usually an exact analytical model is either too complex or all the parameters are not known perfectly so the result is imperfect.  We then use a geometric correction table to make final small corrections.  This would make solving the inverse transformation analytically extremely difficult.  

Regards
TK
 
Group: DynoMotion Message: 7112 From: michaelthomasn Date: 3/24/2013
Subject: Re: MsgBox
Thanks again, Tom.

I see what you mean.

The use for this arm is going to be for loading very small parts into a 2nd operation mill.

The linear movement is not really necessary except when inserting the part into its collet. It pretty much has to go straight in. I may just be able to jog axis' and use the values on the screen to "teach" position.

It would seem much easier to program the pickup of parts from the grid block, too.....if things were linear.

I don't know , yet.

I hope to have the physical arm constructed within the next month, so I suppose I can see what I need then, instead of speculating.

I'll start another thread if I have any more questions.....sorry to have hijacked this one, Jad.

Thanks again, Mike



--- In DynoMotion@yahoogroups.com, Tom Kerekes <tk@...> wrote:
>
> Hi Mike,
>
> Even though a big movement is in fact broken down into smaller linear segments you still might wish to know exactly where the tool is rather than some closest segment.  Furthermore segments are computed, buffered, and downloaded in advance so associating which segment is even associated with the current tool position would be difficult.
>
> In the Kinematics3Rod example we only provide the CAD space to Actuator transformation which is fairly straightforward.  Then solve the inverse numerically.  Usually an exact analytical model is either too complex or all the parameters are not known perfectly so the result is imperfect.  We then use a geometric correction table to make final small corrections.  This would make solving the inverse transformation analytically extremely difficult.  
>
> Regards
> TK
>  
>
>
> ________________________________
> From: michaelthomasn <michaelniksch@...>
> To: DynoMotion@yahoogroups.com ficult
> Sent: Saturday, March 23, 2013 2:42 PM
> Subject: [DynoMotion] Re: MsgBox
>
>
>  
> Thanks, Tom
>
> I was thinking that the code would be broken down to very small linear movements anyway(depending on the smallest segment setting). Are you saying that only the input gcode final destination would be displayed.....or would the endpoints of all of the small segments that the move was broken into be displayed?
>
> "Actually the CKinematics class has code such that if you specify one direction for the kinematics the other direction can be automatically be solved for numerically"
>
> Are you meaning that I actually would not have to specify the forward kinematics if I supplied the inverse kinematics?
>
> I ran across this site today, and haven't had a lot of time to explore it yet....but it appears to be an open site that has inverse kinematics solvers available in C++.....amongst many other cool things for robotics.
>
> It looks as though I need VS 2008 to be able to use the core program....which I don't have, yet.
>
> I wonder if you have ever browsed this site?
>
> http://openrave.org/docs/latest_stable/
>
> Mike
>
> --- In DynoMotion@yahoogroups.com, Tom Kerekes <tk@> wrote:
> >
> > Hi Mike,
> >
> > The GCode coordinate is only the theoretical final destination.  It isn't absolutely required but if you wish to display where the tool actually is moment by moment the forward kinematics is required.   Actually the CKinematics class has code such that if you specify one direction for the kinematics the other direction can be automatically be solved for numerically.
> >
> > Regards
> > TK
> >
> >
> >
> > ________________________________
> > From: michaelthomasn <michaelniksch@>
> > To: DynoMotion@yahoogroups.com
> > Sent: Saturday, March 23, 2013 7:57 AM
> > Subject: [DynoMotion] Re: MsgBox
> >
> >
> >  
> > Jad,
> >
> > Thanks for the response.
> >
> > I'm confused by the need of a forward kinematics solver. I see it as being inverse kinematics = g code to actuator angles, and forward kinematics = actuator angles to g code.....as you have said. It seems to me that the variables that forward kinematics would solve for are already know from the input g code.....x,y,z,a,c(destination).
> >
> > What am I missing?
> >
> > Also, where are you putting you actual formulas?
> >
> > Mike
> >
>