![]() |
|
Construction Equipment If it digs, pushes, hauls dirt "off road" post it here. |
![]() |
|
Thread Tools | Display Modes |
#101
|
|||
|
|||
![]()
I've had one issue with the operation, and that is that I need some way to stop the motors at the end of travel. I could have done this with limit switches like I did for my MAN truck build:
- http://www.scale4x4rc.org/forums/showthread.php?t=80393 An alternative is to use angle sensors in each joint, and I've selected this method for this build because it also allows for a host of other cool applications and features: - End stops - Stall detection - Recording of movement - Replay of movement - Full servo capability at the joint - Alternative control modes (e.g. for beginners), like absolute bucket movement forward/backward and up/down, not angle control - Automatic bucket leveling - Automatic grading - GPS assisted digging - GPS controlled digging - .. and probably more. So I've started to add some angle sensors to the arm. First the stick and the bucket. (This approach could also very well be used on hydraulic arms, btw.) I'm reading the sensor on the corresponding motor controller. That way, the control of the motor based on the angle sensor can be completely controlled on the controller without having to bother the main CPU. As I was already modifying the motor controller, I added some heat sinks for good measure, but those are most likely not required at all. Ebay link: - 18x18x13.5mm heat sink: http://www.ebay.com/itm/361352931009 ![]() To read the sensor, I'm using the unused analog inputs 4 and 5 on the Arduino. I've added longer pins to these positions so that I can attach wires on the front side. I did the same for GND and 5V. ![]() The angle sensor itself is just a 10k Ohm linear potetiometer. I'm using a thumb wheel version to get it as flat as possible. I bought these ones at SparkFun: - Thumbwheel potentiometer, 10k linear: https://www.sparkfun.com/products/retired/11173 ![]() The potentiometer attaches to the hub adapter using one very small self-tapping screw. ![]() ![]() The hub adapter has a D-shape that fits exactly onto the D-shape of the gear motor axle: ![]() ![]() I've printed a part that mocks up a stick mount that has two purposes: - Cover and hold the angle sensor - Be a base when running the control an power lines to the stick. ![]() ![]() The sensor connector has three pins, that connect to the Arduino cable from the first step: - Pin1: GND - Pin2: Sensor output (0-5V) - Pin3: 5V ![]() ![]() ![]() |
#102
|
||||
|
||||
![]()
Very cleaver.... you and this build amaze me ! Keep it up...
__________________
To view links or images in signatures your post count must be 10 or greater. You currently have 0 posts. |
#103
|
|||
|
|||
![]()
Thanks, Trucker Al!
I really like this forum. The positive atmosphere and the combined competence of everyone here fuel many of the builds, I think. Best regards, Stein :-) |
#104
|
|||
|
|||
![]()
Added angle sensor to the bucket.
The bucket angle sensor attaches in the same way as the stick angle sensor, but the cover is different. Its only purpose is to hold the sensor in place and protect it. Not my prettiest piece of work, but it'll get the job done. ![]() ![]() ![]() |
#105
|
||||
|
||||
![]()
that's cool dan!! you lost me with all the computer stuff but still a real cool build
|
#106
|
||||
|
||||
![]()
As I have written before your build is great , ton of info for us beginners, can I ask a couple of questions, what DP or MOD did you base your swing gears on, I am trying to cut a pair but cannot seem to come up with a workable combination,( do not have cnc) I am also very interested in 3D printer work, about how long does it take to produce your track pads and if I may ask what make of printer do you use? Thanks for any info you may have.
Terry |
#107
|
|||
|
|||
![]()
Excellent work, you are on a whole other level.
|
#108
|
|||
|
|||
![]()
Hi Crusher!
I used the Spur gear generator add-in in Fusion 360 to generate the gear, but there are also many online generators: - http://geargenerator.com/ - https://woodgears.ca/gear_cutting/template.html - http://hessmer.org/gears/InvoluteSpurGearBuilder.html For my main gear, these are the parameters: - Diametral pitch: 3.175 cm (1.25 inches) - Number of teeth: 44 - Pressure angle: 20 For the pinion gear it's the same parameters but just 7 teeth. Then I used the 50 rpm (no load) gear motor to drive these gears to get the wanted swing speed: - 50 RPM * ( 7 / 44) = 7.95 RPM (no load) The swing speed from the CAT 390F official specifications is 6.2, so with load I believe my speed matches that pretty well. I did it like this mostly because I couldn't find a gear ring that would fit and also in a way that I could cut it on my CNC. I wanted an internal gear, but my cutting bits for my CNC aren't small enough to cut inner gears, so it had to be an external gear. But I think external gears look cool, though, so all was not lost. :-) Later I've been thinking that I should rather not cut the gears myself, but use some more time to find gear rings on the net that I could use. I'm really happy about the track pads. They really hold up great! Not one have broken so far, even as the machine now weighs 30kg (60lbs). I was initially planning to mill them all from aluminum, but now I'm thinking that if some break, I just print some new ones. On my 3D printer, it takes about two days of continuous printing to print 80 track pads. I have a Makerbot Replicator 2X. - http://store.makerbot.com/replicator2x But that's quite an old 3D printer. I think these days, you can get better offers. The only important thing is that you can print ABS, because it's so much tougher than PLA (less brittle). And you need a heated build plate for ABS printing. Maybe one of these could do the job: - Ultimaker 2 - Zortrax M200 Pro - FlashForge Creator Pro I've not tried any of them, but I've heard some good things about them and the specs look ok. There's probably lots of reviews on youtube. Best regards, Stein :-) |
#109
|
|||
|
|||
![]()
Thanks, BigFord and MarkTurbo! :-)
Stein :-) |
#110
|
|||
|
|||
![]()
That thing is a beast!
|
#111
|
||||
|
||||
![]()
Thank you very much for your reply re swing gears, much appreciated.
Terry |
#112
|
|||
|
|||
![]()
I love that you made a system that you can use a controller with, I was wondering for awhile if it was possible within reason and you have proved (and gone far beyond) that it is.
Ill be copying this system as well as some more ideas of yours when I start my build a ways from now (which i will put in the build page) Its really helpful with all the links to everything you have done and detailed comments on it, thanks for that, it will help me tons, I cant wait for the final version =) |
#113
|
|||
|
|||
![]()
Thank you for those kind and encouraging words, Tk421reporting!
I'm looking forward to following your build! Stein :-) |
#114
|
|||
|
|||
![]()
I'm working on the house body now, and even though I wrote this in another thread already, it really belongs in this thread.
To try to get the right dimensions on all the small scale features, I typically try to find a couple of measurements from a spec sheet, and then scale a photo or diagram as a canvas in Fusion 360 to match the known sizes. E.g. from the spec sheet of the CAT 390F excavator, I can see that the length from the center to the very back (the tail swing radius) is 4.70 meters, and the height from the ground up to the counterweight is 1.64 meters. I insert the canvas and then scale it to match the known measurements (just divide by 14, since the scale is 1/14). After the canvas has been scaled properly, I can draw in the 3D-objects on top of it to match the sizes of the features. Insert canvas: ![]() ![]() Switch to orthograpic view: ![]() Draw in the objects: ![]() Switch back to perspective view: ![]() Hide canvas: ![]() Voilà! Best regards, Stein :-) |
#115
|
|||
|
|||
![]()
On this site you can find specs for most types of construction equipment:
- http://www.ritchiespecs.com/ For example, you can find the specs for this model, the CAT 390F: - http://www.ritchiespecs.com/specific...modelid=108962 |
#116
|
|||
|
|||
![]()
The angle sensors are now in place and I've added the code in the motor controllers to:
- Read the angle sensors - Set a max movement limit - Set a min movement limit - Set a customizable hysteresis to avoid rapid on/off switching at the end stops if the sensor fluctuates. - A way to read the current position from the host CPU (the Raspberry pi). I also added acceleration and variable braking. Both are compatible with the Pololu quik controller. The acceleration was needed to avoid jerkyness when entering or leaving the end limits. The braking helps a lot when holding the arm statically and avoids back-drive of the gear motors. The end stop logic works as I hoped, and I no longer have to worry about crashing into the end of the travel. Just for fun, I added a visualization of the excavator on a web page. It's just the same 3D model from Fusion 360, but exported to STL to be loadable by three.js in a web page. The web page uses WebSocket to read the current position of the joints from the excavator over WiFi. Here is a short video: ![]() https://youtu.be/Z60gWvpeJ8I Stein :-) |
#117
|
||||
|
||||
![]()
Fantastic !!
__________________
To view links or images in signatures your post count must be 10 or greater. You currently have 0 posts. |
#118
|
|||
|
|||
![]()
You can try the visualization on your own PC by clicking on this link:
- http://d1t2tbzmskak12.cloudfront.net...ion/index.html ![]() To view the client source code, just click "View source" on the web page. The web page will try to connect to the excavator using the local IP address 192.168.0.107:8001. If it isn't able to connect, it will just play some random movements. Only computers on my network will be able to connect to my excavator, so you all will see the random movements. On the excavator (the server in this case) I run these few lines to broadcast the positions to all clients that connect: Code:
var ws = require("nodejs-websocket") var server = ws.createServer().listen(8001); setInterval(function() { server.connections.forEach(function (conn) { conn.sendText(JSON.stringify({bucket: state.bucket.pos, stick: state.stick.pos })); }) }, 40); Best regards, Stein :-) |
#119
|
|||
|
|||
![]()
This is now the code on the motor controllers, that has the new current limiting, position reporting and position end limits, acceleration and variable braking.
You don't need to understand any of this code to use it. Just: 1. Connect the USB cable to a PC 2. Download the Arduino programmer: https://www.arduino.cc/en/Main/Software 3. Copy and paste the code below into the programming tool 4. Set the device ID on the second line (any number from 0 to 255, used to identify the controller later) I'm using device IDs 10, 11 and 12 for this build. 5. Click the "Upload" button Done! |
#120
|
|||
|
|||
![]() Code:
/* Based on the MonsterMoto Shield Example Sketch by: Jim Lindblom */ #include <limits.h> int deviceId = 10; // TODO: Set this to a unique ID for each controller! #define BRAKEVCC 0 #define CW 1 #define CCW 2 #define BRAKEGND 3 // VNH2SP30 pin definitions int inApin[2] = {7, 4}; // INA: Clockwise input int inBpin[2] = {8, 9}; // INB: Counter-clockwise input int pwmpin[2] = {5, 6}; // PWM input int cspin[2] = {2, 3}; // CS: Current sense ANALOG input int enpin[2] = {0, 1}; // EN: Status of switches output (Analog pin) // Position sensors int pospin[2] = {4, 5}; // Position sensors at ANALOG input 4,5 // Serial state int inBytes[15]; int inBytesCount = 0; int command = 0; unsigned long lastCommandTime = 0; unsigned long timeoutMillis = 1000; // Timing int timerDivisor = 8; int defaultTimerDivisor = 64; int millisDivisor = defaultTimerDivisor / timerDivisor; // Motor state int current[2] = {0, 0}; int currentLimit[2] = { 160, 160 }; int overcurrentDivisor[2] = {8, 8}; unsigned long overCurrentTime[2] = {0, 0}; int direction[2] = { BRAKEGND, BRAKEGND }; int directionWanted[2] = { BRAKEGND, BRAKEGND }; int speed[2] = { 0, 0 }; int speedPrev[2] = { 0, 0 }; int speedWanted[2] = { 0, 0 }; int acceleration[2] = { 100, 100 }; int position[2] = { 511, 511 }; int positionMin[2] = { INT_MIN, INT_MIN }; int positionMax[2] = { INT_MAX, INT_MAX }; bool positionMaxTriggered[2] = { false, false }; bool positionMinTriggered[2] = { false, false }; int positionHysteresis[2] = { 100, 100 }; // Loop state unsigned long lastTime = 0; unsigned long now = 0; int speedScaler = 4; void setup() { setPwmFrequency(5, timerDivisor); setPwmFrequency(6, timerDivisor); // Initialize digital pins as outputs for (int i=0; i<2; i++) { pinMode(inApin[i], OUTPUT); pinMode(inBpin[i], OUTPUT); pinMode(pwmpin[i], OUTPUT); } // Initialize motors braked motorGo(0, BRAKEGND, 255); motorGo(1, BRAKEGND, 255); // start serial port at 9600 bps: Serial.begin(9600); while (!Serial) { // wait for serial port to connect. Needed for native USB port only } } void loop() { // Keep time now = millis() / millisDivisor; // to account for the change of the timer by setPwmFrequency below // Read commands from serial port if (Serial.available() > 0) { int inByte = Serial.read(); if (inByte > 127) { inBytesCount = 0; command = inByte; switch(command) { // 0x90 & 0x91: Get Motor M0 & M1 Current case 0x90: Serial.write(current[0] / 4); command = 0; break; case 0x91: Serial.write(current[1] / 4); command = 0; break; // 0x94 & 0x95: Get Motor M0 & M1 position case 0x94: Serial.write(position[0] / 4); command = 0; break; case 0x95: Serial.write(position[1] / 4); command = 0; break; } lastCommandTime = now; } else if (command != 0) { if (inBytesCount < 14) { inBytes[inBytesCount] = inByte; } inBytesCount++; switch(inBytesCount) { case 1: { int inSpeed = inByte * 2; // From 0-127 range to 0-254 range int motor = -1; int inDirection = CW; switch(command) { case 0x86: motor = 0; inDirection = BRAKEGND; break; case 0x87: motor = 1; inDirection = BRAKEGND; break; case 0x88: motor = 0; inDirection = CW; break; case 0x8A: motor = 0; inDirection = CCW; break; case 0x8C: motor = 1; inDirection = CW; break; case 0x8E: motor = 1; inDirection = CCW; break; case 0x83: { if (inBytes[0] == 0) { Serial.write(deviceId); } command = 0; break; } } if (motor != -1) { speedWanted[motor] = inSpeed; directionWanted[motor] = inDirection; command = 0; } break; } case 4: { // 0x84, parameter number, parameter value, 0x55, 0x2A // Set parameter // Parameter number 8 and 9 are the current limits for motors 0 and 1 respectively switch(command) { case 0x84: { int retVal = 1; if (inBytes[2] == 0x55 && inBytes[3] == 0x2A) { retVal = 0; switch(inBytes[0]) { case 4: acceleration[0] = inBytes[1]; break; // 0-127 case 5: acceleration[1] = inBytes[1]; break; // 0-127 case 8: currentLimit[0] = inBytes[1] * 8; break; // 0-1016 case 9: currentLimit[1] = inBytes[1] * 8; break; // 0-1016 case 72: positionMax[0] = inBytes[1] * 8; break; // 0-1016 case 73: positionMax[1] = inBytes[1] * 8; break; // 0-1016 case 74: positionMin[0] = inBytes[1] * 8; break; // 0-1016 case 75: positionMin[1] = inBytes[1] * 8; break; // 0-1016 case 76: positionHysteresis[0] = inBytes[1] * 8; break; // 0-1016 case 77: positionHysteresis[1] = inBytes[1] * 8; break; // 0-1016 default: retVal = 2; break; } } Serial.write(retVal); command = 0; break; } } break; } } } } // Update motor state every 10ms if (lastTime == 0 || now < lastTime) { // If the first time or when the millis() values wrap, we need to fix the lastTime to be before the now time. lastTime = now; } if (now - lastTime >= 10) { lastTime = now; for (int i = 0; i < 2; i++) { bool sameDirection = direction[i] == directionWanted[i]; direction[i] = directionWanted[i]; speed[i] = speedWanted[i]; if ((direction[i] == CW) || (direction[i] == CCW)) { // Apply accelleration limiting int accelSpeed = speedScaler * speed[i]; // 10ms loop time and *4 gives the 40ms as in the Pololu controller if (direction[i] == CCW) { accelSpeed = -accelSpeed; } if ((acceleration[i] > 0) && (!(sameDirection && (abs(accelSpeed) < abs(speedPrev[i])))) && (abs(accelSpeed - speedPrev[i]) > acceleration[i])) { accelSpeed = speedPrev[i] + ((speedPrev[i] > accelSpeed) ? -acceleration[i] : acceleration[i]); } direction[i] = accelSpeed < 0 ? CCW : CW; speed[i] = abs(accelSpeed / speedScaler); speedPrev[i] = accelSpeed; // Apply current limiting current[i] = analogRead(cspin[i]); // If overcurrent, kill the output if (current[i] > currentLimit[i]) { overcurrentDivisor[i] = 0; overCurrentTime[i] = now; } // Slowly bring it back if (now > overCurrentTime[i] + 1000 && overcurrentDivisor[i] < 8) { overcurrentDivisor[i]++; overCurrentTime[i] = now; } speed[i] = speed[i] * overcurrentDivisor[i] / 8; } // Apply position limits int readPosition = analogRead(pospin[i]); int changeLimit = positionHysteresis[i] / 2 + 10; if (abs(readPosition - position[i]) > changeLimit) { position[i] = position[i] + (position[i] > readPosition ? -changeLimit : changeLimit); } else { position[i] = readPosition; } if (position[i] > positionMax[i]) { positionMaxTriggered[i] = true; } if (position[i] < positionMax[i] - positionHysteresis[i]) { positionMaxTriggered[i] = false; } if (position[i] < positionMin[i]) { positionMinTriggered[i] = true; } if (position[i] > positionMin[i] + positionHysteresis[i]) { positionMinTriggered[i] = false; } if ((positionMaxTriggered[i] && direction[i] == CW) || (positionMinTriggered[i] && direction[i] == CCW)) { direction[i] = BRAKEGND; speed[i] = 255; speedPrev[i] = 0; } // Stop on serial command timeout if (now - lastCommandTime > timeoutMillis) { direction[i] = BRAKEGND; speed[i] = 0; speedPrev[i] = 0; } motorGo(i, direction[i], speed[i]); } } } void motorGo(uint8_t motor, uint8_t direct, uint8_t pwm) { if (motor >= 0 && motor < 2 && direct >= 0 && direct < 4 && pwm >= 0 && pwm < 256 ) { digitalWrite(inApin[motor], (direct == BRAKEVCC) || (direct == CW) ? HIGH : LOW); digitalWrite(inBpin[motor], (direct == BRAKEVCC) || (direct == CCW) ? HIGH : LOW); analogWrite(pwmpin[motor], pwm); } } void setPwmFrequency(int pin, int divisor) { byte mode; if(pin == 5 || pin == 6 || pin == 9 || pin == 10) { switch(divisor) { case 1: mode = 0x01; break; case 8: mode = 0x02; break; case 64: mode = 0x03; break; case 256: mode = 0x04; break; case 1024: mode = 0x05; break; default: return; } if(pin == 5 || pin == 6) { TCCR0B = TCCR0B & 0b11111000 | mode; } else { TCCR1B = TCCR1B & 0b11111000 | mode; } } else if(pin == 3 || pin == 11) { switch(divisor) { case 1: mode = 0x01; break; case 8: mode = 0x02; break; case 32: mode = 0x03; break; case 64: mode = 0x04; break; case 128: mode = 0x05; break; case 256: mode = 0x06; break; case 1024: mode = 0x7; break; default: return; } TCCR2B = TCCR2B & 0b11111000 | mode; } } |
![]() |
Currently Active Users Viewing This Thread: 21 (0 members and 21 guests) | |
|
|