#include "kinematics.h"		
#include "hal.h"
#include "rtapi_math.h"

static PmCartesian old; 
typedef struct { hal_bit_t *pin_auto ;} tangentkins_hal_t;
tangentkins_hal_t *data;

int kinematicsForward(const double *joints,
                      EmcPose * pos,
                      const KINEMATICS_FORWARD_FLAGS * fflags,
                      KINEMATICS_INVERSE_FLAGS * iflags)
{
    pos->tran.x = joints[0];
    pos->tran.y = joints[1];
    pos->tran.z = joints[2];
    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)
{
    
    static double dx = 0, dy = 0, A = 0;
    
    dy = pos->tran.y - old.y;
    dx = pos->tran.x - old.x;
    if (*data->pin_auto){
        if (dx != 0 || dy != 0) {
            A = atan2(dx, dy)*(180.0/3.141592);
        }
    }else{
        A=pos->a;
    }
    
    joints[0] = pos->tran.x;
    joints[1] = pos->tran.y;
    joints[2] = pos->tran.z;
    joints[3] = A;
    joints[4] = pos->b;
    joints[5] = pos->c;
    joints[6] = pos->u;
    joints[7] = pos->v;
    joints[8] = pos->w;
    
    
    old.x = pos->tran.x; // store previous value here to exclude kins-based movements
    old.y = pos->tran.y;
    
    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_BOTH;
}

#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("tangentkins");
    if(comp_id > 0) {
	data = hal_malloc(sizeof(tangentkins_hal_t));
 	if(hal_pin_bit_new("tangentkins.auto", HAL_IN, &(data->pin_auto), comp_id) < 0 ){
            rtapi_print("Failed to create pin in tangentkins");
 	    return -EINVAL;
        }
 	hal_ready(comp_id);
 	return 0;
    }
    return comp_id;
}

void rtapi_app_exit(void) { hal_exit(comp_id); }
