![]() |
|
Construction Equipment If it digs, pushes, hauls dirt "off road" post it here. |
![]() |
|
Thread Tools | Display Modes |
|
#1
|
|||
|
|||
![]()
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 :-) |
#2
|
|||
|
|||
![]()
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! |
#3
|
|||
|
|||
![]() 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; } } |
#4
|
|||
|
|||
![]()
Added the final angle sensor that reads the angle of the boom. This sensor is the same as the previous two, except that it's mounted a bit differently and it has no cover.
With this sensor in place it's finally possible to run the excavator without risking to break it. :-) If I have time later I'll try to read the rest of the positions and angles with encoders for the swing and tracks, and an IMU (BNO055) + GPS for the house. ![]() ![]() ![]() |
#5
|
|||
|
|||
![]()
Running lines along the arm.
I need to run the power to the bucket motor and wires for the bucket and stick angle sensors along the arm. Also, I want to attach some auxiliary lines that can be used for various attachments later. I ran totally overboard with the auxiliary lines. I've added: - 2 x 2 x 0.75mm2 power line with XT-60 connector (one on each side) - 2 x USB cable (one on each side) The power lines can run about 10A each and can be used for driving motors, lights, etc. The USB cables can be used both as USB cables and also as just normal wire that can be used for driving servos or sending back sensor data. Each USB cable has two wires that can run 2A and two signal wires that can't really run any current, but can be used for signals, like the servo position (the white wire) or sensor output. So the USB cable doubles as a servo cable that can control two servos, just normal power lines (2A) or sensor wires. With a small adapter from USB to Futaba connectors, it will be easy to hook up servos. Some examples of what can be attached: - Quick coupler (using just one power line and that stops on a set current limit) - Impact hammer (one power line) - Drill - Saw (garden timmer, angle grinder, etc) - Light - Any USB device, like a web camera, a 3D depth camera like the Kinect, a desktop rocket launcher, a 32 channel servo driver, etc, etc. USB cables have very varying current capabilities. The cable I'm using here has very thick power lines and the thickness and stiffness also helps to give a visual appearance more similar to hydraulic lines. The the three-wire sensor cable, two-wire power cable and the USB cable: ![]() I've 3D-printed three different types of clamps to hold down the wires along the arm. The screws are 2.6mm x 8mm self-tapping screws. ![]() And a terminal at the stick: ![]() ![]() And it all attaches to the arm in this way: ![]() ![]() ![]() ![]() ![]() ![]() |
#6
|
|||
|
|||
![]()
It's always a question where to put the required RC-components on a machine. I'm talking about things like the on/off switch, charge connector, etc. I want them accessible, but not visible.
On this machine, they could all go underneath, but I'm thinking that there might be a lot of dust, dirt, braches, leaves, etc there, and also it's not that accessible on the underside. So on this model, I opted to put them on top, but conceal them under a lid. I'm mimicking the engine lid from the original: ![]() And then underneath the lid, the control panel is located. It has: - The on/off switch - A battery voltage meter - A sound volume dial The charge connectors are just a standard XT60 and a balancing connector that are accessible under the lid, not attached to the control panel. ![]() ![]() The control panel stand also serves as the mount for the audio amplifier. The amplifier is a 2x50w D-class amplifier. The volume control is a stereo logarithmic pot - A1k. Ebay links: - Amplifier: http://www.ebay.com/itm/272163830096 - Volume control: http://www.ebay.com/itm/331883285534 - Voume cap: http://www.ebay.com/itm/221309764371 - Voltage meter: http://www.ebay.com/itm/201546863361 ![]() ![]() ![]() ![]() ![]() |
![]() |
Currently Active Users Viewing This Thread: 1 (0 members and 1 guests) | |
|
|