Spray Robot
Moderators: TomKerekes, dynomotion
-
- Posts: 60
- Joined: Fri Apr 27, 2018 10:43 pm
Re: Spray Robot
Very good, I made all of the changes you suggested. Here is my updated code, and some screen shots of the StdAfx.h files and CoordMotion.cpp.
So with the non-linear motion. How will the trajectory planner work? There are no linear parameters for Cnts/inch, velocity, and Accel. I will be using 10:1 gearbox reductions for the drives with 1.8 degree steppers. Not sure how that part will work.
I am also assuming that the other axis will remain linear? If I want to add a rotary A,B,or C, or linear Z,U,or V I will just set it up as I normally would?
Thanks,
I believe that I am ready to start the build and debugging process. In the past I have had syntax errors in my math . Do you know if there is a way to simulate X/Y values and step through the math to see if the values are what I would expect them to be? I have some help over the weekend figuring out how to rebuild the libraries. Though it looks like it is as simple as pressing F7?So with the non-linear motion. How will the trajectory planner work? There are no linear parameters for Cnts/inch, velocity, and Accel. I will be using 10:1 gearbox reductions for the drives with 1.8 degree steppers. Not sure how that part will work.
I am also assuming that the other axis will remain linear? If I want to add a rotary A,B,or C, or linear Z,U,or V I will just set it up as I normally would?
Thanks,
- Attachments
-
- StdAfx.h
- (2.26 KiB) Downloaded 300 times
-
- CoordMotion.cpp
- (87.64 KiB) Downloaded 296 times
-
- Kinematics2AxisRobot.h
- (978 Bytes) Downloaded 303 times
-
- Kinematics2AxisRobot.cpp
- (2.63 KiB) Downloaded 293 times
- TomKerekes
- Posts: 2676
- Joined: Mon Dec 04, 2017 1:49 am
Re: Spray Robot
Hi Scott,
Regarding StdAfx.h: It would make more sense to include your kinematics .h file before GCodeInterpreter.h like the other kinematic headers. The idea is to define things in the order they are needed. If the GCodeInterpreter.h references your class it wouldn't be defined yet.
Regarding CoordMotion.cpp you forgot the beginning C in the class name.
Regarding Assigning the Linkage values: that would work assigning them in the TransformCADtoActuators function every time but just make the PC work a little harder. But better to move that to the constructor so it is only set once as they never change. Move them immediately under the line:
m_MotionParams.UseOnlyLinearSegments=true;
Regarding TransformCADtoActuators() function: I forgot to mention that C/C++ functions like sin and acos all operate in radians. So I think all you need to do is change 180 to PI. PI is probably already defined somewhere earlier, if not no worries the compiler will tell you. Also the final angles r0 r1 will be in radians. Multiply by (180.0/PI) to convert to degrees.
On a side note it is best practice to tell the compiler a number's type is floating point by adding a decimal point. For example 2.0 instead of 2 without the decimal. I don't think it matters in your cases because all your math mixes numbers with doubles and the compiler will automatically "promote" an integer to double whe there is a mix of integers and doubles. But it is still a good habit to get into. Otherwise you will eventually discover a nasty bug where for example 1/4 = 0 as the compiler will do integer division instead of floating point division. It hurts my eyes to see those integers
There is one complication. The TransformCADtoActuators() function is being called continuously with changing values as it is used to numerically reverse determine the CAD position from the Motor positions (sort of like trial and error). This saves you from having to come up with the math for determining the CAD position from the motor angles. So here is what I would do.
16 / 1.8 x 10
Hang in there you are making progress
Regarding StdAfx.h: It would make more sense to include your kinematics .h file before GCodeInterpreter.h like the other kinematic headers. The idea is to define things in the order they are needed. If the GCodeInterpreter.h references your class it wouldn't be defined yet.
Regarding CoordMotion.cpp you forgot the beginning C in the class name.
Regarding Assigning the Linkage values: that would work assigning them in the TransformCADtoActuators function every time but just make the PC work a little harder. But better to move that to the constructor so it is only set once as they never change. Move them immediately under the line:
m_MotionParams.UseOnlyLinearSegments=true;
Regarding TransformCADtoActuators() function: I forgot to mention that C/C++ functions like sin and acos all operate in radians. So I think all you need to do is change 180 to PI. PI is probably already defined somewhere earlier, if not no worries the compiler will tell you. Also the final angles r0 r1 will be in radians. Multiply by (180.0/PI) to convert to degrees.
On a side note it is best practice to tell the compiler a number's type is floating point by adding a decimal point. For example 2.0 instead of 2 without the decimal. I don't think it matters in your cases because all your math mixes numbers with doubles and the compiler will automatically "promote" an integer to double whe there is a mix of integers and doubles. But it is still a good habit to get into. Otherwise you will eventually discover a nasty bug where for example 1/4 = 0 as the compiler will do integer division instead of floating point division. It hurts my eyes to see those integers
Yes Visual Studio has amazing debugging capabilities. Compared to debugging Excel you should find it easy. So the simplest thing is to just run the program (KMotionCNC) and debug it by stepping through the math. Note you can't run Libraries themselves. Instead you must run a Program that uses the Libraries.In the past I have had syntax errors in my math . Do you know if there is a way to simulate X/Y values and step through the math to see if the values are what I would expect them to be?
There is one complication. The TransformCADtoActuators() function is being called continuously with changing values as it is used to numerically reverse determine the CAD position from the Motor positions (sort of like trial and error). This saves you from having to come up with the math for determining the CAD position from the motor angles. So here is what I would do.
- Build KMotionCNC in Visual Studio in Debug configuration (Build Solution)
- Set KMotionCNC as Startup Project (right-click on project if not already)
- Debug | Start Debugging
- File Open your Kinematics2AxisRobot.cpp
- Set a breakpoint on first executable line in TransformCADtoActuators() (many ways to do this - a click in the margin is easiest)
- The breakpoint should be hit immediately, the program halts, and a yellow arrow is shown over the red breakpoint dot)
- hovering over variables should show the value
- select variables and right-click | add watch to display in a watch window.
- add variables x and y to a watch window so they can be altered
- using the watch window change the x y values to something you know the answer to like in your previous posts
- single step through the code checking the math as you go
- note you can go back to a previous line right-clicking | set next statement
Yes but not sure why the hot key is F7 for you. It is something else for me (ctrl - shift - B). Maybe you selected something different than me when installing Visual Studio. It simplest to just use the menus anyway.I have some help over the weekend figuring out how to rebuild the libraries. Though it looks like it is as simple as pressing F7?
The actuator variables Acts[] are in raw steps. So you might use the "Cnts/inch" as steps per degree. So then if you compute r0 in degrees then multiply by that the result should work. Step per degree would also depend on microstepping. So assuming 16X microstepping then steps/degree might be:So with the non-linear motion. How will the trajectory planner work? There are no linear parameters for Cnts/inch, velocity, and Accel. I will be using 10:1 gearbox reductions for the drives with 1.8 degree steppers. Not sure how that part will work.
16 / 1.8 x 10
YesI am also assuming that the other axis will remain linear? If I want to add a rotary A,B,or C, or linear Z,U,or V I will just set it up as I normally would?
Hang in there you are making progress
Regards,
Tom Kerekes
Dynomotion, Inc.
Tom Kerekes
Dynomotion, Inc.
- TomKerekes
- Posts: 2676
- Joined: Mon Dec 04, 2017 1:49 am
Re: Spray Robot
One more thing that might be confusing is that to fix a bug you must:
- Stop debugging KMotionCNC
- make the change to the kinematics file and save it
- return to the BuildAllLibs solution
- Build the Solution
- Start debugging KMotionCNC again
Regards,
Tom Kerekes
Dynomotion, Inc.
Tom Kerekes
Dynomotion, Inc.
-
- Posts: 60
- Joined: Fri Apr 27, 2018 10:43 pm
Re: Spray Robot
Thanks Tom! I made the changes and am trying to start debugging. I have been working in the "BuildAllLibs" solution. Where is the solution to rebuild KMotionCNC? I couldnt find it, and have been trying to "Attach to process" in the debug window instead which hasnt worked.
- TomKerekes
- Posts: 2676
- Joined: Mon Dec 04, 2017 1:49 am
Re: Spray Robot
\PC VC Examples\BuildExamples.sln as described here.
Regards,
Tom Kerekes
Dynomotion, Inc.
Tom Kerekes
Dynomotion, Inc.
-
- Posts: 60
- Joined: Fri Apr 27, 2018 10:43 pm
Re: Spray Robot
Alright! Long day, but finally got it debugged and my r0 and r1 values are matching excel! I'm pretty excited to build the machine and test things out.
So in wrapping things up, do I copy everything out of the KMotion debug folder, and paste it into the "release" folder? Now whenever I open KMotionCNC it will open my newly compiled application?
In my C program, when I define the coordinate system, Acts[0] will be connected to ch0, and Acts[1] to ch1, so just wire it accordingly? I suppose the X, and Y values for "DefineCoordSystem(0,1,3,2);" are not really relevant anymore?
If I need to update the linkage dimensions, I will need to recompile both the libraries? I couldnt pass them in with the Kinematics.txt file because they are already compiled into the library I would assume?
Thanks again for all of the help! Tom, you really stepped me through this. Really great support!
Scott
So in wrapping things up, do I copy everything out of the KMotion debug folder, and paste it into the "release" folder? Now whenever I open KMotionCNC it will open my newly compiled application?
In my C program, when I define the coordinate system, Acts[0] will be connected to ch0, and Acts[1] to ch1, so just wire it accordingly? I suppose the X, and Y values for "DefineCoordSystem(0,1,3,2);" are not really relevant anymore?
If I need to update the linkage dimensions, I will need to recompile both the libraries? I couldnt pass them in with the Kinematics.txt file because they are already compiled into the library I would assume?
Thanks again for all of the help! Tom, you really stepped me through this. Really great support!
Scott
- Attachments
-
- CoordMotion.cpp
- (87.64 KiB) Downloaded 290 times
-
- StdAfx.h
- (2.26 KiB) Downloaded 284 times
-
- Kinematics2AxisRobot.h
- (982 Bytes) Downloaded 290 times
-
- Kinematics2AxisRobot.cpp
- (2.74 KiB) Downloaded 275 times
- TomKerekes
- Posts: 2676
- Joined: Mon Dec 04, 2017 1:49 am
Re: Spray Robot
Hi Scott,
No, all you should need to do is switch the BuildAllLibs solution's configuration to Release mode and then Build All. This will compile the GCodeInterpreter.dll (which includes your code) in Release mode into the Release directory which has compiler options to optimize the code to be smaller and run faster. KMotionCNC shouldn't need to be re-built because there weren't any changes. That's the idea behind dynamically linked libraries (DLLs) changes made internally to them should be fully encapsulated.So in wrapping things up, do I copy everything out of the KMotion debug folder, and paste it into the "release" folder? Now whenever I open KMotionCNC it will open my newly compiled application?
No the DefineCoordSystem is still used to map the actuators to actual KFLOP Axis Channels. For example in your case with only xy that compute Acts[0] and Acts[1] motor positions if KFLOP was configured to have channels 3 and 4 control the 2 motors you would DefineCoordSystem(3,4,-1,-1)In my C program, when I define the coordinate system, Acts[0] will be connected to ch0, and Acts[1] to ch1, so just wire it accordingly? I suppose the X, and Y values for "DefineCoordSystem(0,1,3,2);" are not really relevant anymore?
That is correct. You could change the code to read in the values from Kinematics.txt instead of setting to hard-coded values. That was the main reason I asked you to move the setting of the variables to the constructor.If I need to update the linkage dimensions, I will need to recompile both the libraries? I couldnt pass them in with the Kinematics.txt file because they are already compiled into the library I would assume?
Thanks for your patience.Thanks again for all of the help! Tom, you really stepped me through this. Really great support!
Regards,
Tom Kerekes
Dynomotion, Inc.
Tom Kerekes
Dynomotion, Inc.
-
- Posts: 60
- Joined: Fri Apr 27, 2018 10:43 pm
Re: Spray Robot
Well, everything looks good.. I will post some video in a few weeks once the build is running. Thanks again Tom!
-
- Posts: 60
- Joined: Fri Apr 27, 2018 10:43 pm
Re: Spray Robot
Tom,
All the hardware is here, and I have been building this robot but am having some problems. Here is what I have done so far
1. Made an INIT program and calibrated each servo motor
2. Made a homing program - homes to a hard stop, and then moves motor 1 to 0 degrees, and Motor 2 to 90 degrees
This position is equivalent to X=8 and Y=4
3. Tested KMotionCNC in Debug mode - my math all matches Excel all works
4. Recompiled all libraries in Release mode
5. Set Cnts/IN for X and Y Axis in the trajectory planner
Now for the problems:
When I start KMotion CNC the X and Y positions immediately display "-nan(ind)". I noticed while debugging that if I put Zero on for my x or y values I would get the same error in visual studio. So I think that KMotionCNC is sending a fixture offset position that is impossible for the geometry to work. I tried all of my fixture offsets, but cant get anything to work.
Maybe there is something wrong with my homing program? I really dont know what else I could be doing wrong. Would you mind taking a quick look at my homing program? My intent is when M1=0 and M2= 90 that X=8 and Y=4. I think if I fed those numbers correctly the math would work out.
Does that sound right?
Thanks!
Scott
All the hardware is here, and I have been building this robot but am having some problems. Here is what I have done so far
1. Made an INIT program and calibrated each servo motor
2. Made a homing program - homes to a hard stop, and then moves motor 1 to 0 degrees, and Motor 2 to 90 degrees
This position is equivalent to X=8 and Y=4
3. Tested KMotionCNC in Debug mode - my math all matches Excel all works
4. Recompiled all libraries in Release mode
5. Set Cnts/IN for X and Y Axis in the trajectory planner
Now for the problems:
When I start KMotion CNC the X and Y positions immediately display "-nan(ind)". I noticed while debugging that if I put Zero on for my x or y values I would get the same error in visual studio. So I think that KMotionCNC is sending a fixture offset position that is impossible for the geometry to work. I tried all of my fixture offsets, but cant get anything to work.
Maybe there is something wrong with my homing program? I really dont know what else I could be doing wrong. Would you mind taking a quick look at my homing program? My intent is when M1=0 and M2= 90 that X=8 and Y=4. I think if I fed those numbers correctly the math would work out.
Does that sound right?
Thanks!
Scott
- Attachments
-
- Spray Robot INIT.c
- (3.81 KiB) Downloaded 288 times
-
- Spray Robot Home.c
- (2.06 KiB) Downloaded 293 times
-
- Posts: 60
- Joined: Fri Apr 27, 2018 10:43 pm