CoreXY Kinematics

Moderators: TomKerekes, dynomotion

Post Reply
tarober
Posts: 6
Joined: Mon Jan 27, 2020 4:25 pm

CoreXY Kinematics

Post by tarober » Wed Mar 03, 2021 9:27 pm

I am building a 3D printer using the CoreXY movement scheme. I used the Kinematics3Rod file as a template to write a new kinematics file, but when I use these kinematics it does not behave as I expect it to. When I jog any axis, I get movement in all axes. Can you tell me what I am doing wrong? I suspect it is something simple, but I am just starting to learn C++ and am a bit lost.

Also, I looked through the GeppettoExtrude file and didn't see anything that was specific to extrusion. I have also read elsewhere that you used a post-processor to turn E words into U words and just treated the extruder as a U axis. Is this correct?

I intend to use linear scales on each of the X and Y axes. Since these do not translate directly into actuator counts, would it work if I set up two independant channels with just encoder inputs (no output) similar to the CorrectEncoders C program?

Any help would be greatly appreciated!

Sincerely,
Travis

CoreXY motion shceme: http://corexy (dot) com/ (It won't let me post a link)

KinematicsCoreXY.cpp:

Code: Select all

// KinematicsCoreXY.cpp: implementation of the CKinematicsCoreXY class.
//
//////////////////////////////////////////////////////////////////////

#include "stdafx.h"
#include "KinematicsCoreXY.h"

#define sqr(x) ((x)*(x))


//////////////////////////////////////////////////////////////////////
// Construction/Destruction
//////////////////////////////////////////////////////////////////////

CKinematicsCoreXY::CKinematicsCoreXY()
{
	
}

CKinematicsCoreXY::~CKinematicsCoreXY()
{

}

int CKinematicsCoreXY::TransformCADtoActuators(double x, double y, double z, double a, double b, double c, double *Acts, bool NoGeo)
{
	// find motor counts of each actuator

	GeoCorrect(x,y,z,&x,&y,&z);

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

	Acts[3] = a*m_MotionParams.CountsPerInchA;
	Acts[4] = b*m_MotionParams.CountsPerInchB;
	Acts[5] = c*m_MotionParams.CountsPerInchC;

	return 0;
}


// perform Inversion to go the other way

int CKinematicsCoreXY::TransformActuatorstoCAD(double *Acts, double *xr, double *yr, double *zr, double *ar, double *br, double *cr, bool NoGeo)
{
	return InvertTransformCADtoActuators(Acts, xr, yr, zr, ar, br, cr);
}

and KinematicsCoreXY.h

Code: Select all

// KinematicsCoreXY.h: interface for the CKinematicsCoreXY class.
//
//////////////////////////////////////////////////////////////////////


#if !defined(AFX_KINEMATICSCOREXY_H__876A0A72_6EC3_48D0_9040_60AE3DA2F3C7__INCLUDED_)
#define AFX_KINEMATICSCOREXY_H__876A0A72_6EC3_48D0_9040_60AE3DA2F3C7__INCLUDED_

#if _MSC_VER > 1000
#pragma once
#endif // _MSC_VER > 1000

#include "stdafx.h"

class CKinematicsCoreXY : public CKinematics  
{
public:
	CKinematicsCoreXY();
	virtual ~CKinematicsCoreXY();
	virtual int TransformCADtoActuators(double x, double y, double z, double a, double b, double c, double *Acts, bool NoGeo = false);
	virtual int TransformActuatorstoCAD(double *Acts, double *x, double *y, double *z, double *a, double *b, double *c, bool NoGeo = false);
};

#endif // !defined(AFX_KINEMATICSCOREXY_H__876A0A72_6EC3_48D0_9040_60AE3DA2F3C7__INCLUDED_)

User avatar
TomKerekes
Posts: 2529
Joined: Mon Dec 04, 2017 1:49 am

Re: CoreXY Kinematics

Post by TomKerekes » Wed Mar 03, 2021 10:37 pm

Hi Travis,

That looks reasonable. Do you know if your code is being used? Did you set a breakpoint in it?

Does Z work properly? If not another Kinematics class is likely selected. Have you changed Kinematics.txt?

Did you read the article in the wiki?

Yes I would think the CorrectEncoders.c approach would work.
Regards,

Tom Kerekes
Dynomotion, Inc.

tarober
Posts: 6
Joined: Mon Jan 27, 2020 4:25 pm

Re: CoreXY Kinematics

Post by tarober » Thu Mar 04, 2021 4:47 pm

Hello Tom,

Actually, it turned out to be a silly mistake. I didn't realize that you had to take the newly compiled .dll files from the Debug folder and copy them into the Release folder. After I did that it works like it should for the most part. When I stop hitting the jog button there is a short period where the actuators reverse direction almost like they are trying to correct for overshoot even though I do not have any encoder feedback at the moment. Also, when I first hit the jog button the X and Y axes do not accelerate smoothly and seem to oscillate with increasing speed until it comes to a steady state velocity. I will try to get a video of it this afternoon. Thanks for the help!

Post Reply