Created
October 17, 2020 17:02
-
-
Save andypugh/03b9ac265a1db50cb748d3449d3264dd to your computer and use it in GitHub Desktop.
Virtual B axis
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
HAL: | |
net B-pos joint.4.motor-pos-cmd joint.4.motor-pos-fb | |
net jogwheel joint.4.jog-counts | |
net jogwheel axis.b.jog-counts | |
net b-jog touchy.jog.wheel.b joint.4.jog-enable axis.4.jog-enable | |
net jog-speed axis.b.jog-scale | |
Kinematics (virtualbkins.c) | |
/******************************************************************** | |
* Description: manualbkins.c | |
* Kinematics for a mill with a manual swinging head | |
* | |
* Derived from a work by Fred Proctor & Will Shackleford | |
* | |
* Author: andypugh | |
* License: GPL Version 2 | |
* System: Linux | |
* | |
* Copyright (c) 2020 All rights reserved. | |
* | |
* Last change: | |
********************************************************************/ | |
#include "kinematics.h" /* these decls */ | |
#include "rtapi_math.h" | |
#include "hal.h" | |
int kinematicsForward(const double *joints, | |
EmcPose * pos, | |
const KINEMATICS_FORWARD_FLAGS * fflags, | |
KINEMATICS_INVERSE_FLAGS * iflags) | |
{ | |
double s = sin(pos->b * M_PI/180); | |
double c = cos(pos->b * M_PI/180); | |
double sc2 = s * s + c * c; | |
pos->tran.x = (joints[2] * s + joints[0] * c) / sc2; | |
pos->tran.y = joints[1]; | |
pos->tran.z = (joints[2] * c - joints[0] * s) / sc2; | |
pos->a = joints[3]; | |
pos->b = joints[4]; | |
pos->c = joints[5]; | |
pos->u = joints[6]; | |
pos->v = joints[7]; | |
pos->w = joints[8]; | |
return 0; | |
} | |
int kinematicsInverse(const EmcPose * pos, | |
double *joints, | |
const KINEMATICS_INVERSE_FLAGS * iflags, | |
KINEMATICS_FORWARD_FLAGS * fflags) | |
{ | |
double s = sin(pos->b * M_PI/180); | |
double c = cos(pos->b * M_PI/180); | |
joints[0] = pos->tran.x * c - pos->tran.z * s; | |
joints[1] = pos->tran.y; | |
joints[2] = pos->tran.z * c + pos->tran.x * s; | |
joints[3] = pos->a; | |
joints[4] = pos->b; | |
joints[5] = pos->c; | |
joints[6] = pos->u; | |
joints[7] = pos->v; | |
joints[8] = pos->w; | |
return 0; | |
} | |
/* implemented for these kinematics as giving joints preference */ | |
int kinematicsHome(EmcPose * world, | |
double *joint, | |
KINEMATICS_FORWARD_FLAGS * fflags, | |
KINEMATICS_INVERSE_FLAGS * iflags) | |
{ | |
*fflags = 0; | |
*iflags = 0; | |
return kinematicsForward(joint, world, fflags, iflags); | |
} | |
KINEMATICS_TYPE kinematicsType() | |
{ | |
return KINEMATICS_IDENTITY; | |
} | |
#include "rtapi.h" /* RTAPI realtime OS API */ | |
#include "rtapi_app.h" /* RTAPI realtime module decls */ | |
#include "hal.h" | |
EXPORT_SYMBOL(kinematicsType); | |
EXPORT_SYMBOL(kinematicsForward); | |
EXPORT_SYMBOL(kinematicsInverse); | |
MODULE_LICENSE("GPL"); | |
int comp_id; | |
int rtapi_app_main(void) { | |
comp_id = hal_init("manualbkins"); | |
if(comp_id < 0) return comp_id; | |
hal_ready(comp_id); | |
return 0; | |
} | |
void rtapi_app_exit(void) { hal_exit(comp_id); } | |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment