diff options
author | hoekstar <hoekstar> | 2007-12-18 20:31:18 +0000 |
---|---|---|
committer | hoekstar <hoekstar@cb376a5e-1013-0410-a455-b6b1f9ac8223> | 2007-12-18 20:31:18 +0000 |
commit | 876d0e47dbcc9614b19ffe5347d6f840a4006291 (patch) | |
tree | 655f12f275ab2ec32c8528ddec45c40ccc555572 | |
parent | e68308691cae9e3d0ca61728e66144ccb04d3a0e (diff) | |
download | reprap-876d0e47dbcc9614b19ffe5347d6f840a4006291.tar.gz reprap-876d0e47dbcc9614b19ffe5347d6f840a4006291.zip |
added a bunch of preliminary work for the single axis SNAP firmware.
git-svn-id: https://reprap.svn.sourceforge.net/svnroot/reprap@1190 cb376a5e-1013-0410-a455-b6b1f9ac8223
14 files changed, 970 insertions, 207 deletions
diff --git a/trunk/users/hoeken/arduino/PackIt/PackIt.cpp b/trunk/users/hoeken/arduino/PackIt/PackIt.cpp deleted file mode 100644 index 1ff1fac2..00000000 --- a/trunk/users/hoeken/arduino/PackIt/PackIt.cpp +++ /dev/null @@ -1,120 +0,0 @@ - -#include "PackIt.h" -#include "HardwareSerial.h" -#include "WConstants.h" - -PackIt::PackIt(byte to, byte from) -{ - this->to = to; - this->from = from; - this->size = 0; - this->crc = 0; -} - -boolean PackIt::add(byte b) -{ - //do we have room left? - if (this->size < MAX_PACKET_SIZE-1) - { - //add it in! - this->packets[this->size] = b; - this->size++; - - //calculate our crc - this->crc = this->crc ^ b; - - return true; - } - else - return false; -} - -boolean PackIt::add(char c) -{ - return this->add((byte)c); -} - -boolean PackIt::add(int i) -{ - byte j, b; - bool result; - - for (j=0; j<4; j++) - { - b = i & B11111111; - result = this->add(b); - i >>= 8; - } - - return result; -} - -boolean PackIt::add(unsigned int i) -{ - return this->add((int)i); -} - -boolean PackIt::add(long l) -{ - byte i, b; - bool result; - - for (i=0; i<4; i++) - { - b = l & B11111111; - result = this->add(b); - l >>= 8; - } - - return result; -} - -boolean PackIt::add(unsigned long l) -{ - return this->add((long)l); -} - -boolean PackIt::add(float f) -{ - byte i, b; - bool result; - - for (i=0; i<4; i++) - { - b = f & B11111111; - result = this->add(b); - f >>= 8; - } - - return result; -} - -boolean PackIt::add(double d) -{ - byte i, b; - bool result; - - for (i=0; i<8; i++) - { - b = d & B11111111; - result = this->add(b); - d >>= 8; - } - - return result; -} - -void PackIt::send() -{ - byte i; - - //send our header - Serial.print(this->to); - Serial.print(this->from); - Serial.print(this->crc); - Serial.print(this->size); - - //send our data! - for (i=0; i<MAX_PACKET_SIZE; i++) - Serial.print(this->packets[i]); -} diff --git a/trunk/users/hoeken/arduino/PackIt/PackIt.h b/trunk/users/hoeken/arduino/PackIt/PackIt.h deleted file mode 100644 index 6290c781..00000000 --- a/trunk/users/hoeken/arduino/PackIt/PackIt.h +++ /dev/null @@ -1,52 +0,0 @@ -/* - PackIt.h - Simple packet transmission library - Version 0.1 - - This library is used to send basic packets to the host software. - - History: - * Created initial library (0.1) by Zach Smith. - -*/ - -// ensure this library description is only included once -#ifndef PackIt_h -#define PackId_h - -#include "WConstants.h" - -//give us a default size of 255 -#ifndef MAX_PACKET_SIZE -#define MAX_PACKET_SIZE 255 -#endif - -// library interface description -class PackIt { - public: - - // constructors: - PackIt(byte from); - - //our adder methods - boolean add(byte b); - boolean add(char c); - boolean add(int i); - boolean add(unsigned int i); - boolean add(long l); - boolean add(unsigned long l); - boolean add(float f); - boolean add(double d); - - //our sender function - void send(byte to); - void clear(); - - private: - - byte to; - byte from; - byte crc; - byte size; - byte packets[MAX_PACKET_SIZE]; -}; - -#endif diff --git a/trunk/users/hoeken/arduino/PackIt/keywords.txt b/trunk/users/hoeken/arduino/PackIt/keywords.txt deleted file mode 100644 index 36c02f53..00000000 --- a/trunk/users/hoeken/arduino/PackIt/keywords.txt +++ /dev/null @@ -1,28 +0,0 @@ -####################################### -# Syntax Coloring Map For Test -####################################### - -####################################### -# Datatypes (KEYWORD1) -####################################### - -PackIt KEYWORD1 - -####################################### -# Methods and Functions (KEYWORD2) -####################################### - -create KEYWORD2 -add KEYWORD2 -send KEYWORD2 - - -###################################### -# Instances (KEYWORD2) -####################################### - - -####################################### -# Constants (LITERAL1) -####################################### - diff --git a/trunk/users/hoeken/arduino/firmware/3Axis_SNAP/3Axis_SNAP.pde b/trunk/users/hoeken/arduino/firmware/3Axis_SNAP/3Axis_SNAP.pde index 5b7d4938..35180a7b 100644 --- a/trunk/users/hoeken/arduino/firmware/3Axis_SNAP/3Axis_SNAP.pde +++ b/trunk/users/hoeken/arduino/firmware/3Axis_SNAP/3Axis_SNAP.pde @@ -12,13 +12,10 @@ #include <LinearAxis.h> #include <CartesianBot.h> -//the version of our software -#define VERSION_MAJOR 0 -#define VERSION_MINOR 2 +//the addresses of our emulated axes. #define X_ADDRESS 2 #define Y_ADDRESS 3 #define Z_ADDRESS 4 -#define HOST_ADDRESS 0 /******************************** * digital i/o pin assignment diff --git a/trunk/users/hoeken/arduino/firmware/Extruder_SNAP/Extruder_SNAP.pde b/trunk/users/hoeken/arduino/firmware/Extruder_SNAP/Extruder_SNAP.pde index f6466ec2..c718e61b 100644 --- a/trunk/users/hoeken/arduino/firmware/Extruder_SNAP/Extruder_SNAP.pde +++ b/trunk/users/hoeken/arduino/firmware/Extruder_SNAP/Extruder_SNAP.pde @@ -14,6 +14,7 @@ #define VERSION_MAJOR 0 #define VERSION_MINOR 2 #define HOST_ADDRESS 0 + // // Extrude commands // diff --git a/trunk/users/hoeken/arduino/firmware/Single_Arduino_SNAP/Single_Arduino_SNAP.pde b/trunk/users/hoeken/arduino/firmware/Single_Arduino_SNAP/Single_Arduino_SNAP.pde new file mode 100644 index 00000000..a431b940 --- /dev/null +++ b/trunk/users/hoeken/arduino/firmware/Single_Arduino_SNAP/Single_Arduino_SNAP.pde @@ -0,0 +1,85 @@ +/* + Single_Arduino_SNAP.pde - Combined cartesian bot + extruder firmware. + + History: + * Created initial version (0.1) by Zach Smith. +*/ + +/**************************************************************************************** +* digital i/o pin assignment +* +* this uses the undocumented feature of Arduino - pins 14-19 correspond to analog 0-5 +****************************************************************************************/ + +//cartesian bot pins +#define X_STEP_PIN +#define X_DIR_PIN +#define X_MIN_PIN +#define X_MAX_PIN +#define X_ENABLE_PIN +#define Y_STEP_PIN +#define Y_DIR_PIN +#define Y_MIN_PIN +#define Y_MAX_PIN +#define Y_ENABLE_PIN +#define Z_STEP_PIN +#define Z_DIR_PIN +#define Z_MIN_PIN +#define Z_MAX_PIN +#define Z_ENABLE_PIN + +//extruder pins +#define EXTRUDER_MOTOR_SPEED_PIN +#define EXTRUDER_MOTOR_DIR_PIN +#define EXTRUDER_HEATER_PIN +#define EXTRUDER_THERMISTOR_PIN 0 + +//the addresses of our emulated axes. +#define X_ADDRESS 2 +#define Y_ADDRESS 3 +#define Z_ADDRESS 4 +#define EXTRUDER_ADDRESS 8 + +// how many steps do our motors have? +#define X_MOTOR_STEPS 400 +#define Y_MOTOR_STEPS 400 +#define Z_MOTOR_STEPS 400 + +//our library includes. +#include <SNAP.h> +#include <LimitSwitch.h> +#include <RepStepper.h> +#include <LinearAxis.h> +#include <CartesianBot.h> +#include <CartesianBot_SNAP_v1.h> +#include <ThermoplastExtruder_SNAP_v2.h> + +void setup() +{ + Serial.begin(19200); + + //run any setup code we need. + setup_cartesian_bot_snap_v1(); + setup_extruder_snap_v2(); +} + +void loop() +{ + //get our state status / manage our status. + bot.readState(); + extruder.manageState(); + + //process our commands + snap.receivePacket(); + if (snap.packetReady()) + { + //who is it for? + byte dest = snap.getDestination(); + + //route the command to the proper object. + if (dest == EXTRUDER_ADDRESS) + process_thermoplast_extruder_snap_commands_v2(); + else + process_cartesian_bot_snap_commands_v1(); + } +} diff --git a/trunk/users/hoeken/arduino/library/CartesianBot_SNAP_v1/CartesianBot_SNAP-v1.cpp b/trunk/users/hoeken/arduino/library/CartesianBot_SNAP_v1/CartesianBot_SNAP-v1.cpp new file mode 100644 index 00000000..f5f0d717 --- /dev/null +++ b/trunk/users/hoeken/arduino/library/CartesianBot_SNAP_v1/CartesianBot_SNAP-v1.cpp @@ -0,0 +1,575 @@ + +/********************************** +* Global variable instantiations +**********************************/ +CartesianBot bot = CartesianBot( + 'x', X_MOTOR_STEPS, X_DIR_PIN, X_STEP_PIN, X_MIN_PIN, X_MAX_PIN, + 'y', Y_MOTOR_STEPS, Y_DIR_PIN, Y_STEP_PIN, Y_MIN_PIN, Y_MAX_PIN, + 'z', Z_MOTOR_STEPS, Z_DIR_PIN, Z_STEP_PIN, Z_MIN_PIN, Z_MAX_PIN +); + +byte x_notify = 255; +byte y_notify = 255; +byte z_notify = 255; + +byte x_sync_mode = sync_none; +byte y_sync_mode = sync_none; + +SIGNAL(SIG_OUTPUT_COMPARE1A) +{ + bot.readState(); + + if (bot.mode == MODE_SEEK) + { + if (bot.x.can_step) + bot.x.doStep(); + if (bot.x.atTarget() && x_notify != 255) + notifySeek(x_notify, X_ADDRESS, (int)bot.x.getPosition()); + + if (bot.y.can_step) + bot.y.doStep(); + if (bot.y.atTarget() && y_notify != 255) + notifySeek(y_notify, Y_ADDRESS, (int)bot.y.getPosition()); + + if (bot.z.can_step) + bot.z.doStep(); + if (bot.z.atTarget() && z_notify != 255) + notifySeek(z_notify, Z_ADDRESS, (int)bot.z.getPosition()); + + if (bot.atTarget()) + bot.stop(); + } + else if (bot.mode == MODE_DDA) + { + if (bot.x.can_step) + bot.x.ddaStep(bot.max_delta); + + if (bot.y.can_step) + bot.y.ddaStep(bot.max_delta); + + //z-axis not supported in v1.0 of comms. + + if (bot.atTarget()) + { + if (x_notify != 255) + notifyDDA(x_notify, X_ADDRESS, (int)bot.x.getPosition()); + if (y_notify != 255) + notifyDDA(y_notify, Y_ADDRESS, (int)bot.y.getPosition()); + + bot.stop(); + } + } + else if (bot.mode == MODE_HOMERESET) + { + if (bot.x.function == func_homereset) + { + if (!bot.x.atMin()) + bot.x.stepper.pulse(); + else + { + bot.x.setPosition(0); + bot.x.function = func_idle; + bot.stop(); + + if (x_notify != 255) + notifyHomeReset(x_notify, X_ADDRESS); + } + } + + if (bot.y.function == func_homereset) + { + if (!bot.y.atMin()) + bot.y.stepper.pulse(); + else + { + bot.y.setPosition(0); + bot.y.function = func_idle; + bot.stop(); + + if (y_notify != 255) + notifyHomeReset(y_notify, Y_ADDRESS); + } + } + + if (bot.z.function == func_homereset) + { + if (!bot.z.atMin()) + bot.z.stepper.pulse(); + else + { + bot.z.setPosition(0); + bot.z.function = func_idle; + bot.stop(); + + if (z_notify != 255) + notifyHomeReset(z_notify, Z_ADDRESS); + } + } + } + else if (bot.mode == MODE_FIND_MIN) + { + if (bot.x.function == func_findmin) + { + if (!bot.x.atMin()) + bot.x.stepper.pulse(); + else + { + bot.x.setPosition(0); + bot.x.stepper.setDirection(RS_FORWARD); + bot.x.function = func_findmax; + bot.mode = MODE_FIND_MAX; + } + } + + if (bot.y.function == func_findmin) + { + if (!bot.y.atMin()) + bot.y.stepper.pulse(); + else + { + bot.y.setPosition(0); + bot.y.stepper.setDirection(RS_FORWARD); + bot.y.function = func_findmax; + bot.mode = MODE_FIND_MAX; + } + } + + if (bot.z.function == func_findmin) + { + if (!bot.z.atMin()) + bot.z.stepper.pulse(); + else + { + bot.z.setPosition(0); + bot.z.stepper.setDirection(RS_FORWARD); + bot.z.function = func_findmax; + bot.mode = MODE_FIND_MAX; + } + } + } + else if (bot.mode == MODE_FIND_MAX) + { + if (bot.x.function == func_findmax) + { + //do a step if we're not there yet. + if (!bot.x.atMax()) + bot.x.doStep(); + + //are we there yet? + if (bot.x.atMax()) + { + bot.x.setMax(bot.x.getPosition()); + bot.x.function = func_idle; + bot.stop(); + + if (x_notify != 255) + notifyCalibrate(x_notify, X_ADDRESS, bot.x.getMax()); + } + } + + if (bot.y.function == func_findmax) + { + //do a step if we're not there yet. + if (!bot.y.atMax()) + bot.y.doStep(); + + //are we there yet? + if (bot.y.atMax()) + { + bot.y.setMax(bot.y.getPosition()); + bot.y.function = func_idle; + bot.stop(); + + if (x_notify != 255) + notifyCalibrate(x_notify, X_ADDRESS, bot.y.getMax()); + } + } + + if (bot.z.function == func_findmax) + { + //do a step if we're not there yet. + if (!bot.z.atMax()) + bot.z.doStep(); + + //are we there yet? + if (bot.z.atMax()) + { + bot.z.setMax(bot.z.getPosition()); + bot.z.function = func_idle; + bot.stop(); + + if (x_notify != 255) + notifyCalibrate(x_notify, X_ADDRESS, bot.z.getMax()); + } + } + } +} + +void setup_cartesian_bot_snap_v1() +{ + bot.setupTimerInterrupt(); + + snap.addDevice(X_ADDRESS); + snap.addDevice(Y_ADDRESS); + snap.addDevice(Z_ADDRESS); +} + +void process_cartesian_bot_snap_commands_v1() +{ + byte cmd = snap.getByte(0); + byte dest = snap.getDestination(); + unsigned long position; + + switch (cmd) + { + case CMD_VERSION: + snap.sendReply(); + snap.sendDataByte(CMD_VERSION); // Response type 0 + snap.sendDataByte(VERSION_MINOR); + snap.sendDataByte(VERSION_MAJOR); + snap.endMessage(); + break; + + case CMD_FORWARD: + //okay, set our speed. + if (dest == X_ADDRESS) + { + bot.x.stepper.setRPM(snap.getByte(1)); + bot.x.stepper.setDirection(RS_FORWARD); + bot.x.function = func_forward; + bot.setTimer(bot.x.stepper.getSpeed()); + } + else if (dest == Y_ADDRESS) + { + bot.y.stepper.setRPM(snap.getByte(1)); + bot.y.stepper.setDirection(RS_FORWARD); + bot.y.function = func_forward; + bot.setTimer(bot.y.stepper.getSpeed()); + } + else if (dest == Z_ADDRESS) + { + bot.z.stepper.setRPM(snap.getByte(1)); + bot.z.stepper.setDirection(RS_FORWARD); + bot.z.function = func_forward; + bot.setTimer(bot.z.stepper.getSpeed()); + } + break; + + case CMD_REVERSE: + if (dest == X_ADDRESS) + { + bot.x.stepper.setRPM(snap.getByte(1)); + bot.x.stepper.setDirection(RS_REVERSE); + bot.x.function = func_reverse; + bot.setTimer(bot.x.stepper.getSpeed()); + } + else if (dest == Y_ADDRESS) + { + bot.y.stepper.setRPM(snap.getByte(1)); + bot.y.stepper.setDirection(RS_REVERSE); + bot.y.function = func_reverse; + bot.setTimer(bot.y.stepper.getSpeed()); + } + else if (dest == Z_ADDRESS) + { + bot.z.stepper.setRPM(snap.getByte(1)); + bot.z.stepper.setDirection(RS_REVERSE); + bot.z.function = func_reverse; + bot.setTimer(bot.z.stepper.getSpeed()); + } + break; + + case CMD_SETPOS: + position = ((snap.getByte(2) << 8) + (snap.getByte(1))); + + if (dest == X_ADDRESS) + { + bot.x.setPosition(position); + bot.x.setTarget(position); + } + else if (dest == Y_ADDRESS) + { + bot.y.setPosition(position); + bot.y.setTarget(position); + } + else if (dest == Z_ADDRESS) + { + bot.z.setPosition(position); + bot.z.setTarget(position); + } + break; + + case CMD_GETPOS: + if (dest == X_ADDRESS) + position = bot.x.getPosition(); + else if (dest == Y_ADDRESS) + position = bot.y.getPosition(); + else if (dest == Z_ADDRESS) + position = bot.z.getPosition(); + + snap.sendReply(); + snap.sendDataByte(CMD_GETPOS); + snap.sendDataByte(position & 0xff); + snap.sendDataByte(position >> 8); + snap.endMessage(); + break; + + case CMD_SEEK: + // Goto position + position = ((snap.getByte(3) << 8) + snap.getByte(2)); + + //okay, set our speed. + if (dest == X_ADDRESS) + { + bot.x.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.x.stepper.getSpeed()); + bot.x.setTarget(position); + } + else if (dest == Y_ADDRESS) + { + bot.y.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.y.stepper.getSpeed()); + bot.y.setTarget(position); + } + else if (dest == Z_ADDRESS) + { + bot.z.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.z.stepper.getSpeed()); + bot.z.setTarget(position); + } + + //start our seek. + bot.startSeek(); + break; + + case CMD_FREE: + if (dest == X_ADDRESS) + { + digitalWrite(X_ENABLE_PIN, LOW); + bot.x.function = func_idle; + } + if (dest == Y_ADDRESS) + { + digitalWrite(Y_ENABLE_PIN, LOW); + bot.y.function = func_idle; + } + if (dest == Z_ADDRESS) + { + digitalWrite(Z_ENABLE_PIN, LOW); + bot.y.function = func_idle; + } + break; + + case CMD_NOTIFY: + // Parameter is receiver of notification, or 255 if notification should be turned off + if (dest == X_ADDRESS) + x_notify = snap.getByte(1); + if (dest == Y_ADDRESS) + y_notify = snap.getByte(1); + if (dest == Z_ADDRESS) + z_notify = snap.getByte(1); + break; + + case CMD_SYNC: + // Set sync mode.. used to determine which direction to move slave stepper + if (dest == X_ADDRESS) + x_sync_mode = snap.getByte(1); + else if (dest == Y_ADDRESS) + y_sync_mode = snap.getByte(1); + break; + + case CMD_CALIBRATE: + //stop other stuff. + bot.stop(); + + // Request calibration (search at given speed) + if (dest == X_ADDRESS) + { + bot.x.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.x.stepper.getSpeed()); + bot.x.function = func_findmin; + } + else if (dest == Y_ADDRESS) + { + bot.y.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.y.stepper.getSpeed()); + bot.y.function = func_findmin; + } + else if (dest == Z_ADDRESS) + { + bot.z.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.z.stepper.getSpeed()); + bot.z.function = func_findmin; + } + + //start our calibration. + bot.startCalibration(); + break; + + case CMD_GETRANGE: + if (dest == X_ADDRESS) + position = bot.x.getMax(); + else if (dest == Y_ADDRESS) + position = bot.y.getMax(); + else if (dest == Z_ADDRESS) + position = bot.z.getMax(); + + //tell the host. + snap.sendReply(); + snap.sendDataByte(CMD_GETPOS); + snap.sendDataInt(position); + snap.endMessage(); + break; + + case CMD_DDA: + unsigned long target; + + //stop the bot. + bot.stop(); + + //get our coords. + position = snap.getInt(2); + target = snap.getInt(4); + + //which axis is leading? + if (dest == X_ADDRESS) + { + bot.x.setTarget(position); + + //we can figure out the target based on the sync mode + if (y_sync_mode == sync_inc) + bot.y.setTarget(bot.y.getPosition() + target); + else + bot.y.setTarget(bot.y.getPosition() - target); + } + else if (dest == Y_ADDRESS) + { + bot.y.setTarget(position); + bot.x.setTarget(target); + + //we can figure out the target based on the sync mode + if (x_sync_mode == sync_inc) + bot.x.setTarget(bot.x.getPosition() + target); + else + bot.x.setTarget(bot.x.getPosition() - target); + } + + //set z's target to itself. + bot.z.setTarget(bot.z.getPosition()); + + //set our speed. + bot.x.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.x.stepper.getSpeed()); + + //init our DDA stuff! + bot.calculateDDA(); + break; + + case CMD_FORWARD1: + if (dest == X_ADDRESS) + bot.x.forward1(); + else if (dest == Y_ADDRESS) + bot.y.forward1(); + else if (dest == Z_ADDRESS) + bot.z.forward1(); + break; + + case CMD_BACKWARD1: + if (dest == X_ADDRESS) + bot.x.reverse1(); + else if (dest == Y_ADDRESS) + bot.y.reverse1(); + else if (dest == Z_ADDRESS) + bot.z.reverse1(); + break; + + case CMD_SETPOWER: + //doesnt matter because power is handled by the stepper driver board! + break; + + case CMD_GETSENSOR: + snap.sendReply(); + snap.sendDataByte(CMD_GETSENSOR); + // FIXME: Dummy values for now + snap.sendDataByte(0); + snap.sendDataByte(0); + snap.endMessage(); + break; + + case CMD_HOMERESET: + bot.stop(); + + if (dest == X_ADDRESS) + { + //configure our axis + bot.x.stepper.setDirection(RS_REVERSE); + bot.x.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.x.stepper.getSpeed()); + + //tell our axis to go home. + bot.x.function = func_homereset; + } + else if (dest == Y_ADDRESS) + { + //configure our axis + bot.y.stepper.setDirection(RS_REVERSE); + bot.y.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.y.stepper.getSpeed()); + + //tell our axis to go home. + bot.y.function = func_homereset; + } + else if (dest == Z_ADDRESS) + { + //configure our axis + bot.z.stepper.setDirection(RS_REVERSE); + bot.z.stepper.setRPM(snap.getByte(1)); + bot.setTimer(bot.z.stepper.getSpeed()); + + //tell our axis to go home. + bot.z.function = func_homereset; + } + + //starts our home reset mode. + bot.startHomeReset(); + + break; + } + + snap.releaseLock(); +} + +void notifyHomeReset(byte to, byte from) +{ + snap.startMessage(from); + snap.sendMessage(to); + snap.sendDataByte(CMD_HOMERESET); + snap.endMessage(); +} + +void notifyCalibrate(byte to, byte from, unsigned int position) +{ + snap.startMessage(from); + snap.sendMessage(to); + snap.sendDataByte(CMD_CALIBRATE); + snap.sendDataInt(position); + snap.endMessage(); +} + +void notifySeek(byte to, byte from, unsigned int position) +{ + snap.startMessage(from); + snap.sendMessage(to); + snap.sendDataByte(CMD_SEEK); + snap.sendDataInt(position); + snap.endMessage(); +} + +void notifyDDA(byte to, byte from, unsigned int position) +{ + snap.startMessage(from); + snap.sendMessage(to); + snap.sendDataByte(CMD_DDA); + snap.sendDataInt(position); + snap.endMessage(); +}
\ No newline at end of file diff --git a/trunk/users/hoeken/arduino/library/CartesianBot_SNAP_v1/CartesianBot_SNAP-v1.h b/trunk/users/hoeken/arduino/library/CartesianBot_SNAP_v1/CartesianBot_SNAP-v1.h new file mode 100644 index 00000000..41a0825b --- /dev/null +++ b/trunk/users/hoeken/arduino/library/CartesianBot_SNAP_v1/CartesianBot_SNAP-v1.h @@ -0,0 +1,70 @@ +//this guy actually processes the v1 SNAP commands. +void process_cartesian_bot_snap_commands_v1(); + +//notification functions to let the host know whats up. +void notifyHomeReset(byte to, byte from); +void notifyCalibrate(byte to, byte from, unsigned int position); +void notifySeek(byte to, byte from, unsigned int position); +void notifyDDA(byte to, byte from, unsigned int position); + +extern CartesianBot bot; + +// +// Version information +// +#define VERSION_MAJOR 1 +#define VERSION_MINOR 0 +#define HOST_ADDRESS 0 + +// +// Linear Axis commands +// +#define CMD_VERSION 0 +#define CMD_FORWARD 1 +#define CMD_REVERSE 2 +#define CMD_SETPOS 3 +#define CMD_GETPOS 4 +#define CMD_SEEK 5 +#define CMD_FREE 6 +#define CMD_NOTIFY 7 +#define CMD_SYNC 8 +#define CMD_CALIBRATE 9 +#define CMD_GETRANGE 10 +#define CMD_DDA 11 +#define CMD_FORWARD1 12 +#define CMD_BACKWARD1 13 +#define CMD_SETPOWER 14 +#define CMD_GETSENSOR 15 +#define CMD_HOMERESET 16 + +// +// Addresses for our linear axes. +// +#define X_ADDRESS 2 +#define Y_ADDRESS 3 +#define Z_ADDRESS 4 + +/******************************** +* Global mode declarations +********************************/ +enum functions { + func_idle, + func_forward, + func_reverse, + func_syncwait, // Waiting for sync prior to seeking + func_seek, + func_findmin, // Calibration, finding minimum + func_findmax, // Calibration, finding maximum + func_ddamaster, + func_homereset // Move to min position and reset +}; + +/******************************** + * Sync mode declarations + ********************************/ +enum sync_modes { + sync_none, // no sync (default) + sync_seek, // synchronised seeking + sync_inc, // inc motor on each pulse + sync_dec // dec motor on each pulse +};
\ No newline at end of file diff --git a/trunk/users/hoeken/arduino/library/SNAP/SNAP.cpp b/trunk/users/hoeken/arduino/library/SNAP/SNAP.cpp index 2c5e0a4d..6db073ee 100644 --- a/trunk/users/hoeken/arduino/library/SNAP/SNAP.cpp +++ b/trunk/users/hoeken/arduino/library/SNAP/SNAP.cpp @@ -411,3 +411,6 @@ unsigned int SNAP::getInt(byte index) { return (this->rxBuffer[index+1] << 8) + this->rxBuffer[index]; } + +// Preinstantiate Objects +SNAP snap = SNAP(); diff --git a/trunk/users/hoeken/arduino/library/SNAP/SNAP.h b/trunk/users/hoeken/arduino/library/SNAP/SNAP.h index 904d9f22..2fe594b1 100644 --- a/trunk/users/hoeken/arduino/library/SNAP/SNAP.h +++ b/trunk/users/hoeken/arduino/library/SNAP/SNAP.h @@ -6,9 +6,10 @@ #include "HardwareSerial.h" //how many devices we have on this meta device -#define MAX_DEVICE_COUNT 5 // size of our array to store virtual addresses -#define TX_BUFFER_SIZE 16 // Transmit buffer size. -#define RX_BUFFER_SIZE 16 // Receive buffer size. +#define MAX_DEVICE_COUNT 5 // size of our array to store virtual addresses +#define TX_BUFFER_SIZE 16 // Transmit buffer size. +#define RX_BUFFER_SIZE 16 // Receive buffer size. +#define HOST_ADDRESS 0 // address of the host. //our sync packet value. #define SNAP_SYNC 0x54 @@ -120,4 +121,7 @@ class SNAP byte deviceCount; }; +//global variable declaration. +extern SNAP snap; + #endif diff --git a/trunk/users/hoeken/arduino/library/ThermoplastExtruder_SNAP_v2/ThermoplastExtruder_SNAP_v2.cpp b/trunk/users/hoeken/arduino/library/ThermoplastExtruder_SNAP_v2/ThermoplastExtruder_SNAP_v2.cpp new file mode 100644 index 00000000..396f5556 --- /dev/null +++ b/trunk/users/hoeken/arduino/library/ThermoplastExtruder_SNAP_v2/ThermoplastExtruder_SNAP_v2.cpp @@ -0,0 +1,140 @@ +//instantiate our extruder class. +ThermoplastExtruder extruder = ThermoplastExtruder(EXTRUDER_MOTOR_DIR_PIN, EXTRUDER_MOTOR_SPEED_PIN, EXTRUDER_HEATER_PIN, EXTRUDER_THERMISTOR_PIN); + +//this guys sets us up. +void setup_extruder_snap_v2() +{ + snap.addDevice(EXTRUDER_ADDRESS); +} + +//this guy actually processes the commands. +void process_thermoplast_extruder_snap_commands_v2() +{ + byte cmd = snap.getByte(0); + + switch (cmd) + { + case CMD_VERSION: + snap.sendReply(); + snap.sendDataByte(CMD_VERSION); + snap.sendDataByte(VERSION_MINOR); + snap.sendDataByte(VERSION_MAJOR); + snap.endMessage(); + break; + + // Extrude speed takes precedence over fan speed + case CMD_FORWARD: + extruder.setDirection(1); + extruder.setSpeed(snap.getByte(1)); + break; + + // seems to do the same as Forward + case CMD_REVERSE: + extruder.setDirection(0); + extruder.setSpeed(snap.getByte(1)); + break; + + case CMD_SETPOS: + currentPos = snap.getInt(1); + break; + + case CMD_GETPOS: + //send some Bogus data so the Host software is happy + snap.sendReply(); + snap.sendDataByte(CMD_GETPOS); + snap.sendDataInt(currentPos); + snap.endMessage(); + break; + + case CMD_SEEK: + debug.println("n/i: seek"); + break; + + case CMD_FREE: + // Free motor. There is no torque hold for a DC motor, + // so all we do is switch off + extruder.setSpeed(0); + break; + + case CMD_NOTIFY: + debug.println("n/i: notify"); + break; + + case CMD_ISEMPTY: + // We don't know so we say we're not empty + snap.sendReply(); + snap.sendDataByte(CMD_ISEMPTY); + snap.sendDataByte(0); + snap.endMessage(); + break; + + case CMD_SETHEAT: + requestedHeat0 = snap.getByte(1); + requestedHeat1 = snap.getByte(2); + temperatureLimit0 = snap.getByte(3); + temperatureLimit1 = snap.getByte(4); + extruder.setTargetTemperature(temperatureLimit1); + extruder.setHeater(requestedHeat1); + + debug.print("requestedHeat0: "); + debug.println(requestedHeat0); + debug.print("requestedHeat1: "); + debug.println(requestedHeat1); + debug.print("temperatureLimit0: "); + debug.println(temperatureLimit0); + debug.print("temperatureLimit1: "); + debug.println(temperatureLimit1); + break; + + case CMD_GETTEMP: + debug.print("temp: "); + debug.println(extruder.getTemperature(), DEC); + debug.print("raw: "); + debug.println(extruder.getRawTemperature(), DEC); + + snap.sendReply(); + snap.sendDataByte(CMD_GETTEMP); + snap.sendDataByte(extruder.getTemperature()); + snap.sendDataByte(0); + snap.endMessage(); + break; + + case CMD_SETCOOLER: + debug.println("n/i: set cooler"); + break; + + // "Hidden" low level commands + case CMD_PWMPERIOD: + debug.println("n/i: pwm period"); + break; + + case CMD_PRESCALER: + debug.println("n/i: prescaler"); + break; + + case CMD_SETVREF: + debug.println("n/i: set vref"); + break; + + case CMD_SETTEMPSCALER: + debug.println("n/i: set temp scaler"); + break; + + case CMD_GETDEBUGINFO: + debug.println("n/i: get debug info"); + break; + + case CMD_GETTEMPINFO: + snap.sendReply(); + snap.sendDataByte(CMD_GETTEMPINFO); + snap.sendDataByte(requestedHeat0); + snap.sendDataByte(requestedHeat1); + snap.sendDataByte(temperatureLimit0); + snap.sendDataByte(temperatureLimit1); + snap.sendDataByte(extruder.getTemperature()); + snap.sendDataByte(0); + snap.endMessage(); + break; + } + snap.releaseLock(); +}
\ No newline at end of file diff --git a/trunk/users/hoeken/arduino/library/ThermoplastExtruder_SNAP_v2/ThermoplastExtruder_SNAP_v2.h b/trunk/users/hoeken/arduino/library/ThermoplastExtruder_SNAP_v2/ThermoplastExtruder_SNAP_v2.h new file mode 100644 index 00000000..8de3a265 --- /dev/null +++ b/trunk/users/hoeken/arduino/library/ThermoplastExtruder_SNAP_v2/ThermoplastExtruder_SNAP_v2.h @@ -0,0 +1,36 @@ + +// +// Various processing commands. +// +void setup_extruder_snap_v2(); +void process_thermoplast_extruder_snap_commands_v2(); + +// +// Version information +// +#define VERSION_MAJOR 2 +#define VERSION_MINOR 0 + +// +// Extruder commands +// +#define CMD_VERSION 0 +#define CMD_FORWARD 1 +#define CMD_REVERSE 2 +#define CMD_SETPOS 3 +#define CMD_GETPOS 4 +#define CMD_SEEK 5 +#define CMD_FREE 6 +#define CMD_NOTIFY 7 +#define CMD_ISEMPTY 8 +#define CMD_SETHEAT 9 +#define CMD_GETTEMP 10 +#define CMD_SETCOOLER 11 +#define CMD_PWMPERIOD 50 +#define CMD_PRESCALER 51 +#define CMD_SETVREF 52 +#define CMD_SETTEMPSCALER 53 +#define CMD_GETDEBUGINFO 54 +#define CMD_GETTEMPINFO 55 + +extern ThermoplastExtruder extruder;
\ No newline at end of file diff --git a/trunk/users/hoeken/arduino/utilities/createTemperatureLookup.py b/trunk/users/hoeken/arduino/utilities/createTemperatureLookup.py new file mode 100644 index 00000000..ae304fa4 --- /dev/null +++ b/trunk/users/hoeken/arduino/utilities/createTemperatureLookup.py @@ -0,0 +1,52 @@ +# Creates a C code lookup table for doing ADC to temperature conversion +# on a microcontroller +# based on: http://hydraraptor.blogspot.com/2007/10/measuring-temperature-easy-way.html + +from math import * + +class Thermistor: + "Class to do the thermistor maths" + def __init__(self, r0, t0, beta, r1, r2): + self.r0 = r0 # stated resistance, e.g. 10K + self.t0 = t0 + 273.15 # temperature at stated resistance, e.g. 25C + self.beta = beta # stated beta, e.g. 3500 + self.vadc = 5.0 # ADC reference + self.vcc = 5.0 # supply voltage to potential divider + self.vs = r1 * self.vcc / (r1 + r2) # effective bias voltage + self.rs = r1 * r2 / (r1 + r2) # effective bias impedance + self.k = r0 * exp(-beta / self.t0) # constant part of calculation + + def temp(self,adc): + "Convert ADC reading into a temperature in Celcius" + v = adc * self.vadc / 1024 # convert the 10 bit ADC value to a voltage + r = self.rs * v / (self.vs - v) # resistance of thermistor + return (self.beta / log(r / self.k)) - 273.15 # temperature + + def setting(self, t): + "Convert a temperature into a ADC value" + r = self.r0 * exp(self.beta * (1 / (t + 273.15) - 1 / self.t0)) # resistance of the thermistor + v = self.vs * r / (self.rs + r) # the voltage at the potential divider + return round(v / self.vadc * 1024) # the ADC reading + +t = Thermistor(10000, 25, 3947, 1000000, 1000) + +adcs = [1, 20, 25, 30, 35, 40, 45, 50, 60, 70, 80, 90, 100, 110, 130, 150, 190, 220, 250, 300] +first = 1 + +print "#define NUMTEMPS ", len(adcs) + +print "short temptable[NUMTEMPS][2] = {" +print "// { adc , temp }" +for adc in adcs: + if first==1: + first = 0 + else: + print "," + print " {", adc, ", ", int(t.temp(adc)), "}", +print +print "};" + + + +#print t.setting(250) +#print t.temp(200) diff --git a/trunk/users/hoeken/arduino/rpm_tick_formula.php b/trunk/users/hoeken/arduino/utilities/rpm_tick_formula.php index 01ca1e57..01ca1e57 100755 --- a/trunk/users/hoeken/arduino/rpm_tick_formula.php +++ b/trunk/users/hoeken/arduino/utilities/rpm_tick_formula.php |