Re: [Emc-users] Serial kinematics
2011/1/5 Jack Coats j...@coats.org: You might look at the kinematics for a SCADA arm for some hints, it is a very rudimentary version of what you are doing. Nope, scarakins uses very simple calculations with sin and cos functions. It seems to me that from mathematics point of view scarakins and genserkins are very far away from each other. Genserkins uses _much_ more advanced mathematics that I do not yet understand with jacobian functions, velocity and a lot of other matrices. The torch of MIG welder will be attached at the end of the arm with some offset between the tip of the torch and the point, where it is attached to the arm. So my problem is understanding, how to change joint_0 from angular to linear and thus change the way, how the compensating moves for X axis (along which the linear joint will move) are calculated. I would _really_ appreciate, if anyone of developers or users with more experience in kinematics could share their advice! Viesturs -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
On 5 January 2011 08:27, Viesturs Lācis viesturs.la...@gmail.com wrote: I would _really_ appreciate, if anyone of developers or users with more experience in kinematics could share their advice! Adding a single translational joint that is parallel to an axis is very simple. Generalising Serialkins to allow prismatic joints in any orientation is significantly less so. Currently I think that serialkins uses Denavit Hartenberg parameters to solve the kinematics. The d, r and alpha values of each joint are fixed parameters, and the theta value is a pin corresponding to joint position. Generalising to prismatic joints might be as simple as making the d parameter into a pin, and then choosing whether to link the theta or d pin to the joint position in HAL. However, I suspect it might be a lot more difficult than this. For your purposes you can probably just add the joint position to the X value, and subtract in the inverse kins. -- atp Torque wrenches are for the obedience of fools and the guidance of wise men -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
Hi Viesturs, I wanted to reply to your private email too (same matter) but didn't get around to it. Let me try to address your questions one at a time: snipped and rearranged a bit I have another 2 minor questions: 1) I need to control rotary head (because long, round parts will need to be welded along perimeter). Looking at genserkins.c I suspect that A, B and C letters are hardcoded for the arm. It does not matter, what letter, the question is, where exactly in KinematicsForward and KinematicsInverse sections should I paste these lines: pos-u = joint[6] joints[6] = pos-u The kinematics in emc2 don't care if it's the arm or the workpiece that move. they both move relative to each other, so you have to take care of both in your kinematic file. If only the workpiece rotates then surely it's a lot simpler and your assumption above is correct (pos-u = joint[6]...) 2) what do I do about these lines? It is from genserkins.h: 67 #define DEFAULT_A6 0 68 #define DEFAULT_ALPHA6 -PI_2 69 #define DEFAULT_D6 0; The arm is designed to have 5 joints, the 6th joint should a rotary head, so I would like to exclude it from all the calculations of the arm. well, the problem with genserkins is that it's a generic serial kinematic solver. That means it's supposed to work for any/all cases of serial linked joints (rotary and linear). Currently (addressing you next point) the joint type is fixed to rotary, but that doesn't mean the calculations aren't working for linear joints. Just that currently there is no way of telling genserkins that you first joint is linear. To fix this, you would have to add some HAL pins (if you want to make it configurable, like it should be) to specify each joint type (linear or angular), then init the joint accordingly : at line 81 [1] the current assumption is rotary: genser-links[t].quantity = GO_QUANTITY_ANGLE; that needs to be changed to GO_QUANTITY_LENGTH (defined in src/libnml/posemath/gotypes.h) [2] Once you fixed that, you can select for each joint if it's linear or rotary. You would still need to define 6 joints for the genserkins part, because the solver won't work otherwise (so try to define an extra joint, which you won't use), and the rotary table you can add as joint 7. Hope this gets you started, Alex [1] - http://git.linuxcnc.org/gitweb?p=emc2.git;a=blob;f=src/emc/kinematics/genserkins.c;h=1331cb3204bb8f47545305132fb4657498e61c79;hb=HEAD#l81 [2] - http://git.linuxcnc.org/gitweb?p=emc2.git;a=blob;f=src/libnml/posemath/gotypes.h;h=c94df69e2d9a44e7de3375fd8883a6b5cb4e14fd;hb=HEAD#l67 Hello, folks! Genserkins.c says that Currently the type of the joints is hardcoded to ANGULAR. I would appreciate, if anyone could share some advice, how the linear joint could be implemented. My need is to move small robot arm along 3000 mm long linear slide in implementation of robotic MIG welder. My initial design contains 5 joints: 1) linear joint, along which the whole arm will move: 2) shoulder up/down; 3) elbow up/down; 4) wrist rotate; 5) wrist up/down. They are supposed to be serially linked in the exact order as I wrote them. So my main question is - how can linear joint be introduced here? I feel that hardcoding that only joint_0 (first joint in the series) is linear would satisfy vast majority of necessity to combine robotic arms and linear joints. Thank You in advance! Viesturs -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
2011/1/5 Alex Joni alex.j...@robcon.ro: The kinematics in emc2 don't care if it's the arm or the workpiece that move. they both move relative to each other, so you have to take care of both in your kinematic file. If only the workpiece rotates then surely it's a lot simpler and your assumption above is correct (pos-u = joint[6]...) Yes, that is correct, workpiece only needs to rotate. Thanks, that one would be sorted out... well, the problem with genserkins is that it's a generic serial kinematic solver. That means it's supposed to work for any/all cases of serial linked joints (rotary and linear). Currently (addressing you next point) the joint type is fixed to rotary, but that doesn't mean the calculations aren't working for linear joints. Just that currently there is no way of telling genserkins that you first joint is linear. To fix this, you would have to add some HAL pins (if you want to make it configurable, like it should be) to specify each joint type (linear or angular), then init the joint accordingly : at line 81 [1] the current assumption is rotary: genser-links[t].quantity = GO_QUANTITY_ANGLE; that needs to be changed to GO_QUANTITY_LENGTH (defined in src/libnml/posemath/gotypes.h) [2] Please correct me, if I am wrong, but if I will change this line: 81 genser-links[t].quantity = GO_QUANTITY_ANGLE; to this one: 81 genser-links[t].quantity = GO_QUANTITY_LENGTH; then it will change all the joints from angular to linear. Is that correct? I suspect that adding HAL pins, which determine type of joint - LINEAR or ANGULAR, should look like this: In HAL file: # Setting values for joint type - linear or angular. # These values are used by genserkins kinematics module # It would be ideal, if values of these pins could be set automagically, depending on INI file: # [AXIS_N] TYPE = LINEAR or ANGULAR # The values are assigned, based on this rule - for linear joints it is 0 (false), for angular joints it is 1 (true) setp genserkins.TYPE1 0 setp genserkins.TYPE2 1 setp genserkins.TYPE3 1 setp genserkins.TYPE4 1 setp genserkins.TYPE5 1 setp genserkins.TYPE6 1 In genserkins.c file. My idea is to call that pin type. I copied my suggested code together with some previous lines of code, so that it is easier to understand, where I propose to place it: struct haldata { 47 hal_float_t *a[GENSER_MAX_JOINTS]; 48 hal_float_t *alpha[GENSER_MAX_JOINTS]; 49 hal_float_t *d[GENSER_MAX_JOINTS]; 50 hal_float_t *type[GENSER_MAX_JOINTS]; 59 #define D(i) (*(haldata-d[i])) 60 #define TYPE(i) (*(haldata-d[i])) 595 if ((res = 596 hal_pin_float_newf(HAL_IO, (haldata-d[i]), comp_id, 597 genserkins.D-%d, i)) 0) 598 goto error; 599 if ((res = hal_pin_float_newf(HAL_IO, (haldata-type[i]), comp_id, genserkins.TYPE-%d, i)) 0) goto error; 618 D(0) = DEFAULT_D1; 619 D(1) = DEFAULT_D2; 620 D(2) = DEFAULT_D3; 621 D(3) = DEFAULT_D4; 622 D(4) = DEFAULT_D5; 623 D(5) = DEFAULT_D6; 624 TYPE(0) = DEFAULT_TYPE1; TYPE(1) = DEFAULT_TYPE2; TYPE(2) = DEFAULT_TYPE3; TYPE(3) = DEFAULT_TYPE4; TYPE(4) = DEFAULT_TYPE5; TYPE(5) = DEFAULT_TYPE6; 680 for (i = 0; i 6; i++) { 681 haldata-a[i] = malloc(sizeof(double)); 682 haldata-alpha[i] = malloc(sizeof(double)); 683 haldata-d[i] = malloc(sizeof(double)); 684 haldata-type[i] = malloc(sizeof(double)); 697 D(0) = DEFAULT_D1; 698 D(1) = DEFAULT_D2; 699 D(2) = DEFAULT_D3; 700 D(3) = DEFAULT_D4; 701 D(4) = DEFAULT_D5; 702 D(5) = DEFAULT_D6; 703 TYPE(0) = DEFAULT_TYPE1; TYPE(1) = DEFAULT_TYPE2; TYPE(2) = DEFAULT_TYPE3; TYPE(3) = DEFAULT_TYPE4; TYPE(4) = DEFAULT_TYPE5; TYPE(5) = DEFAULT_TYPE6; In genserkins.h file. I added the default TYPE values to be 1. It looks like this: 46 /* default DH parameters, these should be ok for a puma - at least according to Craig */ 47 #define DEFAULT_A1 0 #define DEFAULT_ALPHA1 0 #define DEFAULT_D1 0 #define DEFAULT_TYPE1 1 #define DEFAULT_A2 0 #define DEFAULT_ALPHA2 -PI_2 #define DEFAULT_D2 0 #define DEFAULT_TYPE2 1 #define DEFAULT_A3 300 #define DEFAULT_ALPHA3 0 #define DEFAULT_D3 70 #define DEFAULT_TYPE3 1 #define DEFAULT_A4 50 #define DEFAULT_ALPHA4 -PI_2 #define DEFAULT_D4 400 #define DEFAULT_TYPE4 1 #define DEFAULT_A5 0 #define DEFAULT_ALPHA5 PI_2 #define DEFAULT_D5 0 #define DEFAULT_TYPE5 1 #define DEFAULT_A6 0 #define DEFAULT_ALPHA6 -PI_2 #define DEFAULT_D6 0 #define DEFAULT_TYPE6 1 So now the remaining part is to create code that would select either GO_QUANTITY_ANGLE or GO_QUANTITY_LENGTH, based on type value - if it is 0, then
Re: [Emc-users] homing problem
On Tue, 4 Jan 2011, Don Stanley wrote: Hi Richard; I am not familiar with stepconfig therefore not understanding what is happening. If you are attempting to home and stay at the + end if travel, the HOME=0.0 will override a HOME_OFFSET= setting. If that is what is happening remove the HOME=0.0 and it will finish the home where you are programing it to. Hope this helps Don I changed HOME_SEARCH_VEL = 1.50 to HOME_SEARCH_VEL = -1.50 and problem solved Insufficient active brain cells are my only excuse On Mon, Jan 3, 2011 at 8:03 PM, kqt4a...@comcast.net wrote: I used stepconf to setup my Fireball V90 The only hitch was to invert the x direction Now I added two limit switches, one at each end of the x axis I configured pin 10 as x axis home and limit The only problem is it homes in the wrong direction If I once again use stepconf and uncheck the box to invert the x direction it homes properly [AXIS_0] TYPE = LINEAR HOME = 0.0 MAX_VELOCITY = 3.3 MAX_ACCELERATION = 10.0 STEPGEN_MAXACCEL = 12.5 SCALE = 8000.0 FERROR = 0.05 MIN_FERROR = 0.01 MIN_LIMIT = -0.01 MAX_LIMIT = 18.0 HOME_OFFSET = 0.00 HOME_SEARCH_VEL = 1.50 HOME_LATCH_VEL = 0.062500 HOME_IGNORE_LIMITS = YES Thanks for any suggestions Richard -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users -- -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
2011/1/5 andy pugh bodge...@gmail.com: Adding a single translational joint that is parallel to an axis is very simple. Generalising Serialkins to allow prismatic joints in any orientation is significantly less so. Yes, generalising something makes everything pretty difficult, because it has to be able to deal _all_ the potential cases, not just the one case of particular machine. That is why I remember one pretty nice phrase: One can program such an application that even idiot can use it, but then only idiot will want to use it. Currently I think that serialkins uses Denavit Hartenberg parameters to solve the kinematics. The d, r and alpha values of each joint are fixed parameters, and the theta value is a pin corresponding to joint position. Yes, that is how I understand it, too. With one exception. In genserkins.c: 79 genser-links[t].u.dh.theta = 0; Please correct me here, but it looks to me that theta is 0 and this is the only line in whole file, where theta is mentioned. So I have to admit that I do not yet understand, how exactly it all works. I feel like theta _should_ be the actual joint position, but I have no idea, where to find out, if it is true or not. Generalising to prismatic joints might be as simple as making the d parameter into a pin, and then choosing whether to link the theta or d pin to the joint position in HAL. However, I suspect it might be a lot more difficult than this. I have no idea, if it can work this way. If I understand correctly, that means changing D value dynamically as robot arm moves. For your purposes you can probably just add the joint position to the X value, and subtract in the inverse kins. Yes, I have been thinking about it. But there is one small problem: I am used to play with kinematics, where pos-tran.x is somehow related to joint.0 and vice versa. For example, from the 5 axis module I wrote by myself: pos-tran.x = joints[0] - (200 * sin(joints[5])); It compensates for the head offset, when rotary joint.5 is moved. Now in genserkins I do not see this type of equations. I do not see joints[0] to be mentioned at all. The same for joints[1] and others. It is just damn too difficult for me to understand the whole thing yet. Take a look at genserkins.c from line 100 to line 300 :)) http://git.linuxcnc.org/gitweb?p=emc2.git;a=blob;f=src/emc/kinematics/genserkins.c;h=87d0eb9008a8aedef54110b776d2ed172a73ba1f;hb=v2.4_branch#l100 I think that the simpliest thing that would work, would be something like this: 1) do not give X commands to robot-arm-maths, so that it moves the arm (calculates joint positions) just for Y, Z, A, B and C commands; 2) calculate the drift - how much the tip of torch (or just the 6th dummy joint) has moved along X as a result of all the moves along Y, Z, A, B and C; 3) write something like this: world-tran.x = joints[0] + drift joints[0] = world-tran.x - drift My initial idea was to do it this way: 1) in the code, use U instead of X 2) joints[0] = world-u - drift world-u = joints[0] + drift The problem is that I have no idea, how to acquire the value of drift, because in the kinematics module it uses rotary joint to move along X axis and, since there are no straight equations of joints[n] vs world-tran.n, I do not see, how to acquire the value of joints[0] and thus I do not see a way to get the value of drift in linear units. Viesturs -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
Please correct me, if I am wrong, but if I will change this line: 81 genser-links[t].quantity = GO_QUANTITY_ANGLE; to this one: 81 genser-links[t].quantity = GO_QUANTITY_LENGTH; then it will change all the joints from angular to linear. Is that correct? Yes, that is correct snip the adding HAL pins looks ok, but one would need to test/debug it to say that it's 100% ok. So now the remaining part is to create code that would select either GO_QUANTITY_ANGLE or GO_QUANTITY_LENGTH, based on type value - if it is 0, then GO_QUANTITY_LENGTH, if it is 1, then GO_QUANTITY_ANGLE. That should be fairly simple: change line 81 to: genser-links[t].quantity = TYPE(t); I suspect that linear joint does not need a, d, alpha and theta values as well. Is that correct? hmm.. good question I'm afraid I don't have a useful answer. you would have to check the code (around genserkins.c and gomath) to see how those are treated for linear joints. snip Is it correct that in this case I will need to change GENSER_MAX_JOINTS to 7 in genserkins,h file and probably in few more places in genserkins.c? yes. the proper fix would be to use the constant in genserkins.c too By the way, genserkins.h says: 38 /*! 39 The maximum number of joints supported by the general serial 40 kinematics. Make this at least 6; a device can have fewer than these. 41 */ Could You, please, explain, what is meant by device can have fewer than these? That additional dummy joints will need to be defined so that in any case total number of joints reaches 6? Yes, exactly that. The calculations only work starting from 6 joints. If your machine has fewer, you need to set the others as dummy. Regards, Alex -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
On 5 January 2011 14:10, Viesturs Lācis viesturs.la...@gmail.com wrote: Now in genserkins I do not see this type of equations. I do not see joints[0] to be mentioned at all. The same for joints[1] and others. line 510. A loop cycles through joints[0] to joints[genser-link_num] -- atp Torque wrenches are for the obedience of fools and the guidance of wise men -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
2011/1/5 andy pugh bodge...@gmail.com: On 5 January 2011 14:10, Viesturs Lācis viesturs.la...@gmail.com wrote: Now in genserkins I do not see this type of equations. I do not see joints[0] to be mentioned at all. The same for joints[1] and others. line 510. A loop cycles through joints[0] to joints[genser-link_num] Ok, thanks! Unfortunately it still does not help me understanding, how can I intervene in calculation of positon for a particular joint. Viesturs -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] Serial kinematics
Thanks, Alex! I start feeling like I do understand something :) 2011/1/5 Alex Joni alex.j...@robcon.ro: the adding HAL pins looks ok, but one would need to test/debug it to say that it's 100% ok. How are the simulated machines created? I suspect that there was simulation model of Puma arm, so that could be tweaked - joint.0 created to be linear instead of rotary. I would like to test it. Or I can send both genserkins.c and genserkins.h, if anyone else is interested in them. That should be fairly simple: change line 81 to: genser-links[t].quantity = TYPE(t); Please correct me here, if I am misunderstanding: Since TYPE(t) values would be 0 or 1, I think that this would just set genser-links[t].quantity to be 0 or 1 instead of GO_QUANTITY_LENGTH or GO_QUANTITY_ANGLE. Shouldn't it be something like this? Please, correct the syntax, I think that it is not correct. 73 /* init them all and make them revolute joints */ 74 /* FIXME: should allow LINEAR joints based on HAL param too */ 75 for (t = 0; t GENSER_MAX_JOINTS; t++) { 76 if (TYPE(t) = 0) 77 genser-links[t].u.dh.a = 0; 78 genser-links[t].u.dh.alpha = 0; 79 genser-links[t].u.dh.d = 0; 80 genser-links[t].u.dh.theta = 0; 81 genser-links[t].type = GO_LINK_DH; I did not find gomath.h file, to check, if this one is o.k. 82 genser-links[t].quantity = GO_QUANTITY_LENGTH; 83 if (TYPE(t) = 1) 84 genser-links[t].u.dh.a = A(t); 85 genser-links[t].u.dh.alpha = ALPHA(t); 86 genser-links[t].u.dh.d = D(t); 87 genser-links[t].u.dh.theta = 0; 88 genser-links[t].type = GO_LINK_DH; 89 genser-links[t].quantity = GO_QUANTITY_ANGLE; 90 } I suspect that linear joint does not need a, d, alpha and theta values as well. Is that correct? hmm.. good question I'm afraid I don't have a useful answer. you would have to check the code (around genserkins.c and gomath) to see how those are treated for linear joints. Can anyone tell me, where is gomath.h file located? I was browsing through git pretty long time, but did not find it there. Viesturs -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
Re: [Emc-users] homing problem
On Wed, Jan 5, 2011 at 9:05 AM, kqt4a...@comcast.net wrote: On Tue, 4 Jan 2011, Don Stanley wrote: Hi Richard; I am not familiar with stepconfig therefore not understanding what is happening. If you are attempting to home and stay at the + end if travel, the HOME=0.0 will override a HOME_OFFSET= setting. If that is what is happening remove the HOME=0.0 and it will finish the home where you are programing it to. Hope this helps Don I changed HOME_SEARCH_VEL = 1.50 to HOME_SEARCH_VEL = -1.50 and problem solved Insufficient active brain cells are my only excuse Welcome to the club. Out enrollment is growing every day. On Mon, Jan 3, 2011 at 8:03 PM, kqt4a...@comcast.net wrote: I used stepconf to setup my Fireball V90 The only hitch was to invert the x direction Now I added two limit switches, one at each end of the x axis I configured pin 10 as x axis home and limit The only problem is it homes in the wrong direction If I once again use stepconf and uncheck the box to invert the x direction it homes properly [AXIS_0] TYPE = LINEAR HOME = 0.0 MAX_VELOCITY = 3.3 MAX_ACCELERATION = 10.0 STEPGEN_MAXACCEL = 12.5 SCALE = 8000.0 FERROR = 0.05 MIN_FERROR = 0.01 MIN_LIMIT = -0.01 MAX_LIMIT = 18.0 HOME_OFFSET = 0.00 HOME_SEARCH_VEL = 1.50 HOME_LATCH_VEL = 0.062500 HOME_IGNORE_LIMITS = YES Thanks for any suggestions Richard -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users -- -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users
[Emc-users] config won't load after power failure (from Sherline list)
Hi guys A guy on the Sherline list had a power outage will using his mill after, when trying to load the config it errors. Strangely he says the lathe config loads. hmm then again that uses a different GUI I think. (OEM Sherline) He sent an ugly error message the two things I see of interest is: Print file information:RUN_IN_PLACE=noEMC2_DIR=EMC2_BIN_DIR=/usr/binEMC2_TCL_DIR=/usr/share/emc/tclEMC2_SCRIPT_DIR=EMC2_RTLIB_DIR=/usr/realtime-2.6.24-16-rtai/modules/emc2EMC2_CONFIG_DIR=EMC2_LANG_DIR=/usr/share/emc/tcl/msgsINIVAR=/usr/bin/inivarHALCMD=/usr/bin/halcmdEMC2_EMCSH=/usr/bin/emcshEMC2_IOSH=/usr/bin/ioshEMC2 - 2.2.5Machine configuration directory is '/home/sherline/emc2/configs/Sherline'Machine configuration file is 'mill_mm_mini.ini'INIFILE=/home/sherline/emc2/configs/Sherline/mill_mm_mini.iniPARAMETER_FILE=EMCMOT=EMCIO=TASK=HALUI=DISPLAY=NML_FILE=Starting EMC2...Starting EMC2 server program: emcsvrLoading Real Time OS, RTAPI, and HAL_LIB modulesStarting EMC2 IO program: Starting EMC2 TASK program: Starting EMC2 DISPLAY program: Shutting down and cleaning up EMC2...Killing task emcsvr, PID=5992Removing HAL_LIB, RTAPI, and Real Time OS modulesRemoving NML shared memory segmentsCleanup done and at the bottom: Debug file information:Can not find -sec RS274NGC -var PARAMETER_FILE -num 1 Can not find -sec EMCMOT -var EMCMOT -num 1 Can not find -sec EMCIO -var EMCIO -num 1 Can not find -sec TASK -var TASK -num 1 Can not find -sec DISPLAY -var DISPLAY -num 1 Can not find -sec EMC -var NML_FILE -num 1 Can not find -sec DISPLAY -var INTRO_GRAPHIC -num 1 Can not find -sec DISPLAY -var INTRO_TIME -num 1 commandline:0: execv(/usr/bin/) failedcommandline:0: /usr/bin/ exited without becoming ready/usr/bin/emc: line 572: /usr/bin/: is a directory/usr/bin/emc: line 629: /usr/bin/: is a directory5992 PID TTY STAT TIME COMMANDStopping realtime threadsUnloading hal components/usr/bin/emc: line 356: $NMLFILE: ambiguous redirect I know its not much to go on but does anyone recognize the problem? surely a file was corrupted but is strange the lathe config still works Cheers Chris M -- Learn how Oracle Real Application Clusters (RAC) One Node allows customers to consolidate database storage, standardize their database environment, and, should the need arise, upgrade to a full multi-node Oracle RAC database without downtime or disruption http://p.sf.net/sfu/oracle-sfdevnl ___ Emc-users mailing list Emc-users@lists.sourceforge.net https://lists.sourceforge.net/lists/listinfo/emc-users