From 27c59e78196e2bbe3a44d4de137621d051aa3ecf Mon Sep 17 00:00:00 2001 From: Perry Date: Sat, 26 Nov 2016 13:32:39 -0800 Subject: [PATCH] autogen update --- ArduinoMsgCodec.h | 301 +++++----- Device.cpp | 16 +- Device.h | 20 +- LinkedList.cpp | 1 - LinkedList.h | 148 ++--- MRLComm.ino | 133 +++-- MrlCmd.cpp | 76 --- MrlCmd.h | 25 - MrlComm.cpp | 1180 +++++++++++++++++---------------------- MrlComm.h | 141 +++-- MrlI2cBus.cpp | 57 +- MrlI2cBus.h | 12 +- MrlIo.cpp | 111 ---- MrlIo.h | 34 -- MrlMotor.h | 57 +- MrlMsg.cpp | 175 ------ MrlMsg.h | 63 --- MrlNeopixel.cpp | 423 +++++++------- MrlNeopixel.h | 13 +- MrlPulse.h | 140 +++-- MrlServo.cpp | 43 +- MrlServo.h | 14 +- MrlStepper.h | 38 +- MrlUltrasonic.h | 96 ---- MrlUltrasonicSensor.cpp | 100 ++++ MrlUltrasonicSensor.h | 36 ++ Msg.cpp | 757 +++++++++++++++++++++++++ Msg.h | 125 +++++ Pin.h | 10 - 29 files changed, 2297 insertions(+), 2048 deletions(-) delete mode 100644 MrlCmd.cpp delete mode 100644 MrlCmd.h delete mode 100644 MrlIo.cpp delete mode 100644 MrlIo.h delete mode 100644 MrlMsg.cpp delete mode 100644 MrlMsg.h delete mode 100644 MrlUltrasonic.h create mode 100644 MrlUltrasonicSensor.cpp create mode 100644 MrlUltrasonicSensor.h create mode 100644 Msg.cpp create mode 100644 Msg.h diff --git a/ArduinoMsgCodec.h b/ArduinoMsgCodec.h index 06341f9..d57d314 100644 --- a/ArduinoMsgCodec.h +++ b/ArduinoMsgCodec.h @@ -1,178 +1,145 @@ -#ifndef ArduinoMsgCodec_h -#define ArduinoMsgCodec_h +#ifndef ArduinoMsgCodec_h +#define ArduinoMsgCodec_h /******************************************************************* * MRLCOMM FUNCTION GENERATED INTERFACE - * this file was generated by ArduinoMsgCodec and ArduinoMsgCodec.h.template + * these defines are generated with : + * arduinoMsgs.schema + * ArduinoMsgGenerator + * src\resource\Arduino\generate\ArduinoMsgCodec.template.h */ -///// INO GENERATED DEFINITION BEGIN ////// -// {publishMRLCommError Integer} -#define PUBLISH_MRLCOMM_ERROR 1 -// {getVersion} -#define GET_VERSION 2 -// {publishVersion Integer} -#define PUBLISH_VERSION 3 -// {analogWrite int int} -#define ANALOG_WRITE 4 -// {controllerAttach Arduino int} -#define CONTROLLER_ATTACH 5 -// {createI2cDevice I2CControl int int} -#define CREATE_I2C_DEVICE 6 -// {customMsg int[]} -#define CUSTOM_MSG 7 -// {deviceAttach DeviceControl Object[]} -#define DEVICE_ATTACH 8 -// {deviceDetach DeviceControl} -#define DEVICE_DETACH 9 -// {digitalWrite int int} -#define DIGITAL_WRITE 10 -// {disableBoardStatus} -#define DISABLE_BOARD_STATUS 11 -// {disablePin int} -#define DISABLE_PIN 12 -// {disablePins} -#define DISABLE_PINS 13 -// {enableBoardStatus int} -#define ENABLE_BOARD_STATUS 14 -// {enablePin int} -#define ENABLE_PIN 15 -// {getMrlPinType PinDefinition} -#define GET_MRL_PIN_TYPE 16 -// {heartbeat} -#define HEARTBEAT 17 -// {i2cRead I2CControl int int byte[] int} -#define I2C_READ 18 -// {i2cReturnData SensorData} -#define I2C_RETURN_DATA 19 -// {i2cWrite I2CControl int int byte[] int} -#define I2C_WRITE 20 -// {i2cWriteRead I2CControl int int byte[] int byte[] int} -#define I2C_WRITE_READ 21 -// {intsToString int[] int int} -#define INTS_TO_STRING 22 -// {isAttached} -#define IS_ATTACHED 23 -// {motorMove MotorControl} -#define MOTOR_MOVE 24 -// {motorMoveTo MotorControl} -#define MOTOR_MOVE_TO 25 -// {motorReset MotorControl} -#define MOTOR_RESET 26 -// {motorStop MotorControl} -#define MOTOR_STOP 27 -// {msgRoute} -#define MSG_ROUTE 28 -// {neoPixelSetAnimation NeoPixel int int int int int} -#define NEO_PIXEL_SET_ANIMATION 29 -// {neoPixelWriteMatrix NeoPixel List} -#define NEO_PIXEL_WRITE_MATRIX 30 -// {onSensorData SensorData} -#define ON_SENSOR_DATA 31 -// {pinMode int String} -#define PIN_MODE 32 -// {publishAttachedDevice String} -#define PUBLISH_ATTACHED_DEVICE 33 -// {publishBoardInfo BoardInfo} -#define PUBLISH_BOARD_INFO 34 -// {publishBoardStatus BoardStatus} -#define PUBLISH_BOARD_STATUS 35 -// {publishCustomMsg int[]} -#define PUBLISH_CUSTOM_MSG 36 -// {publishDebug String} -#define PUBLISH_DEBUG 37 -// {publishMessageAck} -#define PUBLISH_MESSAGE_ACK 38 -// {publishPin PinData} -#define PUBLISH_PIN 39 -// {publishPinArray PinData[]} -#define PUBLISH_PIN_ARRAY 40 -// {publishPinDefinition PinDefinition} -#define PUBLISH_PIN_DEFINITION 41 -// {publishPulse Long} -#define PUBLISH_PULSE 42 -// {publishPulseStop Integer} -#define PUBLISH_PULSE_STOP 43 -// {publishSensorData SensorData} -#define PUBLISH_SENSOR_DATA 44 -// {publishServoEvent Integer} -#define PUBLISH_SERVO_EVENT 45 -// {publishTrigger Pin} -#define PUBLISH_TRIGGER 46 -// {pulse int int int int} -#define PULSE 47 -// {pulseStop} -#define PULSE_STOP 48 -// {read int} -#define READ 49 -// {releaseI2cDevice I2CControl int int} -#define RELEASE_I2C_DEVICE 50 -// {sensorActivate SensorControl Object[]} -#define SENSOR_ACTIVATE 51 -// {sensorDeactivate SensorControl} -#define SENSOR_DEACTIVATE 52 -// {sensorPollingStart String} -#define SENSOR_POLLING_START 53 -// {sensorPollingStop String} -#define SENSOR_POLLING_STOP 54 -// {servoAttach ServoControl int} -#define SERVO_ATTACH 55 -// {servoDetach ServoControl} -#define SERVO_DETACH 56 -// {servoSetMaxVelocity ServoControl} -#define SERVO_SET_MAX_VELOCITY 57 -// {servoSetVelocity ServoControl} -#define SERVO_SET_VELOCITY 58 -// {servoSweepStart ServoControl} -#define SERVO_SWEEP_START 59 -// {servoSweepStop ServoControl} -#define SERVO_SWEEP_STOP 60 -// {servoWrite ServoControl} -#define SERVO_WRITE 61 -// {servoWriteMicroseconds ServoControl int} -#define SERVO_WRITE_MICROSECONDS 62 -// {setBoardMegaADK} -#define SET_BOARD_MEGA_ADK 63 -// {setDebounce int} -#define SET_DEBOUNCE 64 -// {setDebug boolean} -#define SET_DEBUG 65 -// {setDigitalTriggerOnly Boolean} -#define SET_DIGITAL_TRIGGER_ONLY 66 -// {setPWMFrequency Integer Integer} -#define SET_PWMFREQUENCY 67 -// {setSampleRate int} -#define SET_SAMPLE_RATE 68 -// {setSerialRate int} -#define SET_SERIAL_RATE 69 -// {setTrigger int int int} -#define SET_TRIGGER 70 -// {softReset} -#define SOFT_RESET 71 -// {write int int} -#define WRITE 72 -///// INO GENERATED DEFINITION END ////// - - /******************************************************************* * serial protocol functions */ #define MAGIC_NUMBER 170 // 10101010 +#define MAX_MSG_SIZE 64 + + +// < publishMRLCommError/str errorMsg +#define PUBLISH_MRLCOMM_ERROR 1 +// > getBoardInfo +#define GET_BOARD_INFO 2 +// < publishBoardInfo/version/boardType +#define PUBLISH_BOARD_INFO 3 +// > enableBoardStatus/bool enabled +#define ENABLE_BOARD_STATUS 4 +// > enablePin/address/type/b16 rate +#define ENABLE_PIN 5 +// > setDebug/bool enabled +#define SET_DEBUG 6 +// > setSerialRate/b32 rate +#define SET_SERIAL_RATE 7 +// > softReset +#define SOFT_RESET 8 +// > enableAck/bool enabled +#define ENABLE_ACK 9 +// < publishAck/function +#define PUBLISH_ACK 10 +// > enableHeartbeat/bool enabled +#define ENABLE_HEARTBEAT 11 +// > heartbeat +#define HEARTBEAT 12 +// < publishHeartbeat +#define PUBLISH_HEARTBEAT 13 +// > echo/bu32 sInt +#define ECHO 14 +// < publishEcho/bu32 sInt +#define PUBLISH_ECHO 15 +// > controllerAttach/serialPort +#define CONTROLLER_ATTACH 16 +// > customMsg/[] msg +#define CUSTOM_MSG 17 +// < publishCustomMsg/[] msg +#define PUBLISH_CUSTOM_MSG 18 +// > deviceDetach/deviceId +#define DEVICE_DETACH 19 +// > i2cBusAttach/deviceId/i2cBus +#define I2C_BUS_ATTACH 20 +// > i2cRead/deviceId/deviceAddress/size +#define I2C_READ 21 +// > i2cWrite/deviceId/deviceAddress/[] data +#define I2C_WRITE 22 +// > i2cWriteRead/deviceId/deviceAddress/readSize/writeValue +#define I2C_WRITE_READ 23 +// < publishI2cData/deviceId/[] data +#define PUBLISH_I2C_DATA 24 +// > neoPixelAttach/deviceId/pin/b32 numPixels +#define NEO_PIXEL_ATTACH 25 +// > neoPixelSetAnimation/deviceId/animation/red/green/blue/b16 speed +#define NEO_PIXEL_SET_ANIMATION 26 +// > neoPixelWriteMatrix/deviceId/[] buffer +#define NEO_PIXEL_WRITE_MATRIX 27 +// > analogWrite/pin/value +#define ANALOG_WRITE 28 +// > digitalWrite/pin/value +#define DIGITAL_WRITE 29 +// > disablePin/pin +#define DISABLE_PIN 30 +// > disablePins +#define DISABLE_PINS 31 +// > pinMode/pin/mode +#define PIN_MODE 32 +// < publishAttachedDevice/deviceId/str deviceName +#define PUBLISH_ATTACHED_DEVICE 33 +// < publishBoardStatus/b16 microsPerLoop/b16 sram/[] deviceSummary +#define PUBLISH_BOARD_STATUS 34 +// < publishDebug/str debugMsg +#define PUBLISH_DEBUG 35 +// < publishPinArray/[] data +#define PUBLISH_PIN_ARRAY 36 +// > setTrigger/pin/triggerValue +#define SET_TRIGGER 37 +// > setDebounce/pin/delay +#define SET_DEBOUNCE 38 +// > servoAttach/deviceId/pin/initPos/b16 initVelocity +#define SERVO_ATTACH 39 +// > servoEnablePwm/deviceId/pin +#define SERVO_ENABLE_PWM 40 +// > servoDisablePwm/deviceId +#define SERVO_DISABLE_PWM 41 +// > servoSetMaxVelocity/deviceId/b16 maxVelocity +#define SERVO_SET_MAX_VELOCITY 42 +// > servoSetVelocity/deviceId/b16 velocity +#define SERVO_SET_VELOCITY 43 +// > servoSweepStart/deviceId/min/max/step +#define SERVO_SWEEP_START 44 +// > servoSweepStop/deviceId +#define SERVO_SWEEP_STOP 45 +// > servoWrite/deviceId/target +#define SERVO_WRITE 46 +// > servoWriteMicroseconds/deviceId/b16 ms +#define SERVO_WRITE_MICROSECONDS 47 +// > serialAttach/deviceId/relayPin +#define SERIAL_ATTACH 48 +// > serialRelay/deviceId/[] data +#define SERIAL_RELAY 49 +// < publishSerialData/deviceId/[] data +#define PUBLISH_SERIAL_DATA 50 +// > ultrasonicSensorAttach/deviceId/triggerPin/echoPin +#define ULTRASONIC_SENSOR_ATTACH 51 +// > ultrasonicSensorStartRanging/deviceId/b32 timeout +#define ULTRASONIC_SENSOR_START_RANGING 52 +// > ultrasonicSensorStopRanging/deviceId +#define ULTRASONIC_SENSOR_STOP_RANGING 53 +// < publishUltrasonicSensorData/deviceId/b16 echoTime +#define PUBLISH_ULTRASONIC_SENSOR_DATA 54 + + + +/******************************************************************* + * BOARD TYPE + */ +#define BOARD_TYPE_ID_UNKNOWN 0 +#define BOARD_TYPE_ID_MEGA 1 +#define BOARD_TYPE_ID_UNO 2 + +#if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_ADK) + #define BOARD BOARD_TYPE_ID_MEGA +#elif defined(ARDUINO_AVR_UNO) + #define BOARD BOARD_TYPE_ID_UNO +#else + #define BOARD BOARD_TYPE_ID_UNKNOWN +#endif - -/******************************************************************* - * BOARD TYPE - */ -#define BOARD_TYPE_ID_UNKNOWN 0 -#define BOARD_TYPE_ID_MEGA 1 -#define BOARD_TYPE_ID_UNO 2 - -#if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_ADK) - #define BOARD BOARD_TYPE_ID_MEGA -#elif defined(ARDUINO_AVR_UNO) - #define BOARD BOARD_TYPE_ID_UNO -#else - #define BOARD BOARD_TYPE_ID_UNKNOWN -#endif - #endif diff --git a/Device.cpp b/Device.cpp index 4e77502..519ecc0 100644 --- a/Device.cpp +++ b/Device.cpp @@ -1,16 +1,8 @@ +#include "Msg.h" #include "Device.h" -Device::Device(int deviceType) { +Device::Device(byte deviceId, byte deviceType) { + id = deviceId; type = deviceType; + msg = Msg::getInstance(); } - -void Device::attachDevice() { - id = nextDeviceId; - nextDeviceId++; -} - -int Device::nextDeviceId=1; // device 0 is Arduino - -bool Device::deviceAttach(unsigned char[], int) { - return false; -} diff --git a/Device.h b/Device.h index cd37aba..1f86c06 100644 --- a/Device.h +++ b/Device.h @@ -24,14 +24,16 @@ // TODO: consider rename to DEVICE_TYPE_UNKNOWN ? currently this isn't called anywhere #define DEVICE_TYPE_NOT_FOUND 0 -#define DEVICE_TYPE_ARDUINO 1 +#define DEVICE_TYPE_ARDUINO 1 #define DEVICE_TYPE_ULTRASONIC 4 #define DEVICE_TYPE_STEPPER 5 #define DEVICE_TYPE_MOTOR 6 #define DEVICE_TYPE_SERVO 7 #define DEVICE_TYPE_I2C 8 #define DEVICE_TYPE_NEOPIXEL 9 +#define DEVICE_TYPE_SERIAL 10 +class Msg; /** * GLOBAL DEVICE TYPES END @@ -40,22 +42,28 @@ class Device { public: - Device(int deviceType); + // deviceId is supplied by a parameter in an 'attach' message + // deviceType is supplied by the device class as a form of runtime + // class identification (rtti) + Device(byte deviceId, byte deviceType); virtual ~Device(){ // default destructor for the device class. // destructor is set as virtual to call the destructor of the subclass. // destructor should be done in the subclass level } + int id; // the all important id of the sensor - equivalent to the "name" - used in callbacks int type; // what type of device is this? int state; // state - single at the moment to handle all the finite states of the sensors (todo maybe this moves into the subclasses?) - // GroG - I think its good here - a uniform state description across all devices is if they are DEVICE_STATE_ACTIVE or DEVICE_STATE_DEACTIVE - // subclasses can/should define their os substate - eg ULTRASONIC_STATE_WAITING_PULSE etc.. virtual void update() {}; // all devices must implement this to update their state. // the universal attach - follows Java-Land Controller.deviceAttach method - virtual bool deviceAttach(unsigned char[], int); - static int nextDeviceId; + // virtual bool deviceAttach(const unsigned char[], const int); + + // Msg is the generated interface for all communication + Msg* msg; + protected: + void attachDevice(); }; diff --git a/LinkedList.cpp b/LinkedList.cpp index f44f021..9015069 100644 --- a/LinkedList.cpp +++ b/LinkedList.cpp @@ -2,7 +2,6 @@ #define LinkedList_cpp #include "LinkedList.h" -#include "Arduino.h" // Initialize LinkedList with false values template diff --git a/LinkedList.h b/LinkedList.h index ab3ee78..e5b2680 100644 --- a/LinkedList.h +++ b/LinkedList.h @@ -1,74 +1,76 @@ -/* - LinkedList.h - V1.1 - Generic LinkedList implementation - Works better with FIFO, because LIFO will need to - search the entire List to find the last one; - For instructions, go to https://github.com/ivanseidel/LinkedList - Created by Ivan Seidel Gomes, March, 2013. - Released into the public domain. -*/ - -#ifndef LinkedList_h -#define LinkedList_h - -template -struct ListNode -{ - T data; - ListNode *next; -}; - -template -class LinkedList{ - -protected: - int _size; - ListNode *root; - ListNode *last; - // Helps "get" method, by saving last position - ListNode *lastNodeGot; - int lastIndexGot; - // isCached should be set to FALSE - // everytime the list suffer changes - bool isCached; - ListNode* getNode(int id); - -public: - LinkedList(); - ~LinkedList(); - /* Returns current size of LinkedList */ - virtual int size(); - /* Adds a T object in the specified index; - Unlink and link the LinkedList correcly; - Increment _size */ - virtual bool add(int index, T); - /* Adds a T object in the end of the LinkedList; - Increment _size; */ - virtual bool add(T); - /* Adds a T object in the start of the LinkedList; - Increment _size; */ - virtual bool unshift(T); - /* Set the object at index, with T; - Increment _size; */ - virtual bool set(int index, T); - /* Remove object at index; - If index is not reachable, returns false; - else, decrement _size */ - virtual T remove(int index); - /* Remove last object; */ - virtual T pop(); - /* Remove first object; */ - virtual T shift(); - /* Get the index'th element on the list; - Return Element if accessible, - else, return false; */ - virtual T get(int index); - /* Clear the entire array */ - virtual void clear(); - virtual ListNode* getRoot(); -}; - -#include "LinkedList.cpp" - -#endif - +/* + LinkedList.h - V1.1 - Generic LinkedList implementation + Works better with FIFO, because LIFO will need to + search the entire List to find the last one; + For instructions, go to https://github.com/ivanseidel/LinkedList + Created by Ivan Seidel Gomes, March, 2013. + Released into the public domain. +*/ + +#ifndef LinkedList_h +#define LinkedList_h + +#include + +template +struct ListNode +{ + T data; + ListNode *next; +}; + +template +class LinkedList{ + +protected: + int _size; + ListNode *root; + ListNode *last; + // Helps "get" method, by saving last position + ListNode *lastNodeGot; + int lastIndexGot; + // isCached should be set to FALSE + // everytime the list suffer changes + bool isCached; + ListNode* getNode(int id); + +public: + LinkedList(); + ~LinkedList(); + /* Returns current size of LinkedList */ + virtual int size(); + /* Adds a T object in the specified index; + Unlink and link the LinkedList correcly; + Increment _size */ + virtual bool add(int index, T); + /* Adds a T object in the end of the LinkedList; + Increment _size; */ + virtual bool add(T); + /* Adds a T object in the start of the LinkedList; + Increment _size; */ + virtual bool unshift(T); + /* Set the object at index, with T; + Increment _size; */ + virtual bool set(int index, T); + /* Remove object at index; + If index is not reachable, returns false; + else, decrement _size */ + virtual T remove(int index); + /* Remove last object; */ + virtual T pop(); + /* Remove first object; */ + virtual T shift(); + /* Get the index'th element on the list; + Return Element if accessible, + else, return false; */ + virtual T get(int index); + /* Clear the entire array */ + virtual void clear(); + virtual ListNode* getRoot(); +}; + +#include "LinkedList.cpp" + +#endif + diff --git a/MRLComm.ino b/MRLComm.ino index 68c6a40..a2872f0 100644 --- a/MRLComm.ino +++ b/MRLComm.ino @@ -1,53 +1,52 @@ /** -* MRLComm.c -* ----------------- -* This file is part of MyRobotLab. -* (myrobotlab.org) -* -* Enjoy ! -* @authors -* GroG -* Kwatters -* Mats -* calamity -* and many others... -* -* MRL Protocol definition -* ----------------- -* MAGIC_NUMBER|NUM_BYTES|FUNCTION|DATA0|DATA1|....|DATA(N) -* NUM_BYTES - is the number of bytes after NUM_BYTES to the end -* -* more info - http://myrobotlab.org/content/myrobotlab-api -* -* General Concept -* ----------------- -* Arduino is a slave process to MyRobotLab Arduino Service - this file receives -* commands and sends back data. -* Refactoring has made MRLComm.c far more general -* there are only 2 "types" of things - controllers and pins - or writers and readers -* each now will have sub-types -* -* Controllers -* ----------------- -* digital pins, pwm, pwm/dir dc motors, pwm/pwm dc motors -* -* Sensors -* ----------------- -* digital polling pins, analog polling pins, range pins, oscope, trigger events -* -* Combination -* ----------------- -* pingdar, non-blocking pulsin -* -* Requirements: MyRobotLab running on a computer & a serial connection -* -* TODO - need a method to identify type of board http://forum.arduino.cc/index.php?topic=100557.0 -* TODO - getBoardInfo() - returns board info ! -* TODO - getPinInfo() - returns pin info ! -* TODO - implement with std::vector vs linked list - https://github.com/maniacbug/StandardCplusplus/blob/master/README.md -* TODO - make MRLComm a c++ library -*/ - + * MRLComm.c + * ----------------- + * This file is part of MyRobotLab. + * (myrobotlab.org) + * + * Enjoy ! + * @authors + * GroG + * Kwatters + * Mats + * calamity + * and many others... + * + * MRL Protocol definition + * ----------------- + * MAGIC_NUMBER|NUM_BYTES|FUNCTION|DATA0|DATA1|....|DATA(N) + * NUM_BYTES - is the number of bytes after NUM_BYTES to the end + * + * more info - http://myrobotlab.org/content/myrobotlab-api + * + * General Concept + * ----------------- + * Arduino is a slave process to MyRobotLab Arduino Service - this file receives + * commands and sends back data. + * Refactoring has made MRLComm.c far more general + * there are only 2 "types" of things - controllers and pins - or writers and readers + * each now will have sub-types + * + * Controllers + * ----------------- + * digital pins, pwm, pwm/dir dc motors, pwm/pwm dc motors + * + * Sensors + * ----------------- + * digital polling pins, analog polling pins, range pins, oscope, trigger events + * + * Combination + * ----------------- + * pingdar, non-blocking pulsin + * + * Requirements: MyRobotLab running on a computer & a serial connection + * + * TODO - need a method to identify type of board http://forum.arduino.cc/index.php?topic=100557.0 + * TODO - getBoardInfo() - returns board info ! + * TODO - getPinInfo() - returns pin info ! + * TODO - implement with std::vector vs linked list - https://github.com/maniacbug/StandardCplusplus/blob/master/README.md + * TODO - make MRLComm a c++ library + */ // Included as a 3rd party arduino library from here: https://github.com/ivanseidel/LinkedList/ #include "LinkedList.h" @@ -56,7 +55,7 @@ /*********************************************************************** * GLOBAL VARIABLES * TODO - work on reducing globals and pass as parameters -*/ + */ MrlComm mrlComm; /*********************************************************************** * STANDARD ARDUINO BEGIN @@ -64,16 +63,13 @@ MrlComm mrlComm; * serial port on your arduino * * Here we default out serial port to 115.2kbps. -*/ + */ void setup() { - // TODO: the arduino service might get a few garbage bytes before we're able - // to run, we should consider some additional logic here like a "publishReset" - // publish version on startup so it's immediately available for mrl. - // TODO: see if we can purge the current serial port buffers - mrlComm.publishVersion(); - // publish the board type (uno/mega) - mrlComm.publishBoardInfo(); + Serial.begin(115200); + + // start with standard serial & rate + mrlComm.begin(Serial); } /** @@ -82,14 +78,17 @@ void setup() { * main loop any arduino sketch runs */ void loop() { - // increment how many times we've run - // TODO: handle overflow here after 32k runs, i suspect this might blow up? - mrlComm.loopCount++; - // get a command and process it from the serial port (if available.) - mrlComm.readCommand(); - // update devices - mrlComm.updateDevices(); - // send back load time and memory - mrlComm.publishBoardStatus(); + // increment how many times we've run + // TODO: handle overflow here after 32k runs, i suspect this might blow up? + mrlComm.loopCount++; + // get a command and process it from + // the serial port (if available.) + if (mrlComm.readMsg()) { + mrlComm.processCommand(); + } + // update devices + mrlComm.updateDevices(); + // send back load time and memory + mrlComm.publishBoardStatus(); } // end of big loop diff --git a/MrlCmd.cpp b/MrlCmd.cpp deleted file mode 100644 index ca0a77b..0000000 --- a/MrlCmd.cpp +++ /dev/null @@ -1,76 +0,0 @@ -#include "MrlCmd.h" - -MrlCmd::MrlCmd(int ioType){ - begin(ioType,115200); - byteCount=0; - msgSize=0; -} - -MrlCmd::~MrlCmd(){ - -} - -/** - * getCommand() - This is the main method to read new data from the serial port, - * when a full mrlcomm message is read from the serial port. - * return values: true if the serial port read a full mrlcomm command - * false if the serial port is still waiting on a command. - */ - -bool MrlCmd::readCommand(){ - // handle serial data begin - int bytesAvailable = available(); - if (bytesAvailable > 0) { - //MrlMsg::publishDebug("RXBUFF:" + String(bytesAvailable)); - // now we should loop over the available bytes .. not just read one by one. - for (int i = 0; i < bytesAvailable; i++) { - // read the incoming byte: - unsigned char newByte = read(); - //MrlMsg::publishDebug("RX:" + String(newByte)); - ++byteCount; - // checking first byte - beginning of message? - if (byteCount == 1 && newByte != MAGIC_NUMBER) { - MrlMsg::publishError(ERROR_SERIAL); - // reset - try again - byteCount = 0; - // return false; - } - if (byteCount == 2) { - // get the size of message - // todo check msg < 64 (MAX_MSG_SIZE) - if (newByte > 64) { - // TODO - send error back - byteCount = 0; - continue; // GroG - I guess we continue now vs return false on error conditions? - } - msgSize = newByte; - } - if (byteCount > 2) { - // fill in msg data - (2) headbytes -1 (offset) - ioCmd[byteCount - 3] = newByte; - } - // if received header + msg - if (byteCount == 2 + msgSize) { - // we've reach the end of the command, just return true .. we've got it - byteCount = 0; - return true; - } - } - } // if Serial.available - // we only partially read a command. (or nothing at all.) - return false; -} - - -unsigned char* MrlCmd::getIoCmd() { - return ioCmd; -} - -unsigned char MrlCmd::getIoCmd(int pos){ - return ioCmd[pos]; -} - -int MrlCmd::getMsgSize(){ - return msgSize; -} - diff --git a/MrlCmd.h b/MrlCmd.h deleted file mode 100644 index c8677ee..0000000 --- a/MrlCmd.h +++ /dev/null @@ -1,25 +0,0 @@ -#ifndef MrlCmd_h -#define MrlCmd_h - -#include "ArduinoMsgCodec.h" -#include "LinkedList.h" -#include "MrlIo.h" -#include "MrlMsg.h" - -#define MAX_MSG_SIZE 64 - -class MrlCmd : public MrlIo{ -private: - unsigned char ioCmd[MAX_MSG_SIZE]; - int byteCount; - int msgSize; -public: - MrlCmd(int ioType); - ~MrlCmd(); - bool readCommand(); - unsigned char* getIoCmd(); - unsigned char getIoCmd(int pos); - int getMsgSize(); -}; - -#endif diff --git a/MrlComm.cpp b/MrlComm.cpp index 92bd2d4..c87396d 100644 --- a/MrlComm.cpp +++ b/MrlComm.cpp @@ -1,679 +1,501 @@ -#include "MrlComm.h" - -MrlComm::MrlComm() { - softReset(); - byteCount = 0; - mrlCmd[0] = new MrlCmd(MRL_IO_SERIAL_0); - for (unsigned int i = 1; i < (sizeof(mrlCmd) / sizeof(MrlCmd*)); i++) { - mrlCmd[i] = NULL; - } - -} - -MrlComm::~MrlComm() { - for (unsigned int i = 0; i < (sizeof(mrlCmd) / sizeof(MrlCmd*)); i++) { - if (mrlCmd[i] != NULL) { - delete mrlCmd[i]; - } - } -} -/*********************************************************************** - * UTILITY METHODS BEGIN - */ -void MrlComm::softReset() { - while (deviceList.size() > 0) { - delete deviceList.pop(); - } - while (pinList.size() > 0) { - delete pinList.pop(); - } - //resetting var to default - loopCount = 0; - publishBoardStatusModulus = 10000; - enableBoardStatus = false; - Device::nextDeviceId = 1; // device 0 is Arduino - debug = false; - for (unsigned int i = 1; i < (sizeof(mrlCmd) / sizeof(MrlCmd*)); i++) { - if (mrlCmd[i] != NULL) { - mrlCmd[i]->end(); - delete mrlCmd[i]; - mrlCmd[i] = NULL; - } - } - heartbeat = false; - heartbeatEnabled = false; - lastHeartbeatUpdate = 0; - for (unsigned int i = 0; i < MAX_MSG_SIZE; i++) { - customMsg[i] = 0; - } - customMsgSize = 0; -} - -/*********************************************************************** - * PUBLISH_BOARD_STATUS - * This function updates the average time it took to run the main loop - * and reports it back with a publishBoardStatus MRLComm message - * - * TODO: avgTiming could be 0 if loadTimingModule = 0 ?! - * - * MAGIC_NUMBER|7|[loadTime long0,1,2,3]|[freeMemory int0,1] - */ -void MrlComm::publishBoardStatus() { - - // protect against a divide by zero in the division. - if (publishBoardStatusModulus == 0) { - publishBoardStatusModulus = 10000; - } - - unsigned int avgTiming = 0; - unsigned long now = micros(); - - avgTiming = (now - lastMicros) / publishBoardStatusModulus; - - // report board status - if (enableBoardStatus && (loopCount % publishBoardStatusModulus == 0)) { - - // send the average loop timing. - MrlMsg msg(PUBLISH_BOARD_STATUS); - msg.addData16(avgTiming); - msg.addData16(getFreeRam()); - msg.addData16(deviceList.size()); - msg.sendMsg(); - } - // update the timestamp of this update. - lastMicros = now; -} - -int MrlComm::getFreeRam() { - // KW: In the future the arduino might have more than an 32/64k of ram. an int might not be enough here to return. - extern int __heap_start, *__brkval; - int v; - return (int) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval); -} - -/*********************************************************************** - * PUBLISH DEVICES BEGIN - * - * All serial IO should happen here to publish a MRLComm message. - * TODO: move all serial IO into a controlled place this this below... - * TODO: create MRLCommMessage class that can just send itself! - * - */ -/** - * Publish the MRLComm message - * MAGIC_NUMBER|2|MRLCOMM_VERSION - */ -void MrlComm::publishVersion() { - MrlMsg msg(PUBLISH_VERSION); - msg.addData(MRLCOMM_VERSION); - msg.sendMsg(); -} -/** - * publishBoardInfo() - * MAGIC_NUMBER|2|PUBLISH_BOARD_INFO|BOARD - * return the board type (mega/uno) that can use in javaland for the pin layout - */ -void MrlComm::publishBoardInfo() { - MrlMsg msg(PUBLISH_BOARD_INFO); - msg.addData(BOARD); - msg.sendMsg(); -} - -/** - * Publish the acknowledgement of the command received and processed. - * MAGIC_NUMBER|2|PUBLISH_MESSAGE_ACK|FUNCTION - */ -void MrlComm::publishCommandAck(int function) { - MrlMsg msg(PUBLISH_MESSAGE_ACK); - // the function that we're ack-ing - msg.addData(function); - msg.sendMsg(); -} -/** - * PUBLISH_ATTACHED_DEVICE - * MSG STRUCTURE - * PUBLISH_ATTACHED_DEVICE | NEW_DEVICE_INDEX | NAME_STR_SIZE | NAME - * - */ -void MrlComm::publishAttachedDevice(int id, int nameSize, unsigned char* name) { - MrlMsg msg(PUBLISH_ATTACHED_DEVICE, id); - msg.addData(name, nameSize, true); - msg.sendMsg(); -} - -/*********************************************************************** - * SERIAL METHODS BEGIN - */ -void MrlComm::readCommand() { - for (unsigned int i = 0; i < (sizeof(mrlCmd) / sizeof(MrlCmd*)); i++) { - if (mrlCmd[i] != NULL) { - if (mrlCmd[i]->readCommand()) { - processCommand(i + 1); - } - } - } -} - -// This function will switch the current command and call -// the associated function with the command -/** - * processCommand() - once the main loop has read an mrlcomm message from the - * serial port, this method will be called. - */ -void MrlComm::processCommand(int ioType) { - unsigned char* ioCmd = mrlCmd[ioType - 1]->getIoCmd(); - if (ioType != MRL_IO_SERIAL_0) { - MrlMsg msg = MrlMsg(MSG_ROUTE); - msg.addData(ioType); - msg.addData(ioCmd, mrlCmd[ioType - 1]->getMsgSize()); - msg.sendMsg(); - // MrlMsg::publishDebug("not from Serial, ioType" + String(ioType)); - return; - } - // FIXME - all case X: should have scope operator { } ! - // MrlMsg::publishDebug("not from Serial:" + String(ioCmd[0])); - switch (ioCmd[0]) { - // === system pass through begin === - case DIGITAL_WRITE: - digitalWrite(ioCmd[1], ioCmd[2]); - break; - case ANALOG_WRITE: { - analogWrite(ioCmd[1], ioCmd[2]); - break; - } - case PIN_MODE: { - pinMode(ioCmd[1], ioCmd[2]); - break; - } - case SERVO_ATTACH: { - int pin = ioCmd[2]; - if (debug) - MrlMsg::publishDebug("SERVO_ATTACH " + String(pin)); - MrlServo* servo = (MrlServo*) getDevice(ioCmd[1]); - servo->attach(pin); - if (debug) - MrlMsg::publishDebug(F("SERVO_ATTACHED")); - break; - } - case SERVO_SWEEP_START: - //startSweep(min,max,step) - ((MrlServo*) getDevice(ioCmd[1]))->startSweep(ioCmd[2], ioCmd[3], - ioCmd[4]); - break; - case SERVO_SWEEP_STOP: - ((MrlServo*) getDevice(ioCmd[1]))->stopSweep(); - break; - case SERVO_WRITE: - ((MrlServo*) getDevice(ioCmd[1]))->servoWrite(ioCmd[2]); - break; - case SERVO_WRITE_MICROSECONDS: - ((MrlServo*) getDevice(ioCmd[1]))->servoWriteMicroseconds(MrlMsg::toInt(ioCmd, 2)); - break; - case SERVO_DETACH: { - if (debug) - MrlMsg::publishDebug("SERVO_DETACH " + String(ioCmd[1])); - ((MrlServo*) getDevice(ioCmd[1]))->detach(); - if (debug) - MrlMsg::publishDebug("SERVO_DETACHED"); - break; - } - case ENABLE_BOARD_STATUS: - enableBoardStatus = true; - publishBoardStatusModulus = (unsigned int) MrlMsg::toInt(ioCmd, 1); - if (debug) - MrlMsg::publishDebug( - "modulus is " + String(publishBoardStatusModulus)); - break; - - // ENABLE_PIN_EVENTS | ADDRESS | PIN TYPE 0 = DIGITAL | 1 = ANALOG - case ENABLE_PIN: { - int address = ioCmd[1]; - int type = ioCmd[2]; - int rate = MrlMsg::toInt(ioCmd, 3); - // don't add it twice - for (int i = 0; i < pinList.size(); ++i) { - Pin* pin = pinList.get(i); - if (pin->address == address) { - // TODO already exists error? - break; - } - } - - if (type == DIGITAL) { - pinMode(address, INPUT); - } - Pin* p = new Pin(address, type, rate); - p->lastUpdate = 0; - pinList.add(p); - break; - } - case DISABLE_PIN: { - int address = ioCmd[1]; - ListNode* node = pinList.getRoot(); - int index = 0; - while (node != NULL) { - if (node->data->address == address) { - delete node->data; - pinList.remove(index); - break; - } - node = node->next; - index++; - } - break; - } - - case DISABLE_PINS: { - while (pinList.size() > 0) { - delete pinList.pop(); - } - break; - } - case DISABLE_BOARD_STATUS: - enableBoardStatus = false; - break; - case SET_PWMFREQUENCY: - setPWMFrequency(ioCmd[1], ioCmd[2]); - break; - case PULSE: - //((MrlPulse*)getDevice(ioCmd[1]))->pulse(ioCmd); - break; - case PULSE_STOP: - //((MrlPulse*)getDevice(ioCmd[1]))->pulseStop(); - break; - case SET_TRIGGER: - //setTrigger(); - break; - case SET_DEBOUNCE: - //setDebounce(); - break; - case SET_DIGITAL_TRIGGER_ONLY: - //setDigitalTriggerOnly(); - break; - case SET_SERIAL_RATE: - setSerialRate(); - break; - case GET_VERSION: - publishVersion(); - break; - case SET_SAMPLE_RATE: - //setSampleRate(); - break; - case SOFT_RESET: - softReset(); - break; - case SENSOR_POLLING_START: - //sensorPollingStart(); - break; - case DEVICE_ATTACH: - deviceAttach(ioCmd); - break; - case DEVICE_DETACH: - deviceDetach(ioCmd[1]); - break; - case SENSOR_POLLING_STOP: - //sensorPollingStop(); - break; - // Start of i2c read and writes - case I2C_READ: - ((MrlI2CBus*) getDevice(ioCmd[1]))->i2cRead(ioCmd); - break; - case I2C_WRITE: - ((MrlI2CBus*) getDevice(ioCmd[1]))->i2cWrite(ioCmd); - break; - case I2C_WRITE_READ: - ((MrlI2CBus*) getDevice(ioCmd[1]))->i2cWriteRead(ioCmd); - break; - case SET_DEBUG: - debug = ioCmd[1]; - if (debug) { - MrlMsg::publishDebug(F("Debug logging enabled.")); - } - break; - case PUBLISH_BOARD_INFO: - publishBoardInfo(); - break; - case NEO_PIXEL_WRITE_MATRIX: - ((MrlNeopixel*) getDevice(ioCmd[1]))->neopixelWriteMatrix(ioCmd); - break; - case NEO_PIXEL_SET_ANIMATION: - ((MrlNeopixel*) getDevice(ioCmd[1]))->setAnimation(ioCmd+2); - break; - case CONTROLLER_ATTACH: - mrlCmd[ioCmd[1] - 1] = new MrlCmd(ioCmd[1]); - break; - case MSG_ROUTE: { - MrlMsg msg(ioCmd[2]); - msg.addData(ioCmd + 3, mrlCmd[ioType - 1]->getMsgSize() - 3); - msg.begin(ioCmd[1], 115200); - msg.sendMsg(); - break; - } - case SERVO_SET_MAX_VELOCITY: { - ((MrlServo*) getDevice(ioCmd[1]))->setMaxVelocity(MrlMsg::toInt(ioCmd,3)); - break; - } - case SERVO_SET_VELOCITY: { - ((MrlServo*) getDevice(ioCmd[1]))->setVelocity(MrlMsg::toInt(ioCmd,3)); - break; - } - case HEARTBEAT: { - heartbeatEnabled = true; - break; - } - case CUSTOM_MSG: { - for (byte i = 0; i < ioCmd[1] && customMsgSize < 64; i++) { - customMsg[customMsgSize] = ioCmd[i+2]; - customMsgSize++; - } - break; - } - default: - MrlMsg::publishError(ERROR_UNKOWN_CMD); - break; - } // end switch - // ack that we got a command (should we ack it first? or after we process the command?) - heartbeat = true; - lastHeartbeatUpdate = millis(); - publishCommandAck(ioCmd[0]); - // reset command buffer to be ready to receive the next command. - // KW: we should only need to set the byteCount back to zero. clearing this array is just for safety sake i guess? - // GR: yup - //memset(ioCmd, 0, sizeof(ioCmd)); - //byteCount = 0; -} // process Command -/*********************************************************************** - * CONTROL METHODS BEGIN - * These methods map one to one for each MRLComm command that comes in. - * - * TODO - add text api - */ - -// SET_PWMFREQUENCY -void MrlComm::setPWMFrequency(int address, int prescalar) { - // FIXME - different boards have different timers - // sets frequency of pwm of analog - // FIXME - us ifdef appropriate uC which - // support these clocks TCCR0B - // int clearBits = 0x07; - // if (address == 0x25) { - // TCCR0B &= ~clearBits; - // TCCR0B |= prescalar; - // } else if (address == 0x2E) { - // TCCR1B &= ~clearBits; - // TCCR1B |= prescalar; - // } else if (address == 0xA1) { - // TCCR2B &= ~clearBits; - // TCCR2B |= prescalar; - // } -} - -// SET_SERIAL_RATE -void MrlComm::setSerialRate() { - //mrlCmd->end(); - //mrlCmd->begin(MRL_IO_SERIAL_0,mrlCmd->getIoCmd(1)); -} - -/********************************************************************** - * ATTACH DEVICES BEGIN - * - *
- *
- * MSG STRUCTURE
- *                    |<-- ioCmd starts here                                        |<-- config starts here
- * MAGIC_NUMBER|LENGTH|ATTACH_DEVICE|DEVICE_TYPE|NAME_SIZE|NAME .... (N)|CONFIG_SIZE|DATA0|DATA1 ...|DATA(N)
- *
- * ATTACH_DEVICE - this method id
- * DEVICE_TYPE - the mrlcomm device type we are attaching
- * NAME_SIZE - the size of the name of the service of the device we are attaching
- * NAME .... (N) - the name data
- * CONFIG_SIZE - the size of the folloing config
- * DATA0|DATA1 ...|DATA(N) - config data
- *
- *
- * - * Device types are defined in org.myrobotlab.service.interface.Device - * TODO crud Device operations create remove (update not needed?) delete - * TODO probably need getDeviceId to decode id from Arduino.java - because if its - * implemented as a ptr it will be 4 bytes - if it is a generics id - * it could be implemented with 1 byte - */ -void MrlComm::deviceAttach(unsigned char* ioCmd) { - // TOOD:KW check free memory to see if we can attach a new device. o/w return an error! - // we're creating a new device. auto increment it - // TODO: consider what happens if we overflow on this auto-increment. (very unlikely. but possible) - // we want to echo back the name - // and send the config in a nice neat package to - // the attach method which creates the device - //unsigned char* ioCmd = mrlCmd->getIoCmd(); - int nameSize = ioCmd[2]; - - // get config size - int configSizePos = 3 + nameSize; - int configSize = ioCmd[configSizePos]; - int configPos = configSizePos + 1; - config = ioCmd + configPos; - // MAKE NOTE: I've chosen to have config & configPos globals - // this is primarily to avoid the re-allocation/de-allocation of the config buffer - // but part of me thinks it should be a local var passed into the function to avoid - // the dangers of global var ... fortunately Arduino is single threaded - // It also makes sense to pass in config on the constructor of a new device - // based on device type - "you inflate the correct device with the correct config" - // but I went on the side of globals & hopefully avoiding more memory management and fragmentation - // CAL: change config to a pointer in ioCmd (save some memory) so config[0] = ioCmd[configPos] - - int type = ioCmd[1]; - Device* devicePtr = 0; - // KW: remove this switch statement by making "attach(int[]) a virtual method on the device base class. - // perhaps a factory to produce the devicePtr based on the deviceType.. - // currently the attach logic is embeded in the constructors .. maybe we can make that a more official - // lifecycle for the devices.. - // check out the make_stooge method on https://sourcemaking.com/design_patterns/factory_method/cpp/1 - // This is really how we should do this. (methinks) - // Cal: the make_stooge method is certainly more C++ like, but essentially do the same thing as we do, - // it just move this big switch to another place - - // GR: I agree .. "attach" should be a universal concept of devices, yet it does not need to be implmented - // in the constructor .. so I'm for making a virtualized attach, but just like Java-Land the attach - // needs to have size sent in with the config since it can be variable array - // e.g. attach(int[] config, configSize) - - switch (type) { - case DEVICE_TYPE_ARDUINO: { - //devicePtr = attachAnalogPinArray(); - break; - } - /* - case SENSOR_TYPE_DIGITAL_PIN_ARRAY: { - //devicePtr = attachDigitalPinArray(); - break; - } - case SENSOR_TYPE_PULSE: { - //devicePtr = attachPulse(); - break; - } - */ - case DEVICE_TYPE_ULTRASONIC: { - //devicePtr = attachUltrasonic(); - break; - } - case DEVICE_TYPE_STEPPER: { - //devicePtr = attachStepper(); - break; - } - case DEVICE_TYPE_MOTOR: { - //devicePtr = attachMotor(); - break; - } - case DEVICE_TYPE_SERVO: { - devicePtr = new MrlServo(); //no need to pass the type here - break; - } - case DEVICE_TYPE_I2C: { - devicePtr = new MrlI2CBus(); - break; - } - case DEVICE_TYPE_NEOPIXEL: { - devicePtr = new MrlNeopixel(); - break; - } - default: { - // TODO: publish error message - MrlMsg::publishDebug(F("Unknown Message Type.")); - break; - } - } - - // if we have a device - then attach it and call its attach method with config passed in - // and send back a publishedAttachedDevice with its name - so Arduino-Java land knows - // it was successfully attached - if (devicePtr) { - if (devicePtr->deviceAttach(config, configSize)) { - addDevice(devicePtr); - publishAttachedDevice(devicePtr->id, nameSize, ioCmd + 3); - } else { - MrlMsg::publishError(ERROR_UNKOWN_SENSOR, F("DEVICE not attached")); - delete devicePtr; - } - } -} -/** - * deviceDetach - get the device - * if it exists delete it and remove it from the deviceList - */ -void MrlComm::deviceDetach(int id) { - ListNode* node = deviceList.getRoot(); - int index = 0; - while (node != NULL) { - if (node->data->id == id) { - delete node->data; - deviceList.remove(index); - break; - } - node = node->next; - index++; - } -} -/** - * getDevice - this method will look up a device by it's id in the device list. - * it returns null if the device isn't found. - */ -Device* MrlComm::getDevice(int id) { - ListNode* node = deviceList.getRoot(); - while (node != NULL) { - if (node->data->id == id) { - return node->data; - } - node = node->next; - } - MrlMsg::publishError(ERROR_DOES_NOT_EXIST); - return NULL; //returning a NULL ptr can cause runtime error - // you'll still get a runtime error if any field, member or method not - // defined is accessed -} -/** - * This adds a device to the current set of active devices in the deviceList. - * - * FIXME - G: I think dynamic array would work better - * at least for the deviceList - * TODO: KW: i think it's pretty dynamic now. - * G: the nextDeviceId & Id leaves something to be desired - and the "index" does - * not spin through the deviceList to find it .. a dynamic array of pointers would only - * expand if it could not accomidate the current number of devices, when a device was - * removed - the slot could be re-used by the next device request - */ -void MrlComm::addDevice(Device* device) { - deviceList.add(device); -} - -/*********************************************************************** - * UPDATE DEVICES BEGIN - * updateDevices updates each type of device put on the device list - * depending on their type. - * This method processes each loop. Typically this "back-end" - * processing will read data from pins, or change states of non-blocking - * pulses, or possibly regulate a motor based on pid values read from - * pins - */ -void MrlComm::updateDevices() { - - // update self - the first device which - // is type Arduino - update(); - - ListNode* node = deviceList.getRoot(); - // iterate through our device list and call update on them. - while (node != NULL) { - node->data->update(); - node = node->next; - } -} - -/*********************************************************************** - * UPDATE BEGIN - * updates self - reads from the pinList both analog and digital - * sends pin data back - */ -void MrlComm::update() { - unsigned long now = millis(); - if ((now - lastHeartbeatUpdate > 1000) && heartbeatEnabled) { - if (!heartbeat) { - softReset(); - return; - } - heartbeat = false; - lastHeartbeatUpdate = now; - } - if (pinList.size() > 0) { - // device id for our Arduino is always 0 - MrlMsg msg(PUBLISH_SENSOR_DATA, 0); // the callback id - - // size of payload - 1 byte for address + 2 bytes per pin read - // this is an optimization in that we send back "all" the read pin data in a - // standard 2 byte package - digital reads don't need both bytes, but the - // sending it all back in 1 msg and the simplicity is well worth it - //msg.addData(pinList.size() * 3 /* 1 address + 2 read bytes */); - msg.countData(); - msg.autoSend(57); - ListNode* node = pinList.getRoot(); - // iterate through our device list and call update on them. - unsigned int msgSent = 0; - while (node != NULL) { - Pin* pin = node->data; - if (pin->rate == 0 || (now > pin->lastUpdate + (1000 / pin->rate))) { - pin->lastUpdate = now; - // TODO: moe the analog read outside of thie method and pass it in! - if (pin->type == ANALOG) { - pin->value = analogRead(pin->address); - } else { - pin->value = digitalRead(pin->address); - } - - // loading both analog & digital data - msg.addData(pin->address); // 1 byte - msg.addData16(pin->value); // 2 bytes - msgSent++; - } - node = node->next; - } - if (msgSent) msg.sendMsg(); - } -} - -unsigned int MrlComm::getCustomMsg() { - if (customMsgSize == 0) { - return 0; - } - int retval = customMsg[0]; - for (int i = 0; i < customMsgSize-1; i++) { - customMsg[i] = customMsg[i+1]; - } - customMsg[customMsgSize] = 0; - customMsgSize--; - return retval; -} - -int MrlComm::getCustomMsgSize() { - return customMsgSize; -} - +#include "Msg.h" +#include "Device.h" +#include "Pin.h" +#include "MrlNeoPixel.h" +#include "Servo.h" +#include "MrlServo.h" +#include "MrlI2cBus.h" +#include "MrlUltrasonicSensor.h" +#include "LinkedList.h" +#include "MrlComm.h" + +/** +
+ Schema Type Conversions
+
+ Schema      ARDUINO					Java							Range
+ none		byte/unsigned char		int (cuz Java byte bites)		1 byte - 0 to 255
+ boolean	boolean					boolean							0 1
+ b16		int						int (short)						2 bytes	-32,768 to 32,767
+ b32		long					int								4 bytes -2,147,483,648 to 2,147,483, 647
+ bu32		unsigned long			long							0 to 4,294,967,295
+ str		char*, size				String							variable length
+ []			byte[], size			int[]							variable length
+ 
+ */ + +MrlComm::MrlComm() { + softReset(); + msg = Msg::getInstance(this); +} + +MrlComm::~MrlComm() { +} + +/*********************************************************************** + * PUBLISH_BOARD_STATUS + * This function updates the average time it took to run the main loop + * and reports it back with a publishBoardStatus MRLComm message + * + * TODO: avgTiming could be 0 if loadTimingModule = 0 ?! + * + * MAGIC_NUMBER|7|[loadTime long0,1,2,3]|[freeMemory int0,1] + */ +void MrlComm::publishBoardStatus() { + + // protect against a divide by zero in the division. + if (publishBoardStatusModulus == 0) { + publishBoardStatusModulus = 10000; + } + + unsigned int avgTiming = 0; + unsigned long now = micros(); + + avgTiming = (now - lastMicros) / publishBoardStatusModulus; + + // report board status + if (boardStatusEnabled && (loopCount % publishBoardStatusModulus == 0)) { + byte deviceSummary[deviceList.size() * 2]; + for (int i = 0; i < deviceList.size(); ++i) { + deviceSummary[i] = deviceList.get(i)->id; + deviceSummary[i + 1] = deviceList.get(i)->type; + } + msg->publishBoardStatus(avgTiming, getFreeRam(), deviceSummary, deviceList.size() * 2); + } + // update the timestamp of this update. + lastMicros = now; +} + +int MrlComm::getFreeRam() { + // KW: In the future the arduino might have more than an 32/64k of ram. an int might not be enough here to return. + extern int __heap_start, *__brkval; + int v; + return (int) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval); +} + +/** + * getDevice - this method will look up a device by it's id in the device list. + * it returns null if the device isn't found. + */ +Device* MrlComm::getDevice(int id) { + ListNode* node = deviceList.getRoot(); + while (node != NULL) { + if (node->data->id == id) { + return node->data; + } + node = node->next; + } + + msg->publishError(F("device does not exist")); + return NULL; //returning a NULL ptr can cause runtime error + // you'll still get a runtime error if any field, member or method not + // defined is accessed +} +/** + * This adds a device to the current set of active devices in the deviceList. + * + * FIXME - G: I think dynamic array would work better + * at least for the deviceList + * TODO: KW: i think it's pretty dynamic now. + * G: the nextDeviceId & Id leaves something to be desired - and the "index" does + * not spin through the deviceList to find it .. a dynamic array of pointers would only + * expand if it could not accomidate the current number of devices, when a device was + * removed - the slot could be re-used by the next device request + */ +Device* MrlComm::addDevice(Device* device) { + deviceList.add(device); + return device; +} + +/*********************************************************************** + * UPDATE DEVICES BEGIN + * updateDevices updates each type of device put on the device list + * depending on their type. + * This method processes each loop. Typically this "back-end" + * processing will read data from pins, or change states of non-blocking + * pulses, or possibly regulate a motor based on pid values read from + * pins + */ +void MrlComm::updateDevices() { + + // update self - the first device which + // is type Arduino + update(); + + ListNode* node = deviceList.getRoot(); + // iterate through our device list and call update on them. + while (node != NULL) { + node->data->update(); + node = node->next; + } +} + +/*********************************************************************** + * UPDATE BEGIN + * updates self - reads from the pinList both analog and digital + * sends pin data back + */ +void MrlComm::update() { + unsigned long now = millis(); + if ((now - lastHeartbeatUpdate > 1000) && heartbeatEnabled) { + softReset(); + lastHeartbeatUpdate = now; + return; + } + + if (pinList.size() > 0) { + + // size of payload - 1 byte for address + 2 bytes per pin read + // this is an optimization in that we send back "all" the read pin data in a + // standard 2 byte package - digital reads don't need both bytes, but the + // sending it all back in 1 msg and the simplicity is well worth it + // msg.addData(pinList.size() * 3 /* 1 address + 2 read bytes */); + + ListNode* node = pinList.getRoot(); + // iterate through our device list and call update on them. + unsigned int dataCount = 0; + while (node != NULL) { + Pin* pin = node->data; + if (pin->rate == 0 || (now > pin->lastUpdate + (1000 / pin->rate))) { + pin->lastUpdate = now; + // TODO: move the analog read outside of this method and pass it in! + if (pin->type == ANALOG) { + pin->value = analogRead(pin->address); + } else { + pin->value = digitalRead(pin->address); + } + + // loading both analog & digital data + msg->add(pin->address); // 1 byte + msg->add16(pin->value); // 2 byte b16 value + + ++dataCount; + } + node = node->next; + } + if (dataCount) { + msg->publishPinArray(msg->getBuffer(), msg->getBufferSize()); + } + } +} + +int MrlComm::getCustomMsgSize() { + return customMsgSize; +} + +void MrlComm::processCommand() { + msg->processCommand(); + if (ackEnabled) { + msg->publishAck(1); + } +} + +void MrlComm::enableAck(bool enabled) { + ackEnabled = enabled; +} + +bool MrlComm::readMsg() { + return msg->readMsg(); +} + +void MrlComm::begin(HardwareSerial& serial) { + + // TODO: the arduino service might get a few garbage bytes before we're able + // to run, we should consider some additional logic here like a "publishReset" + // publish version on startup so it's immediately available for mrl. + // TODO: see if we can purge the current serial port buffers + + while (!serial) { + ; // wait for serial port to connect. Needed for native USB + } + + // clear serial + serial.flush(); + + msg->begin(serial); + + // send 3 boardInfos to PC to announce, + // Hi I'm an Arduino with version x, board type y, and I'm ready :) + for (int i = 0; i < 5; ++i) { + msg->publishBoardInfo(MRLCOMM_VERSION, BOARD); + serial.flush(); + } +} + +/**************************************************************** + * GENERATED METHOD INTERFACE BEGIN + * All methods signatures below this line are controlled by arduinoMsgs.schema + * The implementation contains custom logic - but the signature is generated + * + */ + +// > getBoardInfo +void MrlComm::getBoardInfo() { + msg->publishBoardInfo(MRLCOMM_VERSION, BOARD); +} + +// > echo/str name1/b8/bu32 bui32/b32 bi32/b9/str name2/[] config/bu32 bui322 +/* + void MrlComm::echo(long sInt, byte name1Size, const char*name1, byte b8, + unsigned long bui32, long bi32, byte b9, byte name2Size, + const char*name2, byte configSize, const byte*config, + unsigned long bui322) { + */ +void MrlComm::echo(unsigned long b32) { + msg->publishEcho(b32); +} + +// > controllerAttach/serialPort +// TODO - talk to calamity +void MrlComm::controllerAttach(byte serialPort) { + msg->publishDebug(String("controllerAttach " + String(serialPort))); +} + +// > customMsg/[] msg +// from PC --> loads customMsg buffer +void MrlComm::customMsg(byte msgSize, const byte*msg) { + for (byte i = 0; i < msgSize && msgSize < 64; i++) { + customMsgBuffer[i] = msg[i]; // *(msg + i); + } + customMsgSize = msgSize; +} + +/** + * deviceDetach - get the device + * if it exists delete it and remove it from the deviceList + */ +// > deviceDetach/deviceId +void MrlComm::deviceDetach(byte id) { + ListNode* node = deviceList.getRoot(); + int index = 0; + while (node != NULL) { + if (node->data->id == id) { + delete node->data; + deviceList.remove(index); + break; + } + node = node->next; + index++; + } +} + +// > disablePin/pin +void MrlComm::disablePin(byte address) { + ListNode* node = pinList.getRoot(); + int index = 0; + while (node != NULL) { + if (node->data->address == address) { + delete node->data; + pinList.remove(index); + break; + } + node = node->next; + index++; + } +} + +// > disablePins +void MrlComm::disablePins() { + while (pinList.size() > 0) { + delete pinList.pop(); + } +} + +// > enableBoardStatus +void MrlComm::enableBoardStatus(bool enabled) { + // msg->publishDebug("enableBoardStatus"); + boardStatusEnabled = enabled; +} + +// > enableHeartbeat/bool enabled +void MrlComm::enableHeartbeat(bool enabled) { + heartbeatEnabled = enabled; +} + +// > enablePin/address/type/b16 rate +void MrlComm::enablePin(byte address, byte type, int rate) { + // don't add it twice + for (int i = 0; i < pinList.size(); ++i) { + Pin* pin = pinList.get(i); + if (pin->address == address) { + // TODO already exists error? + break; + } + } + + if (type == DIGITAL) { + pinMode(address, INPUT); + } + Pin* p = new Pin(address, type, rate); + p->lastUpdate = 0; + pinList.add(p); +} + +// > heartbeat +void MrlComm::heartbeat() { + lastHeartbeatUpdate = millis(); +} + +// > i2cAttach/deviceId/i2cBus/deviceType/deviceAddress +void MrlComm::i2cAttach(byte deviceId, byte i2cBus, byte deviceType, byte deviceAddress) { + // @Mats - do you need deviceType & deviceAddress here ? + // if not we should shorten the i2cAttach parameters :) + MrlI2CBus* i2cbus = (MrlI2CBus*) addDevice(new MrlI2CBus(deviceId)); + i2cbus->attach(i2cBus); +} + +// > i2cRead/deviceId/deviceAddress/size +void MrlComm::i2cRead(byte deviceId, byte deviceAddress, byte size) { + ((MrlI2CBus*) getDevice(deviceId))->i2cRead(deviceAddress, size); +} + +// > i2cWrite/deviceId/deviceAddress/[] data +void MrlComm::i2cWrite(byte deviceId, byte deviceAddress, byte dataSize, const byte*data) { + ((MrlI2CBus*) getDevice(deviceId))->i2cWrite(deviceAddress, dataSize, data); +} + +// > i2cWriteRead/deviceId/deviceAddress/readSize/writeValue +void MrlComm::i2cWriteRead(byte deviceId, byte deviceAddress, byte readSize, byte writeValue) { + ((MrlI2CBus*) getDevice(deviceId))->i2cWriteRead(deviceAddress, readSize, writeValue); +} + +// > neoPixelAttach/pin/b16 numPixels +void MrlComm::neoPixelAttach(byte deviceId, byte pin, long numPixels) { + MrlNeopixel* neo = (MrlNeopixel*) addDevice(new MrlNeopixel(deviceId)); + neo->attach(pin, numPixels); +} + +// > neoPixelAttach/pin/b16 numPixels +void MrlComm::neoPixelSetAnimation(byte deviceId, byte animation, byte red, byte green, byte blue, int speed) { + ((MrlNeopixel*) getDevice(deviceId))->setAnimation(animation, red, green, blue, speed); +} + +// > neoPixelWriteMatrix/deviceId/[] buffer +void MrlComm::neoPixelWriteMatrix(byte deviceId, byte bufferSize, const byte*buffer) { + ((MrlNeopixel*) getDevice(deviceId))->neopixelWriteMatrix(bufferSize, buffer); +} + +// > servoAttach/deviceId/pin/targetOutput/b16 velocity +void MrlComm::servoAttach(byte deviceId, byte pin, byte targetOutput, int velocity) { + MrlServo* servo = new MrlServo(deviceId); + addDevice(servo); + // not your mama's attach - this is attaching/initializing the MrlDevice + servo->attach(pin, targetOutput, velocity); +} + +// > servoEnablePwm/deviceId/pin +void MrlComm::servoEnablePwm(byte deviceId, byte pin) { + MrlServo* servo = (MrlServo*) getDevice(deviceId); + servo->enablePwm(pin); +} + +// > servoDisablePwm/deviceId +void MrlComm::servoDisablePwm(byte deviceId) { + MrlServo* servo = (MrlServo*) getDevice(deviceId); + servo->disablePwm(); +} + +// > servoSetMaxVelocity/deviceId/b16 maxVelocity +void MrlComm::servoSetMaxVelocity(byte deviceId, int maxVelocity) { + MrlServo* servo = (MrlServo*) getDevice(deviceId); + servo->setMaxVelocity(maxVelocity); +} + +// > servoSetVelocity/deviceId/b16 velocity +void MrlComm::servoSetVelocity(byte deviceId, int velocity) { + MrlServo* servo = (MrlServo*) getDevice(deviceId); + servo->setVelocity(velocity); +} + +void MrlComm::servoSweepStart(byte deviceId, byte min, byte max, byte step) { + MrlServo* servo = (MrlServo*) getDevice(deviceId); + servo->startSweep(min, max, step); +} + +void MrlComm::servoSweepStop(byte deviceId) { + MrlServo* servo = (MrlServo*) getDevice(deviceId); + servo->stopSweep(); +} + +void MrlComm::servoWrite(byte deviceId, byte target) { + msg->publishDebug("MrlComm::servoWrite - servoWrite" + String(deviceId)); + MrlServo* servo = (MrlServo*) getDevice(deviceId); + msg->publishDebug("got - servoWrite" + String(deviceId)); + servo->servoWrite(target); + msg->publishDebug("got - wrote" + String(deviceId)); +} + +void MrlComm::servoWriteMicroseconds(byte deviceId, int ms) { + MrlServo* servo = (MrlServo*) getDevice(deviceId); + servo->servoWriteMicroseconds(ms); +} + +void MrlComm::setDebug(bool enabled) { + msg->debug = enabled; +} + +void MrlComm::setSerialRate(long rate) { + msg->publishDebug("setSerialRate " + String(rate)); +} + +// TODO - implement +// > setTrigger/pin/value +void MrlComm::setTrigger(byte pin, byte triggerValue) { + msg->publishDebug("implement me ! setDebounce (" + String(pin) + "," + String(triggerValue)); +} + +// TODO - implement +// > setDebounce/pin/delay +void MrlComm::setDebounce(byte pin, byte delay) { + msg->publishDebug("implement me ! setDebounce (" + String(pin) + "," + String(delay)); +} + +// TODO - implement +// > serialAttach/deviceId/relayPin +void MrlComm::serialAttach(byte deviceId, byte relayPin) { + +} + +// TODO - implement +// > serialRelay/deviceId/[] data +void MrlComm::serialRelay(byte deviceId, byte dataSize, const byte*data) { + +} + +// > softReset +void MrlComm::softReset() { + // removing devices & pins + while (deviceList.size() > 0) { + delete deviceList.pop(); + } + while (pinList.size() > 0) { + delete pinList.pop(); + } + //resetting variables to default + loopCount = 0; + publishBoardStatusModulus = 10000; + boardStatusEnabled = false; + msg->debug = false; + heartbeatEnabled = false; + lastHeartbeatUpdate = 0; + for (unsigned int i = 0; i < MAX_MSG_SIZE; i++) { + customMsgBuffer[i] = 0; + } + customMsgSize = 0; +} + +// > ultrasonicSensorAttach/deviceId/triggerPin/echoPin +void MrlComm::ultrasonicSensorAttach(byte deviceId, byte triggerPin, byte echoPin) { + MrlUltrasonicSensor* sensor = (MrlUltrasonicSensor*) addDevice(new MrlUltrasonicSensor(deviceId)); + sensor->attach(triggerPin, echoPin); +} +// > ultrasonicSensorStartRanging/deviceId +void MrlComm::ultrasonicSensorStartRanging(byte deviceId, long timeout) { + MrlUltrasonicSensor* sensor = (MrlUltrasonicSensor*)getDevice(deviceId); + sensor->startRanging(timeout); +} +// > ultrasonicSensorStopRanging/deviceId +void MrlComm::ultrasonicSensorStopRanging(byte deviceId) { + MrlUltrasonicSensor* sensor = (MrlUltrasonicSensor*)getDevice(deviceId); + sensor->stopRanging(); +} diff --git a/MrlComm.h b/MrlComm.h index 8dc4d88..9b27869 100644 --- a/MrlComm.h +++ b/MrlComm.h @@ -1,19 +1,17 @@ #ifndef MrlComm_h #define MrlComm_h -#include #include "ArduinoMsgCodec.h" -#include "MrlMsg.h" -#include "MrlCmd.h" -#include "LinkedList.h" -#include "MrlServo.h" -#include "Device.h" -#include "MrlI2cBus.h" -#include "MrlNeopixel.h" -#include "Pin.h" // TODO - standard convention of dev versions are odd release is even ? -#define MRLCOMM_VERSION 40 +#define MRLCOMM_VERSION 43 + +// forward defines to break circular dependency +class Device; +class Msg; +class MrlComm; +class Pin; + /*********************************************************************** * Class MrlComm - @@ -42,36 +40,113 @@ class MrlComm{ unsigned char* config; // performance metrics and load timing // global debug setting, if set to true publishDebug will write to the serial port. - bool debug; int byteCount; int msgSize; - bool enableBoardStatus; + bool boardStatusEnabled; unsigned int publishBoardStatusModulus; // the frequency in which to report the load timing metrics (in number of main loops) unsigned long lastMicros; // timestamp of last loop (if stats enabled.) -#if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_ADK) - MrlCmd* mrlCmd[4]; -#else - MrlCmd* mrlCmd[1]; -#endif - bool heartbeat; - bool heartbeatEnabled; + + bool heartbeatEnabled = false; unsigned long lastHeartbeatUpdate; - unsigned int customMsg[MAX_MSG_SIZE]; + + byte customMsgBuffer[MAX_MSG_SIZE]; int customMsgSize; - void softReset(); + + // handles all messages to and from pc + Msg* msg; + +public: + // utility methods int getFreeRam(); - void publishError(int type); - void publishError(int type, String message); - void publishCommandAck(int function); - void publishAttachedDevice(int id, int nameSize, unsigned char* name); - void setPWMFrequency(int address, int prescalar); - void setSerialRate(); - void deviceAttach(unsigned char* ioCmd); - void deviceDetach(int id); Device* getDevice(int id); - void addDevice(Device* device); + + bool ackEnabled = false; + + Device* addDevice(Device* device); void update(); + // Below are generated callbacks controlled by + // arduinoMsgs.schema + // + // > getBoardInfo + void getBoardInfo(); + // > enableBoardStatus/bool enabled + void enableBoardStatus( boolean enabled); + // > enablePin/address/type/b16 rate + void enablePin( byte address, byte type, int rate); + // > setDebug/bool enabled + void setDebug( boolean enabled); + // > setSerialRate/b32 rate + void setSerialRate( long rate); + // > softReset + void softReset(); + // > enableAck/bool enabled + void enableAck( boolean enabled); + // > enableHeartbeat/bool enabled + void enableHeartbeat( boolean enabled); + // > heartbeat + void heartbeat(); + // > echo/bu32 sInt + void echo( unsigned long sInt); + // > controllerAttach/serialPort + void controllerAttach( byte serialPort); + // > customMsg/[] msg + void customMsg( byte msgSize, const byte*msg); + // > deviceDetach/deviceId + void deviceDetach( byte deviceId); + // > i2cBusAttach/deviceId/i2cBus + void i2cBusAttach( byte deviceId, byte i2cBus); + // > i2cRead/deviceId/deviceAddress/size + void i2cRead( byte deviceId, byte deviceAddress, byte size); + // > i2cWrite/deviceId/deviceAddress/[] data + void i2cWrite( byte deviceId, byte deviceAddress, byte dataSize, const byte*data); + // > i2cWriteRead/deviceId/deviceAddress/readSize/writeValue + void i2cWriteRead( byte deviceId, byte deviceAddress, byte readSize, byte writeValue); + // > neoPixelAttach/deviceId/pin/b32 numPixels + void neoPixelAttach( byte deviceId, byte pin, long numPixels); + // > neoPixelSetAnimation/deviceId/animation/red/green/blue/b16 speed + void neoPixelSetAnimation( byte deviceId, byte animation, byte red, byte green, byte blue, int speed); + // > neoPixelWriteMatrix/deviceId/[] buffer + void neoPixelWriteMatrix( byte deviceId, byte bufferSize, const byte*buffer); + // > disablePin/pin + void disablePin( byte pin); + // > disablePins + void disablePins(); + // > setTrigger/pin/triggerValue + void setTrigger( byte pin, byte triggerValue); + // > setDebounce/pin/delay + void setDebounce( byte pin, byte delay); + // > servoAttach/deviceId/pin/initPos/b16 initVelocity + void servoAttach( byte deviceId, byte pin, byte initPos, int initVelocity); + // > servoEnablePwm/deviceId/pin + void servoEnablePwm( byte deviceId, byte pin); + // > servoDisablePwm/deviceId + void servoDisablePwm( byte deviceId); + // > servoSetMaxVelocity/deviceId/b16 maxVelocity + void servoSetMaxVelocity( byte deviceId, int maxVelocity); + // > servoSetVelocity/deviceId/b16 velocity + void servoSetVelocity( byte deviceId, int velocity); + // > servoSweepStart/deviceId/min/max/step + void servoSweepStart( byte deviceId, byte min, byte max, byte step); + // > servoSweepStop/deviceId + void servoSweepStop( byte deviceId); + // > servoWrite/deviceId/target + void servoWrite( byte deviceId, byte target); + // > servoWriteMicroseconds/deviceId/b16 ms + void servoWriteMicroseconds( byte deviceId, int ms); + // > serialAttach/deviceId/relayPin + void serialAttach( byte deviceId, byte relayPin); + // > serialRelay/deviceId/[] data + void serialRelay( byte deviceId, byte dataSize, const byte*data); + // > ultrasonicSensorAttach/deviceId/triggerPin/echoPin + void ultrasonicSensorAttach( byte deviceId, byte triggerPin, byte echoPin); + // > ultrasonicSensorStartRanging/deviceId/b32 timeout + void ultrasonicSensorStartRanging( byte deviceId, long timeout); + // > ultrasonicSensorStopRanging/deviceId + void ultrasonicSensorStopRanging( byte deviceId); + // + // end + public: unsigned long loopCount; // main loop count MrlComm(); @@ -79,11 +154,13 @@ class MrlComm{ void publishBoardStatus(); void publishVersion(); void publishBoardInfo(); - void readCommand(); + void processCommand(); void processCommand(int ioType); void updateDevices(); unsigned int getCustomMsg(); int getCustomMsgSize(); + void begin(HardwareSerial& serial); + bool readMsg(); }; - + #endif diff --git a/MrlI2cBus.cpp b/MrlI2cBus.cpp index 874013f..f5fa77c 100644 --- a/MrlI2cBus.cpp +++ b/MrlI2cBus.cpp @@ -1,7 +1,9 @@ +#include "Msg.h" +#include "Device.h" #include "MrlI2cBus.h" -MrlI2CBus::MrlI2CBus() : - Device(DEVICE_TYPE_I2C) { +MrlI2CBus::MrlI2CBus(int deviceId) : + Device(deviceId, DEVICE_TYPE_I2C) { if (TWCR == 0) { //// do this check so that Wire only gets initialized once WIRE.begin(); // Force 400 KHz i2c @@ -9,24 +11,17 @@ MrlI2CBus::MrlI2CBus() : } } -bool MrlI2CBus::deviceAttach(unsigned char config[], int configSize) { - if (configSize != 2) { - MrlMsg msg(PUBLISH_MRLCOMM_ERROR); - msg.addData(ERROR_DOES_NOT_EXIST); - msg.addData(String(F("MrlI2CBus invalid attach config size"))); - return false; - } - bus = config[1]; - attachDevice(); +bool MrlI2CBus::attach(byte bus) { + this->bus = bus; return true; } // I2CWRITE | DEVICE_INDEX | I2CADDRESS | DATASIZE | DATA..... -void MrlI2CBus::i2cWrite(unsigned char* ioCmd) { - int dataSize = ioCmd[3]; - WIRE.beginTransmission(ioCmd[2]); // address to the i2c device +void MrlI2CBus::i2cWrite(byte deviceAddress, byte dataSize, const byte*data) { + + WIRE.beginTransmission(deviceAddress); // address to the i2c device for (int i = 0; i < dataSize; i++) { // data to write - WIRE.write(ioCmd[i +4]); + WIRE.write(data[i]); } WIRE.endTransmission(); } @@ -36,16 +31,16 @@ void MrlI2CBus::i2cWrite(unsigned char* ioCmd) { // DEVICE_INDEX = Index to the I2C bus // I2CADDRESS = The address of the i2c device // DATA_SIZE = The number of bytes to read from the i2c device -void MrlI2CBus::i2cRead(unsigned char* ioCmd) { +void MrlI2CBus::i2cRead(byte deviceAddress, byte size) { + + int answer = WIRE.requestFrom(deviceAddress, size); // reqest a number of bytes to read - int answer = WIRE.requestFrom(ioCmd[2], ioCmd[3]); // reqest a number of bytes to read - MrlMsg msg(PUBLISH_SENSOR_DATA); - msg.addData(ioCmd[1]); // DEVICE_INDEX - msg.addData(ioCmd[3]); // DATASIZE for (int i = 0; i < answer; i++) { - msg.addData(Wire.read()); + msg->add(Wire.read()); } - msg.sendMsg(); + + // byte deviceId = ioCmd[1]; not needed we have our own deviceId + msg->publishI2cData(id, msg->getBuffer(), msg->getBufferSize()); } // I2WRITEREAD | DEVICE_INDEX | I2CADDRESS | DATASIZE | DEVICE_MEMORY_ADDRESS @@ -53,18 +48,18 @@ void MrlI2CBus::i2cRead(unsigned char* ioCmd) { // DEVICE_INDEX = Index to the I2C bus // I2CADDRESS = The address of the i2c device // DATA_SIZE = The number of bytes to read from the i2c device -void MrlI2CBus::i2cWriteRead(unsigned char* ioCmd) { - WIRE.beginTransmission(ioCmd[2]); // address to the i2c device - WIRE.write(ioCmd[4]); // device memory address to read from +void MrlI2CBus::i2cWriteRead(byte deviceAddress, byte readSize, byte writeValue) { + WIRE.beginTransmission(writeValue); // address to the i2c device + WIRE.write(writeValue); // device memory address to read from WIRE.endTransmission(); - int answer = WIRE.requestFrom((uint8_t) ioCmd[2], (uint8_t) ioCmd[3]); // reqest a number of bytes to read - MrlMsg msg(PUBLISH_SENSOR_DATA); - msg.addData(ioCmd[1]); // DEVICE_INDEX - msg.addData(ioCmd[3]); // DATASIZE + int answer = WIRE.requestFrom(deviceAddress, readSize); // reqest a number of bytes to read + for (int i = 0; i < answer; i++) { - msg.addData(Wire.read()); + msg->add(Wire.read()); } - msg.sendMsg(); + + // byte deviceId = ioCmd[1]; + msg->publishI2cData(id, msg->getBuffer(), msg->getBufferSize()); } void MrlI2CBus::update() { diff --git a/MrlI2cBus.h b/MrlI2cBus.h index 04ed829..323d8b4 100644 --- a/MrlI2cBus.h +++ b/MrlI2cBus.h @@ -1,8 +1,6 @@ #ifndef MrlI2cBus_h #define MrlI2cBus_h -#include "Device.h" -#include "MrlMsg.h" #define WIRE Wire #include @@ -28,11 +26,11 @@ class MrlI2CBus : public Device { private: int bus; public: - MrlI2CBus(); - bool deviceAttach(unsigned char config[], int configSize); - void i2cRead(unsigned char* ioCmd); - void i2cWrite(unsigned char* ioCmd); - void i2cWriteRead(unsigned char* ioCmd); + MrlI2CBus(int deviceId); + bool attach(byte bus); + void i2cRead(byte deviceAddress, byte size); + void i2cWrite(byte deviceAddress, byte dataSize, const byte*data); + void i2cWriteRead(byte deviceAddress, byte readSize, byte writeValue); void update(); }; diff --git a/MrlIo.cpp b/MrlIo.cpp deleted file mode 100644 index 75db101..0000000 --- a/MrlIo.cpp +++ /dev/null @@ -1,111 +0,0 @@ -#include "MrlIo.h" - -int MrlIo::openIo = 0; - -MrlIo::MrlIo() { - ioType = MRL_IO_NOT_DEFINED; -} - -MrlIo::~MrlIo(){ - //end(); -} - -bool MrlIo::begin(int _ioType, long speed) { - if (openIo & (1 << _ioType)){ - //port already open - ioType = _ioType; - return true; - } - switch (_ioType){ - case MRL_IO_SERIAL_0: - serial = &Serial; - break; -#if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_ADK) - case MRL_IO_SERIAL_1: - serial = &Serial1; - break; - case MRL_IO_SERIAL_2: - serial = &Serial2; - break; - case MRL_IO_SERIAL_3: - serial = &Serial3; - break; -#endif - default: - return false; - break; - } - serial->begin(speed); - // ioType == _ioType; huh ? - openIo |= (1 << ioType); - //delay(500); - return true; -} - -void MrlIo::write(unsigned char value) { - if(!(openIo & (1 << ioType))){ - //port close - ioType = MRL_IO_NOT_DEFINED; - return; - } -// if(ioType==MRL_IO_SERIAL_0){ -// Serial.write(value); -// } -// else if(ioType==MRL_IO_SERIAL_1){ -// Serial1.write(value); -// } - serial->write(value); -} - -void MrlIo::write(unsigned char* buffer, int len) { - if(!(openIo & (1 << ioType))){ - //port close - ioType = MRL_IO_NOT_DEFINED; - return; - } - serial->write(buffer, len); -} - -int MrlIo::read() { - if(!(openIo & (1 << ioType))){ - //port close - ioType = MRL_IO_NOT_DEFINED; - return -1; - } - return serial->read(); -} - -int MrlIo::available() { - //serial->println(ioType); - if(!(openIo & (1 << ioType))){ - //port close - ioType = MRL_IO_NOT_DEFINED; - - return 0; - } - return serial->available(); -} - -void MrlIo::end() { - if (!(openIo & (1 << ioType))){ - //port already close - ioType = MRL_IO_NOT_DEFINED; - return; - } - serial->end(); - serial = NULL; - openIo &= ~(1 << ioType); - ioType = MRL_IO_NOT_DEFINED; - delay(500); -} - -void MrlIo::flush() { - if (!(openIo & (1 << ioType))){ - //port already close - ioType = MRL_IO_NOT_DEFINED; - return; - } - serial->flush(); -} - - diff --git a/MrlIo.h b/MrlIo.h deleted file mode 100644 index c6ff953..0000000 --- a/MrlIo.h +++ /dev/null @@ -1,34 +0,0 @@ -#ifndef MrlIo_h -#define MrlIo_h - -#include -#include "ArduinoMsgCodec.h" - -#define MRL_IO_NOT_DEFINED 0 -#define MRL_IO_SERIAL_0 1 -#if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_ADK) - #define MRL_IO_SERIAL_1 2 - #define MRL_IO_SERIAL_2 3 - #define MRL_IO_SERIAL_3 4 -#endif - - -class MrlIo { - private: - int ioType; - HardwareSerial* serial; - public: - static int openIo; - MrlIo(); - ~MrlIo(); - bool begin(int ioType, long speed); - void write(unsigned char value); - void write(unsigned char* buffer, int len); - int read(); - int available(); - void end(); - void flush(); - void test(); -}; - -#endif diff --git a/MrlMotor.h b/MrlMotor.h index 7871060..2ad9b1c 100644 --- a/MrlMotor.h +++ b/MrlMotor.h @@ -1,30 +1,29 @@ -#ifndef MrlMotor_h -#define MrlMotor_h - -/** - * Motor Device - */ - -#include "Device.h" - -class MrlMotor : public Device { - // details of the different motor controls/types - public: - MrlMotor() : Device(DEVICE_TYPE_MOTOR) { - // TODO: implement classes or custom control for different motor controller types - // usually they require 2 PWM pins, direction & speed... sometimes the logic is a - // little different to drive it. - // GroG: 3 Motor Types so far - probably a single MrlMotor could handle it - // they are MotorDualPwm MotorSimpleH and MotorPulse - // Stepper should be its own MrlStepper - } - void update() { - // we should update the pwm values for the control of the motor device here - // this is potentially where the hardware specific logic could go for various motor controllers - // L298N vs IBT2 vs other... maybe consider a subclass for the type of motor-controller. - // GroG : All motor controller I know of which can be driven by the Arduino fall in the - // MotorDualPwm MotorSimpleH and MotorPulse - categories - } -}; - +#ifndef MrlMotor_h +#define MrlMotor_h + +/** + * Motor Device + */ + + +class MrlMotor : public Device { + // details of the different motor controls/types + public: + MrlMotor() : Device(DEVICE_TYPE_MOTOR) { + // TODO: implement classes or custom control for different motor controller types + // usually they require 2 PWM pins, direction & speed... sometimes the logic is a + // little different to drive it. + // GroG: 3 Motor Types so far - probably a single MrlMotor could handle it + // they are MotorDualPwm MotorSimpleH and MotorPulse + // Stepper should be its own MrlStepper + } + void update() { + // we should update the pwm values for the control of the motor device here + // this is potentially where the hardware specific logic could go for various motor controllers + // L298N vs IBT2 vs other... maybe consider a subclass for the type of motor-controller. + // GroG : All motor controller I know of which can be driven by the Arduino fall in the + // MotorDualPwm MotorSimpleH and MotorPulse - categories + } +}; + #endif diff --git a/MrlMsg.cpp b/MrlMsg.cpp deleted file mode 100644 index 3d34db0..0000000 --- a/MrlMsg.cpp +++ /dev/null @@ -1,175 +0,0 @@ -#include "MrlMsg.h" - -MrlMsg::MrlMsg(int msgType) { - type = msgType; - deviceId = -1; - dataCountEnabled = false; - begin(MRL_IO_SERIAL_0,115200); - auto_send=0; -} - -MrlMsg::MrlMsg(int msgType, int id) { - type = msgType; - deviceId = id; - dataCountEnabled = false; - begin(MRL_IO_SERIAL_0,115200); - auto_send=0; -} - -// addData overload methods -void MrlMsg::addData(byte data) { - dataBuffer.add(data); - dataSizeCount++; - if(dataBuffer.size() >= auto_send && auto_send) sendMsg(); -} - -void MrlMsg::addData(int data) { - addData((byte) data); -} - -void MrlMsg::addData(unsigned int data) { - addData((byte) data); -} - -void MrlMsg::addData(unsigned char* dataArray, int size, bool inclDataSize) { - if (inclDataSize) { - dataBuffer.add((byte) size); - } - for (int i = 0; i < size; i++) { - dataBuffer.add((byte) dataArray[i]); - } - dataSizeCount += size; - if(dataBuffer.size() >= auto_send && auto_send) sendMsg(); -} - -void MrlMsg::addData(long data) { - addData((unsigned long) data); -} - -void MrlMsg::addData(unsigned long data) { - dataBuffer.add((byte)((data >> 24) & 0xFF)); - dataBuffer.add((byte)((data >> 16) & 0xFF)); - dataBuffer.add((byte)((data >> 8) & 0xFF)); - dataBuffer.add((byte)(data & 0xFF)); - dataSizeCount += 4; - if(dataBuffer.size() >= auto_send && auto_send) sendMsg(); -} - -void MrlMsg::addData(String data, bool inclDataSize) { - if (inclDataSize) { - dataBuffer.add((byte) data.length()); - } - for (unsigned int i = 0; i < data.length(); i++) { - dataBuffer.add(data[i]); - } - dataSizeCount += data.length(); - if(dataBuffer.size() >= auto_send && auto_send) sendMsg(); -} - -void MrlMsg::addData(int data[], int size, bool inclDataSize) { - if (inclDataSize) { - dataBuffer.add((byte) size); - } - for (int i = 0; i < size; i++) { - dataBuffer.add(data[i]); - } - dataSizeCount += size; - if(dataBuffer.size() >= auto_send && auto_send) sendMsg(); -} - -void MrlMsg::addData16(int data) { - addData16((unsigned int) data); -} - -void MrlMsg::addData16(unsigned int data) { - dataBuffer.add((byte)(data >> 8)); - dataBuffer.add((byte)(data & 0xFF)); - dataSizeCount += 2; - if(dataBuffer.size() >= auto_send && auto_send) sendMsg(); -} - -// enabled the data counter -void MrlMsg::countData() { - dataCountEnabled = true; - dataSizeCount = 0; - dataSizePos = dataBuffer.size(); -} - -// add the data counter at the saved position -void MrlMsg::addDataCount() { - dataCountEnabled = false; - dataBuffer.add(dataSizePos, (byte) dataSizeCount); -} - -// send the message to Serial -void MrlMsg::sendMsg() { - // publishDebug("Sending msg"); - bool _dataCountEnabled = dataCountEnabled; - if (dataCountEnabled) { - addDataCount(); - } - int dataSize = dataBuffer.size(); - int msgSize = dataSize + 1; - if (deviceId > -1) { - msgSize += 1; - } - write(MAGIC_NUMBER); - write(msgSize); - write(type); - if (deviceId > -1) { - write(deviceId); - } - ListNode* node = dataBuffer.getRoot(); - while (node != NULL) { - write(node->data); - node = node->next; - } - flush(); - dataBuffer.clear(); - if (_dataCountEnabled) { - countData(); - } -} - -/** - * Publish Debug - return a text debug message back to the java based arduino service in MRL - * MAGIC_NUMBER|1+MSG_LENGTH|MESSAGE_BYTES - * - * This method will publish a string back to the Arduino service for debugging purproses. - * - */ - -void MrlMsg::publishDebug(String message){ - // NOTE-KW: If this method gets called excessively I have seen memory corruption in the - // arduino where it seems to be getting a null string passed in as "message" - // very very very very very odd.. I suspect a bug in the arduino hardware/software - MrlMsg msg(PUBLISH_DEBUG); - msg.addData(message); - msg.sendMsg(); -} - -/** - * send an error message/code back to MRL. - * MAGIC_NUMBER|2|PUBLISH_MRLCOMM_ERROR|ERROR_CODE - */ -// KW: remove this, force an error message. -void MrlMsg::publishError(int type) { - MrlMsg msg(PUBLISH_MRLCOMM_ERROR); - msg.addData(type); - msg.sendMsg(); -} -/** - * Send an error message along with the error code - * - */ -void MrlMsg::publishError(int type, String message) { - MrlMsg msg(PUBLISH_MRLCOMM_ERROR); - msg.addData(type); - msg.addData(message); - msg.sendMsg(); -} - -void MrlMsg::autoSend(int value){ - auto_send = value; -} - diff --git a/MrlMsg.h b/MrlMsg.h deleted file mode 100644 index 78084c2..0000000 --- a/MrlMsg.h +++ /dev/null @@ -1,63 +0,0 @@ -#ifndef MrlMsg_h -#define MrlMsg_h - -#include "ArduinoMsgCodec.h" -#include "LinkedList.h" -#include "MrlIo.h" -#include "Arduino.h" - - -// ------ error types ------ -#define ERROR_SERIAL 1 -#define ERROR_UNKOWN_CMD 2 -#define ERROR_ALREADY_EXISTS 3 -#define ERROR_DOES_NOT_EXIST 4 -#define ERROR_UNKOWN_SENSOR 5 - -/********************************************************************** - * MrlMsg - This class is responsible to send the messages to MRL in - * java-land - */ -class MrlMsg : public MrlIo{ - private: - LinkedList dataBuffer; - int type; // message id ie PUBLISH_VERSION - int deviceId; - // those variable allow to count the data and add the number to the dataBuffer - int dataSizePos; - int dataSizeCount; - bool dataCountEnabled; - int auto_send; - - public: - MrlMsg(int msgType); - MrlMsg(int msgType, int id); - void addData(byte data); - void addData(int data); - void addData(unsigned int data); - void addData(unsigned char* dataArray, int size, bool inclDataSize = false); - void addData(long data); - void addData(unsigned long data); - void addData(String data, bool inclDataSize = false); - void addData(int data[], int size, bool inclDataSize = false); - void addData16(int data); - void addData16(unsigned int data); - void countData(); - void addDataCount(); - void sendMsg(); - void autoSend(int value); - static long toInt(unsigned char* buffer, int start) { - return (buffer[start] << 8) + buffer[start + 1]; - } - - static long toLong(unsigned char* buffer, int start) { - return (((long)buffer[start] << 24) + - ((long)buffer[start + 1] << 16) + - (buffer[start + 2] << 8) + buffer[start + 3]); - } - static void publishDebug(String message); - static void publishError(int type); - static void publishError(int type, String message); -}; - -#endif diff --git a/MrlNeopixel.cpp b/MrlNeopixel.cpp index 736c354..efe0d8e 100644 --- a/MrlNeopixel.cpp +++ b/MrlNeopixel.cpp @@ -1,3 +1,5 @@ +#include "Msg.h" +#include "Device.h" #include "MrlNeopixel.h" Pixel::Pixel() { @@ -10,13 +12,15 @@ void Pixel::clearPixel() { green = 0; } -void Pixel::setPixel(unsigned char red, unsigned char green, unsigned char blue){ +void Pixel::setPixel(unsigned char red, unsigned char green, + unsigned char blue) { this->red = red; this->green = green; this->blue = blue; } -MrlNeopixel::MrlNeopixel():Device(DEVICE_TYPE_NEOPIXEL) { +MrlNeopixel::MrlNeopixel(int deviceId) : + Device(deviceId, DEVICE_TYPE_NEOPIXEL) { _baseColorRed = 0; _baseColorGreen = 0; _baseColorBlue = 0; @@ -29,22 +33,10 @@ MrlNeopixel::~MrlNeopixel() { delete pixels; } -bool MrlNeopixel::deviceAttach(unsigned char config[], int configSize) { - if (configSize != 2) { - MrlMsg msg(PUBLISH_MRLCOMM_ERROR); - msg.addData(ERROR_DOES_NOT_EXIST); - msg.addData(String(F("MrlNeopixel invalid attach config size"))); - msg.sendMsg(); - return false; - } - pin = config[0]; - numPixel = config[1]; - pixels = new Pixel[numPixel + 1]; - if (BOARD == BOARD_TYPE_ID_UNKNOWN) { - MrlMsg msg(PUBLISH_MRLCOMM_ERROR); - msg.addData(ERROR_DOES_NOT_EXIST); - msg.addData(String(F("Board not supported"))); - msg.sendMsg(); +bool MrlNeopixel::attach(byte pin, long numPixels) { + pixels = new Pixel[numPixels + 1]; + if (BOARD == BOARD_TYPE_ID_UNKNOWN) { // REALLY ? WHY ? + msg->publishError(F("Board not supported")); return false; } state = 1; @@ -52,16 +44,14 @@ bool MrlNeopixel::deviceAttach(unsigned char config[], int configSize) { pinMode(pin, OUTPUT); lastShow = 0; Pixel pixel = Pixel(); - for (unsigned int i = 1; i <= numPixel; i++) { + for (long i = 1; i <= numPixels; i++) { pixels[i] = pixel; } newData = true; - attachDevice(); return true; } inline void MrlNeopixel::sendBitB(bool bitVal) { -#ifndef VIRTUAL_ARDUINO_H uint8_t bit = bitmask; if (bitVal) { // 0 bit PORTB |= bit; @@ -105,12 +95,9 @@ inline void MrlNeopixel::sendBitB(bool bitVal) { sei(); //activate interrupts } - - #endif } inline void MrlNeopixel::sendBitC(bool bitVal) { -#ifndef VIRTUAL_ARDUINO_H uint8_t bit = bitmask; if (bitVal) { // 0 bit PORTC |= bit; @@ -157,8 +144,6 @@ inline void MrlNeopixel::sendBitC(bool bitVal) { // Note that the inter-bit gap can be as long as you want as long as it doesn't exceed the 5us reset timeout (which is A long time) // Here I have been generous and not tried to squeeze the gap tight but instead erred on the side of lots of extra time. // This has thenice side effect of avoid glitches on very long strings becuase - - #endif } #if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_ADK) @@ -521,7 +506,6 @@ inline void MrlNeopixel::sendBitA(bool bitVal) { #endif inline void MrlNeopixel::sendBitD(bool bitVal) { -#ifndef VIRTUAL_ARDUINO_H uint8_t bit = bitmask; if (bitVal) { // 0 bit PORTD |= bit; @@ -565,7 +549,7 @@ inline void MrlNeopixel::sendBitD(bool bitVal) { sei(); //activate interrupts } -#endif + } inline void MrlNeopixel::sendByte(unsigned char byte) { @@ -599,251 +583,250 @@ void MrlNeopixel::show() { } -void MrlNeopixel::neopixelWriteMatrix(unsigned char* ioCmd) { - for (int i = 3; i < ioCmd[2] + 3; i += 4) { - pixels[ioCmd[i]].red = ioCmd[i + 1]; - pixels[ioCmd[i]].green = ioCmd[i + 2]; - pixels[ioCmd[i]].blue = ioCmd[i + 3]; +void MrlNeopixel::neopixelWriteMatrix(byte bufferSize, const byte*buffer) { + for (int i = 3; i < bufferSize + 3; i += 4) { + pixels[i].red = buffer[i + 1]; + pixels[i].green = buffer[i + 2]; + pixels[i].blue = buffer[i + 3]; } newData = true; } void MrlNeopixel::update() { - if ((lastShow + 33) > millis()){ + if ((lastShow + 33) > millis()) { return; //update 30 times/sec if there is new data to show } switch (_animation) { - case NEOPIXEL_ANIMATION_NO_ANIMATION: - break; + case NEOPIXEL_ANIMATION_NO_ANIMATION: + break; case NEOPIXEL_ANIMATION_STOP: animationStop(); break; case NEOPIXEL_ANIMATION_COLOR_WIPE: animationColorWipe(); break; - case NEOPIXEL_ANIMATION_LARSON_SCANNER: - animationLarsonScanner(); - break; - case NEOPIXEL_ANIMATION_THEATER_CHASE: - animationTheaterChase(); - break; - case NEOPIXEL_ANIMATION_THEATER_CHASE_RAINBOW: - animationTheaterChaseRainbow(); - break; - case NEOPIXEL_ANIMATION_RAINBOW: - animationRainbow(); - break; - case NEOPIXEL_ANIMATION_RAINBOW_CYCLE: - animationRainbowCycle(); - break; - case NEOPIXEL_ANIMATION_FLASH_RANDOM: - animationFlashRandom(); - break; - case NEOPIXEL_ANIMATION_IRONMAN: - animationIronman(); - break; + case NEOPIXEL_ANIMATION_LARSON_SCANNER: + animationLarsonScanner(); + break; + case NEOPIXEL_ANIMATION_THEATER_CHASE: + animationTheaterChase(); + break; + case NEOPIXEL_ANIMATION_THEATER_CHASE_RAINBOW: + animationTheaterChaseRainbow(); + break; + case NEOPIXEL_ANIMATION_RAINBOW: + animationRainbow(); + break; + case NEOPIXEL_ANIMATION_RAINBOW_CYCLE: + animationRainbowCycle(); + break; + case NEOPIXEL_ANIMATION_FLASH_RANDOM: + animationFlashRandom(); + break; + case NEOPIXEL_ANIMATION_IRONMAN: + animationIronman(); + break; default: - MrlMsg::publishError(ERROR_DOES_NOT_EXIST, - F("Neopixel animation do not exist")); + msg->publishError(F("Neopixel animation do not exist")); break; } - if(newData){ - show(); + if (newData) { + show(); } } -void MrlNeopixel::setAnimation(unsigned char* config){ - unsigned char size = config[0]; - if (size != 6){ - MrlMsg::publishError(ERROR_DOES_NOT_EXIST, F("Wrong config size for Neopixel setAnimation")); - return; - } - _animation = config[1]; - _baseColorRed = config[2]; - _baseColorGreen = config[3]; - _baseColorBlue = config[4]; - _speed = (config[5] << 8) + config[6]; - _pos = 1; - _count = 0; - _off = false; - _dir = 1; - _step = 1; - _alpha = 50; - newData=true; +void MrlNeopixel::setAnimation ( byte animation, byte red, byte green, byte blue, int speed) { + + _animation = animation; + _baseColorRed = red; + _baseColorGreen = green; + _baseColorBlue = blue; + _speed = speed; + _pos = 1; + _count = 0; + _off = false; + _dir = 1; + _step = 1; + _alpha = 50; + newData = true; } void MrlNeopixel::animationStop() { for (unsigned int i = 1; i <= numPixel; i++) { pixels[i].clearPixel(); } - _animation = NEOPIXEL_ANIMATION_NO_ANIMATION; + _animation = NEOPIXEL_ANIMATION_NO_ANIMATION; newData = true; } void MrlNeopixel::animationColorWipe() { - if(!((_count++)%_speed)) { - if(_off) { - pixels[_pos++].setPixel(0, 0, 0); - } - else{ - pixels[_pos++].setPixel(_baseColorRed, _baseColorGreen, _baseColorBlue); - } - if(_pos > numPixel) { - _pos = 1; - _off = !_off; - } - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + if (_off) { + pixels[_pos++].setPixel(0, 0, 0); + } else { + pixels[_pos++].setPixel(_baseColorRed, _baseColorGreen, + _baseColorBlue); + } + if (_pos > numPixel) { + _pos = 1; + _off = !_off; + } + } else + lastShow = millis(); + newData = true; } void MrlNeopixel::animationLarsonScanner() { - if(!((_count++)%_speed)) { - for(unsigned int i = 1; i <= numPixel; i++){ - pixels[i].clearPixel(); - } - unsigned int pos = _pos; - for(int i = -2; i <= 2; i++){ - pos = _pos + i; - if (pos < 1) - pos += numPixel; - if (pos > numPixel) - pos -= numPixel; - int j = (abs(i) * 10)+1; - pixels[pos].setPixel(_baseColorRed / j, _baseColorGreen /j, _baseColorBlue / j); - } - _pos += _dir; - if (_pos < 1) { - pos = 2; - _dir = -_dir; - } - else if(_pos > numPixel) { - _pos = numPixel - 1; - _dir = -_dir; - } - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + for (unsigned int i = 1; i <= numPixel; i++) { + pixels[i].clearPixel(); + } + unsigned int pos = _pos; + for (int i = -2; i <= 2; i++) { + pos = _pos + i; + if (pos < 1) + pos += numPixel; + if (pos > numPixel) + pos -= numPixel; + int j = (abs(i) * 10) + 1; + pixels[pos].setPixel(_baseColorRed / j, _baseColorGreen / j, + _baseColorBlue / j); + } + _pos += _dir; + if (_pos < 1) { + pos = 2; + _dir = -_dir; + } else if (_pos > numPixel) { + _pos = numPixel - 1; + _dir = -_dir; + } + } else + lastShow = millis(); + newData = true; } void MrlNeopixel::animationTheaterChase() { - if(!((_count++)%_speed)) { - for (unsigned int i = 0; i <= numPixel; i+=3){ - if(i + _pos <= numPixel){ - pixels[i + _pos].clearPixel(); - } - } - _pos++; - if(_pos >= 4) _pos = 1; - for (unsigned int i = 0; i <= numPixel; i+=3){ - if(i + _pos <= numPixel){ - pixels[i + _pos].setPixel(_baseColorRed, _baseColorGreen, _baseColorBlue); - } - } - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + for (unsigned int i = 0; i <= numPixel; i += 3) { + if (i + _pos <= numPixel) { + pixels[i + _pos].clearPixel(); + } + } + _pos++; + if (_pos >= 4) + _pos = 1; + for (unsigned int i = 0; i <= numPixel; i += 3) { + if (i + _pos <= numPixel) { + pixels[i + _pos].setPixel(_baseColorRed, _baseColorGreen, + _baseColorBlue); + } + } + } else + lastShow = millis(); + newData = true; } void MrlNeopixel::animationWheel(unsigned char WheelPos, Pixel& pixel) { - WheelPos = 255 - WheelPos; - if(WheelPos < 85) { - pixel.setPixel(255 - WheelPos * 3, 0 , WheelPos * 3); - } - else if(WheelPos < 170) { - WheelPos -= 85; - pixel.setPixel(0, WheelPos * 3, 255 - WheelPos * 3); - } - else { - WheelPos -= 170; - pixel.setPixel(WheelPos * 3, 255 - WheelPos * 3, 0); - } + WheelPos = 255 - WheelPos; + if (WheelPos < 85) { + pixel.setPixel(255 - WheelPos * 3, 0, WheelPos * 3); + } else if (WheelPos < 170) { + WheelPos -= 85; + pixel.setPixel(0, WheelPos * 3, 255 - WheelPos * 3); + } else { + WheelPos -= 170; + pixel.setPixel(WheelPos * 3, 255 - WheelPos * 3, 0); + } } void MrlNeopixel::animationTheaterChaseRainbow() { - if(!((_count++)%_speed)) { - for (unsigned int i = 0; i <= numPixel; i+=3){ - if(i + _pos <= numPixel){ - pixels[i + _pos].clearPixel(); - } - } - _pos++; - if(_pos >= 4) _pos = 1; - for (unsigned int i = 0; i <= numPixel; i+=3){ - if(i + _pos <= numPixel){ - animationWheel((_baseColorRed + i), pixels[i + _pos]); - } - } - _baseColorRed++; - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + for (unsigned int i = 0; i <= numPixel; i += 3) { + if (i + _pos <= numPixel) { + pixels[i + _pos].clearPixel(); + } + } + _pos++; + if (_pos >= 4) + _pos = 1; + for (unsigned int i = 0; i <= numPixel; i += 3) { + if (i + _pos <= numPixel) { + animationWheel((_baseColorRed + i), pixels[i + _pos]); + } + } + _baseColorRed++; + } else + lastShow = millis(); + newData = true; } void MrlNeopixel::animationRainbow() { - if(!((_count++)%_speed)) { - for (unsigned int i = 0; i <= numPixel; i++){ - animationWheel((_baseColorRed + i), pixels[i]); - } - _baseColorRed++; - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + for (unsigned int i = 0; i <= numPixel; i++) { + animationWheel((_baseColorRed + i), pixels[i]); + } + _baseColorRed++; + } else + lastShow = millis(); + newData = true; } void MrlNeopixel::animationRainbowCycle() { - if(!((_count++)%_speed)) { - for (unsigned int i = 0; i <= numPixel; i++){ - animationWheel((i * 256 / numPixel) + _baseColorRed, pixels[i]); - } - _baseColorRed++; - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + for (unsigned int i = 0; i <= numPixel; i++) { + animationWheel((i * 256 / numPixel) + _baseColorRed, pixels[i]); + } + _baseColorRed++; + } else + lastShow = millis(); + newData = true; } void MrlNeopixel::animationFlashRandom() { - if(!((_count++)%_speed)) { - if(_step == 1){ - _pos = random(numPixel)+1; - } - if (_step < 6){ - int r = (_baseColorRed * _step) / 5; - int g = (_baseColorGreen * _step) / 5; - int b = (_baseColorBlue * _step) / 5; - pixels[_pos].setPixel(r, g, b); - } - else{ - int r = (_baseColorRed * (11-_step)) / 5; - int g = (_baseColorGreen * (11-_step)) / 5; - int b = (_baseColorBlue * (11-_step)) / 5; - pixels[_pos].setPixel(r, g, b); - } - _step++; - if(_step > 11) _step = 1; - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + if (_step == 1) { + _pos = random(numPixel) + 1; + } + if (_step < 6) { + int r = (_baseColorRed * _step) / 5; + int g = (_baseColorGreen * _step) / 5; + int b = (_baseColorBlue * _step) / 5; + pixels[_pos].setPixel(r, g, b); + } else { + int r = (_baseColorRed * (11 - _step)) / 5; + int g = (_baseColorGreen * (11 - _step)) / 5; + int b = (_baseColorBlue * (11 - _step)) / 5; + pixels[_pos].setPixel(r, g, b); + } + _step++; + if (_step > 11) + _step = 1; + } else + lastShow = millis(); + newData = true; } void MrlNeopixel::animationIronman() { - if(!((_count++)%_speed)) { - int flip = random(32); - if (flip > 22) _dir = -_dir; - _alpha += 5 * _dir; - if (_alpha < 5) { - _alpha = 5; - _dir = 1; - } - if (_alpha > 100) { - _alpha = 100; - _dir = -1; - } - for (unsigned int i = 1; i <= numPixel; i++){ - pixels[i].setPixel((_baseColorRed * _alpha) / 100, (_baseColorGreen * _alpha) / 100, (_baseColorBlue * _alpha) / 100); - } - } - else lastShow = millis(); - newData = true; + if (!((_count++) % _speed)) { + int flip = random(32); + if (flip > 22) + _dir = -_dir; + _alpha += 5 * _dir; + if (_alpha < 5) { + _alpha = 5; + _dir = 1; + } + if (_alpha > 100) { + _alpha = 100; + _dir = -1; + } + for (unsigned int i = 1; i <= numPixel; i++) { + pixels[i].setPixel((_baseColorRed * _alpha) / 100, + (_baseColorGreen * _alpha) / 100, + (_baseColorBlue * _alpha) / 100); + } + } else + lastShow = millis(); + newData = true; } diff --git a/MrlNeopixel.h b/MrlNeopixel.h index bd1513b..2652c61 100644 --- a/MrlNeopixel.h +++ b/MrlNeopixel.h @@ -1,8 +1,7 @@ #ifndef MrlNeopixel_h #define MrlNeopixel_h -#include "Device.h" -#include "MrlMsg.h" +#include /*********************************************************************** * NEOPIXEL DEFINE @@ -49,6 +48,8 @@ #define NEOPIXEL_ANIMATION_FLASH_RANDOM 8 #define NEOPIXEL_ANIMATION_IRONMAN 9 +class Msg; + /***************************** * Neopixel device * @@ -86,9 +87,9 @@ class MrlNeopixel:public Device{ int _step; unsigned char _alpha; public: - MrlNeopixel(); + MrlNeopixel(int deviceId); ~MrlNeopixel(); - bool deviceAttach(unsigned char config[], int configSize); + bool attach(byte pin, long numPixels); inline void sendBitB(bool bitVal); inline void sendBitC(bool bitVal); inline void sendBitD(bool bitVal); @@ -105,9 +106,9 @@ class MrlNeopixel:public Device{ inline void sendByte(unsigned char byte); inline void sendPixel(Pixel p); void show(); - void neopixelWriteMatrix(unsigned char* ioCmd); + void neopixelWriteMatrix(byte bufferSize, const byte*buffer); void update(); - void setAnimation(unsigned char* config); + void setAnimation ( byte animation, byte red, byte green, byte blue, int speed); void animationStop(); void animationColorWipe(); void animationLarsonScanner(); diff --git a/MrlPulse.h b/MrlPulse.h index f416e2e..4b7578d 100644 --- a/MrlPulse.h +++ b/MrlPulse.h @@ -1,73 +1,69 @@ -#ifndef MrlPulse_h -#define MrlPulse_h - -#include "Device.h" -#include "Pin.h" -#include "MrlMsg.h" - -/** - * Pulse Sensor Device - * TODO: add a description about this device! How does it work? What is it? - */ -class MrlPulse : public Device { - public: - unsigned long lastValue; - int count; - Pin* pin; - MrlPulse() : Device(SENSOR_TYPE_PULSE) { - count=0; - } - ~MrlPulse() { - if (pin) delete pin; - } - void pulse(unsigned char* ioCmd) { - if (!pin) return; - pin->count = 0; - pin->target = toLong(ioCmd,2); - pin->rate = ioCmd[6]; - pin->rateModulus = ioCmd[7]; - pin->state = PUBLISH_SENSOR_DATA; - } - void pulseStop() { - pin->state = PUBLISH_PULSE_STOP; - } - void update() { - //this need work - if (type == 0) return; - lastValue = (lastValue == 0) ? 1 : 0; - // leading edge ... 0 to 1 - if (lastValue == 1) { - count++; - if (pin->count >= pin->target) { - pin->state = PUBLISH_PULSE_STOP; - } - } - // change state of pin - digitalWrite(pin->address, lastValue); - // move counter/current position - // see if feedback rate is valid - // if time to send feedback do it - // if (loopCount%feedbackRate == 0) - // 0--to-->1 counting leading edge only - // pin.method == PUBLISH_PULSE_PIN && - // stopped on the leading edge - if (pin->state != PUBLISH_PULSE_STOP && lastValue == 1) { - // TODO: support publish pulse stop! - // publishPulseStop(pin.state, pin.sensorIndex, pin.address, sensor.count); - // deactivate - // lastDebounceTime[digitalReadPin[i]] = millis(); - // test git - } - if (pin->state == PUBLISH_PULSE_STOP) { - //pin.isActive = false; - // TODO: support publish pulse stop! - // TODO: if we're not active, remove ourselves from the device list? - } - // publish the pulse! - // TODO: support publishPuse! - // publishPulse(pin.state, pin.sensorIndex, pin.address, pin.count); - } - -}; - +#ifndef MrlPulse_h +#define MrlPulse_h + +/** + * Pulse Sensor Device + * TODO: add a description about this device! How does it work? What is it? + */ +class MrlPulse : public Device { + public: + unsigned long lastValue; + int count; + Pin* pin; + MrlPulse() : Device(SENSOR_TYPE_PULSE) { + count=0; + } + ~MrlPulse() { + if (pin) delete pin; + } + void pulse(unsigned char* ioCmd) { + if (!pin) return; + pin->count = 0; + pin->target = toLong(ioCmd,2); + pin->rate = ioCmd[6]; + pin->rateModulus = ioCmd[7]; + pin->state = PUBLISH_SENSOR_DATA; + } + void pulseStop() { + pin->state = PUBLISH_PULSE_STOP; + } + void update() { + //this need work + if (type == 0) return; + lastValue = (lastValue == 0) ? 1 : 0; + // leading edge ... 0 to 1 + if (lastValue == 1) { + count++; + if (pin->count >= pin->target) { + pin->state = PUBLISH_PULSE_STOP; + } + } + // change state of pin + digitalWrite(pin->address, lastValue); + // move counter/current position + // see if feedback rate is valid + // if time to send feedback do it + // if (loopCount%feedbackRate == 0) + // 0--to-->1 counting leading edge only + // pin.method == PUBLISH_PULSE_PIN && + // stopped on the leading edge + if (pin->state != PUBLISH_PULSE_STOP && lastValue == 1) { + // TODO: support publish pulse stop! + // publishPulseStop(pin.state, pin.sensorIndex, pin.address, sensor.count); + // deactivate + // lastDebounceTime[digitalReadPin[i]] = millis(); + // test git + } + if (pin->state == PUBLISH_PULSE_STOP) { + //pin.isActive = false; + // TODO: support publish pulse stop! + // TODO: if we're not active, remove ourselves from the device list? + } + // publish the pulse! + // TODO: support publishPuse! + // publishPulse(pin.state, pin.sensorIndex, pin.address, pin.count); + } + +}; + #endif diff --git a/MrlServo.cpp b/MrlServo.cpp index 594f674..78a6614 100644 --- a/MrlServo.cpp +++ b/MrlServo.cpp @@ -1,6 +1,9 @@ +#include +#include "Msg.h" +#include "Device.h" #include "MrlServo.h" -MrlServo::MrlServo() : Device(DEVICE_TYPE_SERVO) { +MrlServo::MrlServo(int deviceId) : Device(deviceId, DEVICE_TYPE_SERVO) { isMoving = false; isSweeping = false; // create the servo @@ -8,7 +11,7 @@ MrlServo::MrlServo() : Device(DEVICE_TYPE_SERVO) { lastUpdate = 0; currentPos = 0.0; targetPos = 0; - velocity = 0; + velocity = -1; } MrlServo::~MrlServo() { @@ -20,44 +23,28 @@ MrlServo::~MrlServo() { // this method "may" be called with a pin or pin & pos depending on // config size -bool MrlServo::deviceAttach(unsigned char config[], int configSize){ - if (configSize < 1 || configSize > 4){ - MrlMsg msg(PUBLISH_MRLCOMM_ERROR); - msg.addData(ERROR_DOES_NOT_EXIST); - msg.addData(String(F("MrlServo invalid attach config size"))); - return false; - } - attachDevice(); - pin = config[0]; - if (configSize == 2) { - velocity = 0; - //servoWrite(config[1]); - servo->write(config[1]); - currentPos = config[1]; - targetPos = config[1]; - } - else if (configSize == 4) { - velocity = MrlMsg::toInt(config,2); - //servoWrite(config[1]); - servo->write(config[1]); - currentPos = config[1]; - targetPos = config[1]; - } +bool MrlServo::attach(byte pin, byte initPos, int initVelocity){ + // msg->publishDebug("MrlServo.deviceAttach !!!"); + servo->write(initPos); + currentPos = initPos; + targetPos = initPos; + velocity = initVelocity; servo->attach(pin); return true; } // This method is equivalent to Arduino's Servo.attach(pin) - (no pos) -void MrlServo::attach(int pin){ +void MrlServo::enablePwm(int pin){ servo->attach(pin); servo->write((int)currentPos); //return to it's last know state (may be 0 if currentPos is not set) // TODO-KW: we should always have a moveTo for safety, o/w we have no idea what angle we're going to start up at.. maybe } -void MrlServo::detach(){ +void MrlServo::disablePwm(){ servo->detach(); } +// FIXME - what happened to events ? void MrlServo::update() { //it may have an imprecision of +- 1 due to the conversion of currentPos to int if (isMoving) { @@ -68,7 +55,7 @@ void MrlServo::update() { if (isSweeping) { step = sweepStep; } - if (velocity == 0) { // when velocity == 0, it mean full speed ahead + if (velocity < 0) { // when velocity < 0, it mean full speed ahead step = targetPos - currentPos; } else if ((int)currentPos > targetPos) { diff --git a/MrlServo.h b/MrlServo.h index ff94042..9512245 100644 --- a/MrlServo.h +++ b/MrlServo.h @@ -1,9 +1,6 @@ #ifndef MrlServo_h #define MrlServo_h -#include -#include "Device.h" -#include "MrlMsg.h" // servo event types // ===== published sub-types based on device type begin === @@ -25,15 +22,16 @@ class MrlServo : public Device { int min; int max; unsigned long lastUpdate; - unsigned int velocity; // in deg/sec + int velocity; // in deg/sec | velocity < 0 == no speed control int sweepStep; unsigned int maxVelocity; + public: - MrlServo(); + MrlServo(int deviceId); ~MrlServo(); - bool deviceAttach(unsigned char config[], int configSize); - void attach(int pin); - void detach(); + bool attach(byte pin, byte initPos, int initVelocity); + void enablePwm(int pin); + void disablePwm(); void update(); void servoWrite(int position); void servoWriteMicroseconds(int position); diff --git a/MrlStepper.h b/MrlStepper.h index fb836fb..1352ba8 100644 --- a/MrlStepper.h +++ b/MrlStepper.h @@ -1,21 +1,19 @@ -#ifndef MrlStepper_h -#define MrlStepper_h - -/** - * Stepper Device - */ - -#include "Device.h" - -class MrlStepper : public Device { - // details of the different motor controls/types - public: - MrlStepper() : Device(DEVICE_TYPE_STEPPER) { - - } - void update() { - } -}; - - +#ifndef MrlStepper_h +#define MrlStepper_h + +/** + * Stepper Device + */ + +class MrlStepper : public Device { + // details of the different motor controls/types + public: + MrlStepper() : Device(DEVICE_TYPE_STEPPER) { + + } + void update() { + } +}; + + #endif diff --git a/MrlUltrasonic.h b/MrlUltrasonic.h deleted file mode 100644 index 02b12b2..0000000 --- a/MrlUltrasonic.h +++ /dev/null @@ -1,96 +0,0 @@ -#ifndef MrlUltrasonic_h -#define MrlUltrasonic_h - -#include "Device.h" -#include "LinkedList.h" -#include "MrlMsg.h" - -/** - * Ultrasonic Sensor - * TODO: add a description about this device, what is it? what does it do? - * How does it work? - */ -class MrlUltrasonic : public Device { - public: - int trigPin; - int echoPin; - LinkedList pins; // the pins currently assigned to this sensor 0 - unsigned long ts; - unsigned long lastValue; - int timeoutUS; - MrlUltrasonic() : Device(SENSOR_TYPE_ULTRASONIC) { - timeoutUS=0; //this need to be set - trigPin=0;//this need to be set - echoPin=0;//this need to be set - } - ~MrlUltrasonic() { - while(pins.size()>0){ - delete pins.pop(); - } - - } - void update() { - //This need to be reworked - if (type == 0) return; - Pin* pin = pins.get(0); - if (pin->state == ECHO_STATE_START) { - // trigPin prepare - start low for an - // upcoming high pulse - pinMode(trigPin, OUTPUT); - digitalWrite(trigPin, LOW); - // put the echopin into a high state - // is this necessary ??? - pinMode(echoPin, OUTPUT); - digitalWrite(echoPin, HIGH); - unsigned long newts = micros(); - if (newts - ts > 2) { - ts = newts; - pin->state = ECHO_STATE_TRIG_PULSE_BEGIN; - } - } else if (pin->state == ECHO_STATE_TRIG_PULSE_BEGIN) { - // begin high pulse for at least 10 us - pinMode(trigPin, OUTPUT); - digitalWrite(trigPin, HIGH); - unsigned long newts = micros(); - if (newts - ts > 10) { - ts = newts; - pin->state = ECHO_STATE_TRIG_PULSE_END; - } - } else if (pin->state == ECHO_STATE_TRIG_PULSE_END) { - // end of pulse - pinMode(trigPin, OUTPUT); - digitalWrite(trigPin, LOW); - pin->state = ECHO_STATE_MIN_PAUSE_PRE_LISTENING; - ts = micros(); - } else if (pin->state == ECHO_STATE_MIN_PAUSE_PRE_LISTENING) { - unsigned long newts = micros(); - if (newts - ts > 1500) { - ts = newts; - // putting echo pin into listen mode - pinMode(echoPin, OUTPUT); - digitalWrite(echoPin, HIGH); - pinMode(echoPin, INPUT); - pin->state = ECHO_STATE_LISTENING; - } - } else if (pin->state == ECHO_STATE_LISTENING) { - // timeout or change states.. - int value = digitalRead(echoPin); - unsigned long newts = micros(); - if (value == LOW) { - lastValue = newts - ts; - ts = newts; - pin->state = ECHO_STATE_GOOD_RANGE; - } else if (newts - ts > timeoutUS) { - pin->state = ECHO_STATE_TIMEOUT; - ts = newts; - lastValue = 0; - } - } else if (pin->state == ECHO_STATE_GOOD_RANGE || pin->state == ECHO_STATE_TIMEOUT) { - // publishSensorDataLong(pin.address, sensor.lastValue); - pin->state = ECHO_STATE_START; - } // end else if - } -}; - - -#endif diff --git a/MrlUltrasonicSensor.cpp b/MrlUltrasonicSensor.cpp new file mode 100644 index 0000000..ad9565e --- /dev/null +++ b/MrlUltrasonicSensor.cpp @@ -0,0 +1,100 @@ +#include "Msg.h" +#include "Device.h" +#include "MrlUltrasonicSensor.h" + +MrlUltrasonicSensor::MrlUltrasonicSensor(int deviceId) : Device(deviceId, DEVICE_TYPE_ULTRASONIC) { + msg->publishDebug("ctor MrlUltrasonicSensor " + String(deviceId)); + timeoutUS=1000; //this need to be set + trigPin=0;//this need to be set + echoPin=0;//this need to be set +} + +MrlUltrasonicSensor::~MrlUltrasonicSensor() {} + +void MrlUltrasonicSensor::attach(byte trigPin, byte echoPin){ + msg->publishDebug("Ultrasonic.attach " + String(trigPin) + " " + String(echoPin)); + this->trigPin = trigPin; + this->echoPin = echoPin; +} + +void MrlUltrasonicSensor::startRanging(long timeout) { + msg->publishDebug("Ultrasonic.startRanging " + String(timeout)); + isRanging = true; + state = ECHO_STATE_START; +} + +void MrlUltrasonicSensor::stopRanging() { + msg->publishDebug(F("Ultrasonic.stopRanging")); + isRanging = false; +} + +void MrlUltrasonicSensor::update() { + + if (!isRanging){ + return; + } + + msg->publishDebug("state " + String(state)); + + ++lastValue; + msg->publishUltrasonicSensorData(id, lastValue); + return; + + if (state == ECHO_STATE_START) { + // trigPin prepare - start low for an + // upcoming high pulse + pinMode(trigPin, OUTPUT); + digitalWrite(trigPin, LOW); + // put the echopin into a high state + // is this necessary ??? + pinMode(echoPin, OUTPUT); + digitalWrite(echoPin, HIGH); + unsigned long newts = micros(); + if (newts - ts > 2) { + ts = newts; + state = ECHO_STATE_TRIG_PULSE_BEGIN; + } + } else if (state == ECHO_STATE_TRIG_PULSE_BEGIN) { + // begin high pulse for at least 10 us + pinMode(trigPin, OUTPUT); + digitalWrite(trigPin, HIGH); + unsigned long newts = micros(); + if (newts - ts > 10) { + ts = newts; + state = ECHO_STATE_TRIG_PULSE_END; + } + } else if (state == ECHO_STATE_TRIG_PULSE_END) { + // end of pulse + pinMode(trigPin, OUTPUT); + digitalWrite(trigPin, LOW); + state = ECHO_STATE_MIN_PAUSE_PRE_LISTENING; + ts = micros(); + } else if (state == ECHO_STATE_MIN_PAUSE_PRE_LISTENING) { + unsigned long newts = micros(); + if (newts - ts > 1500) { + ts = newts; + // putting echo pin into listen mode + pinMode(echoPin, OUTPUT); + digitalWrite(echoPin, HIGH); + pinMode(echoPin, INPUT); + state = ECHO_STATE_LISTENING; + } + } else if (state == ECHO_STATE_LISTENING) { + // timeout or change states.. + int value = digitalRead(echoPin); + unsigned long newts = micros(); + if (value == LOW) { + lastValue = newts - ts; + ts = newts; + state = ECHO_STATE_GOOD_RANGE; + } else if (newts - ts > timeoutUS) { + state = ECHO_STATE_TIMEOUT; + ts = newts; + lastValue = 0; + } + } else if (state == ECHO_STATE_GOOD_RANGE || state == ECHO_STATE_TIMEOUT) { + msg->publishUltrasonicSensorData(id, lastValue); + state = ECHO_STATE_START; + } // end else if +} + diff --git a/MrlUltrasonicSensor.h b/MrlUltrasonicSensor.h new file mode 100644 index 0000000..191351d --- /dev/null +++ b/MrlUltrasonicSensor.h @@ -0,0 +1,36 @@ +#ifndef MrlUltrasonicSensor_h +#define MrlUltrasonicSensor_h + +// ECHO FINITE STATE MACHINE - NON BLOCKING PULSIN +#define ECHO_STATE_START 1 +#define ECHO_STATE_TRIG_PULSE_BEGIN 2 +#define ECHO_STATE_TRIG_PULSE_END 3 +#define ECHO_STATE_MIN_PAUSE_PRE_LISTENING 4 +#define ECHO_STATE_LISTENING 5 +#define ECHO_STATE_GOOD_RANGE 6 +#define ECHO_STATE_TIMEOUT 7 + +/** + * Ultrasonic Sensor + * TODO: add a description about this device, what is it? what does it do? + * How does it work? + */ +class MrlUltrasonicSensor : public Device { + public: + int trigPin; + int echoPin; + unsigned long ts; + unsigned long lastValue; + unsigned long timeoutUS; + bool isRanging = false; + + MrlUltrasonicSensor(int deviceId); + ~MrlUltrasonicSensor(); + + void attach(byte trigPin, byte echoPin); + void update(); + void startRanging(long timeout); + void stopRanging(); +}; + +#endif diff --git a/Msg.cpp b/Msg.cpp new file mode 100644 index 0000000..0c44eaa --- /dev/null +++ b/Msg.cpp @@ -0,0 +1,757 @@ +/** + *
+ *
+ Welcome to Msg.java
+ Its created by running ArduinoMsgGenerator
+ which combines the MrlComm message schema (src/resource/Arduino/arduinoMsg.schema)
+ with the cpp template (src/resource/Arduino/generate/Msg.template.cpp)
+
+ 	Schema Type Conversions
+
+	Schema      ARDUINO					Java							Range
+	none		byte/unsigned char		int (cuz Java byte bites)		1 byte - 0 to 255
+	boolean		boolean					boolean							0 1
+    b16			int						int (short)						2 bytes	-32,768 to 32,767
+    b32			long					int								4 bytes -2,147,483,648 to 2,147,483, 647
+    bu32		unsigned long			long							0 to 4,294,967,295
+    str			char*, size				String							variable length
+    []			byte[], size			int[]							variable length
+
+ All message editing should be done in the arduinoMsg.schema
+
+ The binary wire format of an Arduino is:
+
+ MAGIC_NUMBER|MSG_SIZE|METHOD_NUMBER|PARAM0|PARAM1 ...
+
+ 
+ + */ + +#include "Msg.h" +#include "LinkedList.h" +#include "MrlComm.h" + +Msg* Msg::instance = NULL; + +Msg::Msg() { + this->mrlComm = mrlComm; +} + +Msg::~Msg() { +} + +// the two singleton methods - the one with the MrlComm paramters +// must be used for initialization +Msg* Msg::getInstance(MrlComm* mrlComm) { + instance = new Msg(); + instance->mrlComm = mrlComm; + return instance; +} + +Msg* Msg::getInstance() { + return instance; +} + +/** + * Expected Interface - these are the method signatures which will be called + * by Msg class + * + * PC --serialized--> Msg --de-serialized--> MrlComm.method(parm0, param1, ...) + * + // > getBoardInfo + void getBoardInfo(); + // > enableBoardStatus/bool enabled + void enableBoardStatus( boolean enabled); + // > enablePin/address/type/b16 rate + void enablePin( byte address, byte type, int rate); + // > setDebug/bool enabled + void setDebug( boolean enabled); + // > setSerialRate/b32 rate + void setSerialRate( long rate); + // > softReset + void softReset(); + // > enableAck/bool enabled + void enableAck( boolean enabled); + // > enableHeartbeat/bool enabled + void enableHeartbeat( boolean enabled); + // > heartbeat + void heartbeat(); + // > echo/bu32 sInt + void echo( unsigned long sInt); + // > controllerAttach/serialPort + void controllerAttach( byte serialPort); + // > customMsg/[] msg + void customMsg( byte msgSize, const byte*msg); + // > deviceDetach/deviceId + void deviceDetach( byte deviceId); + // > i2cBusAttach/deviceId/i2cBus + void i2cBusAttach( byte deviceId, byte i2cBus); + // > i2cRead/deviceId/deviceAddress/size + void i2cRead( byte deviceId, byte deviceAddress, byte size); + // > i2cWrite/deviceId/deviceAddress/[] data + void i2cWrite( byte deviceId, byte deviceAddress, byte dataSize, const byte*data); + // > i2cWriteRead/deviceId/deviceAddress/readSize/writeValue + void i2cWriteRead( byte deviceId, byte deviceAddress, byte readSize, byte writeValue); + // > neoPixelAttach/deviceId/pin/b32 numPixels + void neoPixelAttach( byte deviceId, byte pin, long numPixels); + // > neoPixelSetAnimation/deviceId/animation/red/green/blue/b16 speed + void neoPixelSetAnimation( byte deviceId, byte animation, byte red, byte green, byte blue, int speed); + // > neoPixelWriteMatrix/deviceId/[] buffer + void neoPixelWriteMatrix( byte deviceId, byte bufferSize, const byte*buffer); + // > disablePin/pin + void disablePin( byte pin); + // > disablePins + void disablePins(); + // > setTrigger/pin/triggerValue + void setTrigger( byte pin, byte triggerValue); + // > setDebounce/pin/delay + void setDebounce( byte pin, byte delay); + // > servoAttach/deviceId/pin/initPos/b16 initVelocity + void servoAttach( byte deviceId, byte pin, byte initPos, int initVelocity); + // > servoEnablePwm/deviceId/pin + void servoEnablePwm( byte deviceId, byte pin); + // > servoDisablePwm/deviceId + void servoDisablePwm( byte deviceId); + // > servoSetMaxVelocity/deviceId/b16 maxVelocity + void servoSetMaxVelocity( byte deviceId, int maxVelocity); + // > servoSetVelocity/deviceId/b16 velocity + void servoSetVelocity( byte deviceId, int velocity); + // > servoSweepStart/deviceId/min/max/step + void servoSweepStart( byte deviceId, byte min, byte max, byte step); + // > servoSweepStop/deviceId + void servoSweepStop( byte deviceId); + // > servoWrite/deviceId/target + void servoWrite( byte deviceId, byte target); + // > servoWriteMicroseconds/deviceId/b16 ms + void servoWriteMicroseconds( byte deviceId, int ms); + // > serialAttach/deviceId/relayPin + void serialAttach( byte deviceId, byte relayPin); + // > serialRelay/deviceId/[] data + void serialRelay( byte deviceId, byte dataSize, const byte*data); + // > ultrasonicSensorAttach/deviceId/triggerPin/echoPin + void ultrasonicSensorAttach( byte deviceId, byte triggerPin, byte echoPin); + // > ultrasonicSensorStartRanging/deviceId/b32 timeout + void ultrasonicSensorStartRanging( byte deviceId, long timeout); + // > ultrasonicSensorStopRanging/deviceId + void ultrasonicSensorStopRanging( byte deviceId); + + */ + + +void Msg::publishMRLCommError(const char* errorMsg, byte errorMsgSize) { + write(MAGIC_NUMBER); + write(1 + (1 + errorMsgSize)); // size + write(PUBLISH_MRLCOMM_ERROR); // msgType = 1 + write((byte*)errorMsg, errorMsgSize); + flush(); + reset(); +} + +void Msg::publishBoardInfo( byte version, byte boardType) { + write(MAGIC_NUMBER); + write(1 + 1 + 1); // size + write(PUBLISH_BOARD_INFO); // msgType = 3 + write(version); + write(boardType); + flush(); + reset(); +} + +void Msg::publishAck( byte function) { + write(MAGIC_NUMBER); + write(1 + 1); // size + write(PUBLISH_ACK); // msgType = 10 + write(function); + flush(); + reset(); +} + +void Msg::publishHeartbeat() { + write(MAGIC_NUMBER); + write(1); // size + write(PUBLISH_HEARTBEAT); // msgType = 13 + flush(); + reset(); +} + +void Msg::publishEcho( unsigned long sInt) { + write(MAGIC_NUMBER); + write(1 + 4); // size + write(PUBLISH_ECHO); // msgType = 15 + writebu32(sInt); + flush(); + reset(); +} + +void Msg::publishCustomMsg(const byte* msg, byte msgSize) { + write(MAGIC_NUMBER); + write(1 + (1 + msgSize)); // size + write(PUBLISH_CUSTOM_MSG); // msgType = 18 + write((byte*)msg, msgSize); + flush(); + reset(); +} + +void Msg::publishI2cData( byte deviceId, const byte* data, byte dataSize) { + write(MAGIC_NUMBER); + write(1 + 1 + (1 + dataSize)); // size + write(PUBLISH_I2C_DATA); // msgType = 24 + write(deviceId); + write((byte*)data, dataSize); + flush(); + reset(); +} + +void Msg::publishAttachedDevice( byte deviceId, const char* deviceName, byte deviceNameSize) { + write(MAGIC_NUMBER); + write(1 + 1 + (1 + deviceNameSize)); // size + write(PUBLISH_ATTACHED_DEVICE); // msgType = 33 + write(deviceId); + write((byte*)deviceName, deviceNameSize); + flush(); + reset(); +} + +void Msg::publishBoardStatus( int microsPerLoop, int sram, const byte* deviceSummary, byte deviceSummarySize) { + write(MAGIC_NUMBER); + write(1 + 2 + 2 + (1 + deviceSummarySize)); // size + write(PUBLISH_BOARD_STATUS); // msgType = 34 + writeb16(microsPerLoop); + writeb16(sram); + write((byte*)deviceSummary, deviceSummarySize); + flush(); + reset(); +} + +void Msg::publishDebug(const char* debugMsg, byte debugMsgSize) { + write(MAGIC_NUMBER); + write(1 + (1 + debugMsgSize)); // size + write(PUBLISH_DEBUG); // msgType = 35 + write((byte*)debugMsg, debugMsgSize); + flush(); + reset(); +} + +void Msg::publishPinArray(const byte* data, byte dataSize) { + write(MAGIC_NUMBER); + write(1 + (1 + dataSize)); // size + write(PUBLISH_PIN_ARRAY); // msgType = 36 + write((byte*)data, dataSize); + flush(); + reset(); +} + +void Msg::publishSerialData( byte deviceId, const byte* data, byte dataSize) { + write(MAGIC_NUMBER); + write(1 + 1 + (1 + dataSize)); // size + write(PUBLISH_SERIAL_DATA); // msgType = 50 + write(deviceId); + write((byte*)data, dataSize); + flush(); + reset(); +} + +void Msg::publishUltrasonicSensorData( byte deviceId, int echoTime) { + write(MAGIC_NUMBER); + write(1 + 1 + 2); // size + write(PUBLISH_ULTRASONIC_SENSOR_DATA); // msgType = 54 + write(deviceId); + writeb16(echoTime); + flush(); + reset(); +} + + +void Msg::processCommand() { + + int startPos = 0; + int method = ioCmd[0]; + + switch (method) { + case GET_BOARD_INFO: { // getBoardInfo + mrlComm->getBoardInfo(); + break; + } + case ENABLE_BOARD_STATUS: { // enableBoardStatus + boolean enabled = (ioCmd[startPos+1]); + startPos += 1; + mrlComm->enableBoardStatus( enabled); + break; + } + case ENABLE_PIN: { // enablePin + byte address = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte type = ioCmd[startPos+1]; // bu8 + startPos += 1; + int rate = b16(ioCmd, startPos+1); + startPos += 2; //b16 + mrlComm->enablePin( address, type, rate); + break; + } + case SET_DEBUG: { // setDebug + boolean enabled = (ioCmd[startPos+1]); + startPos += 1; + mrlComm->setDebug( enabled); + break; + } + case SET_SERIAL_RATE: { // setSerialRate + long rate = b32(ioCmd, startPos+1); + startPos += 4; //b32 + mrlComm->setSerialRate( rate); + break; + } + case SOFT_RESET: { // softReset + mrlComm->softReset(); + break; + } + case ENABLE_ACK: { // enableAck + boolean enabled = (ioCmd[startPos+1]); + startPos += 1; + mrlComm->enableAck( enabled); + break; + } + case ENABLE_HEARTBEAT: { // enableHeartbeat + boolean enabled = (ioCmd[startPos+1]); + startPos += 1; + mrlComm->enableHeartbeat( enabled); + break; + } + case HEARTBEAT: { // heartbeat + mrlComm->heartbeat(); + break; + } + case ECHO: { // echo + unsigned long sInt = bu32(ioCmd, startPos+1); + startPos += 4; //bu32 + mrlComm->echo( sInt); + break; + } + case CONTROLLER_ATTACH: { // controllerAttach + byte serialPort = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->controllerAttach( serialPort); + break; + } + case CUSTOM_MSG: { // customMsg + const byte* msg = ioCmd+startPos+2; + byte msgSize = ioCmd[startPos+1]; + startPos += 1 + ioCmd[startPos+1]; + mrlComm->customMsg( msgSize, msg); + break; + } + case DEVICE_DETACH: { // deviceDetach + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->deviceDetach( deviceId); + break; + } + case I2C_BUS_ATTACH: { // i2cBusAttach + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte i2cBus = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->i2cBusAttach( deviceId, i2cBus); + break; + } + case I2C_READ: { // i2cRead + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte deviceAddress = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte size = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->i2cRead( deviceId, deviceAddress, size); + break; + } + case I2C_WRITE: { // i2cWrite + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte deviceAddress = ioCmd[startPos+1]; // bu8 + startPos += 1; + const byte* data = ioCmd+startPos+2; + byte dataSize = ioCmd[startPos+1]; + startPos += 1 + ioCmd[startPos+1]; + mrlComm->i2cWrite( deviceId, deviceAddress, dataSize, data); + break; + } + case I2C_WRITE_READ: { // i2cWriteRead + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte deviceAddress = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte readSize = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte writeValue = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->i2cWriteRead( deviceId, deviceAddress, readSize, writeValue); + break; + } + case NEO_PIXEL_ATTACH: { // neoPixelAttach + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + long numPixels = b32(ioCmd, startPos+1); + startPos += 4; //b32 + mrlComm->neoPixelAttach( deviceId, pin, numPixels); + break; + } + case NEO_PIXEL_SET_ANIMATION: { // neoPixelSetAnimation + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte animation = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte red = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte green = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte blue = ioCmd[startPos+1]; // bu8 + startPos += 1; + int speed = b16(ioCmd, startPos+1); + startPos += 2; //b16 + mrlComm->neoPixelSetAnimation( deviceId, animation, red, green, blue, speed); + break; + } + case NEO_PIXEL_WRITE_MATRIX: { // neoPixelWriteMatrix + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + const byte* buffer = ioCmd+startPos+2; + byte bufferSize = ioCmd[startPos+1]; + startPos += 1 + ioCmd[startPos+1]; + mrlComm->neoPixelWriteMatrix( deviceId, bufferSize, buffer); + break; + } + case ANALOG_WRITE: { // analogWrite + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte value = ioCmd[startPos+1]; // bu8 + startPos += 1; + analogWrite( pin, value); + break; + } + case DIGITAL_WRITE: { // digitalWrite + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte value = ioCmd[startPos+1]; // bu8 + startPos += 1; + digitalWrite( pin, value); + break; + } + case DISABLE_PIN: { // disablePin + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->disablePin( pin); + break; + } + case DISABLE_PINS: { // disablePins + mrlComm->disablePins(); + break; + } + case PIN_MODE: { // pinMode + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte mode = ioCmd[startPos+1]; // bu8 + startPos += 1; + pinMode( pin, mode); + break; + } + case SET_TRIGGER: { // setTrigger + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte triggerValue = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->setTrigger( pin, triggerValue); + break; + } + case SET_DEBOUNCE: { // setDebounce + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte delay = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->setDebounce( pin, delay); + break; + } + case SERVO_ATTACH: { // servoAttach + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte initPos = ioCmd[startPos+1]; // bu8 + startPos += 1; + int initVelocity = b16(ioCmd, startPos+1); + startPos += 2; //b16 + mrlComm->servoAttach( deviceId, pin, initPos, initVelocity); + break; + } + case SERVO_ENABLE_PWM: { // servoEnablePwm + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte pin = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->servoEnablePwm( deviceId, pin); + break; + } + case SERVO_DISABLE_PWM: { // servoDisablePwm + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->servoDisablePwm( deviceId); + break; + } + case SERVO_SET_MAX_VELOCITY: { // servoSetMaxVelocity + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + int maxVelocity = b16(ioCmd, startPos+1); + startPos += 2; //b16 + mrlComm->servoSetMaxVelocity( deviceId, maxVelocity); + break; + } + case SERVO_SET_VELOCITY: { // servoSetVelocity + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + int velocity = b16(ioCmd, startPos+1); + startPos += 2; //b16 + mrlComm->servoSetVelocity( deviceId, velocity); + break; + } + case SERVO_SWEEP_START: { // servoSweepStart + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte min = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte max = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte step = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->servoSweepStart( deviceId, min, max, step); + break; + } + case SERVO_SWEEP_STOP: { // servoSweepStop + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->servoSweepStop( deviceId); + break; + } + case SERVO_WRITE: { // servoWrite + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte target = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->servoWrite( deviceId, target); + break; + } + case SERVO_WRITE_MICROSECONDS: { // servoWriteMicroseconds + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + int ms = b16(ioCmd, startPos+1); + startPos += 2; //b16 + mrlComm->servoWriteMicroseconds( deviceId, ms); + break; + } + case SERIAL_ATTACH: { // serialAttach + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte relayPin = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->serialAttach( deviceId, relayPin); + break; + } + case SERIAL_RELAY: { // serialRelay + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + const byte* data = ioCmd+startPos+2; + byte dataSize = ioCmd[startPos+1]; + startPos += 1 + ioCmd[startPos+1]; + mrlComm->serialRelay( deviceId, dataSize, data); + break; + } + case ULTRASONIC_SENSOR_ATTACH: { // ultrasonicSensorAttach + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte triggerPin = ioCmd[startPos+1]; // bu8 + startPos += 1; + byte echoPin = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->ultrasonicSensorAttach( deviceId, triggerPin, echoPin); + break; + } + case ULTRASONIC_SENSOR_START_RANGING: { // ultrasonicSensorStartRanging + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + long timeout = b32(ioCmd, startPos+1); + startPos += 4; //b32 + mrlComm->ultrasonicSensorStartRanging( deviceId, timeout); + break; + } + case ULTRASONIC_SENSOR_STOP_RANGING: { // ultrasonicSensorStopRanging + byte deviceId = ioCmd[startPos+1]; // bu8 + startPos += 1; + mrlComm->ultrasonicSensorStopRanging( deviceId); + break; + } + + default: + publishError("unknown method " + String(method)); + break; + } // end switch + // ack that we got a command (should we ack it first? or after we process the command?) + + lastHeartbeatUpdate = millis(); + publishAck(ioCmd[0]); + +} // process Command + +void Msg::add(const int value) { + sendBuffer[sendBufferSize] = (value & 0xFF); + sendBufferSize += 1; +} + +void Msg::add16(const int value) { + sendBuffer[sendBufferSize] = ((value >> 8) & 0xFF); + sendBuffer[sendBufferSize + 1] = (value & 0xFF); + sendBufferSize += 2; +} + +void Msg::add(unsigned long value) { + sendBuffer[sendBufferSize] = ((value >> 24) & 0xFF); + sendBuffer[sendBufferSize + 1] = ((value >> 16) & 0xFF); + sendBuffer[sendBufferSize + 2] = ((value >> 8) & 0xFF); + sendBuffer[sendBufferSize + 3] = (value & 0xFF); + sendBufferSize += 4; +} + +int Msg::b16(const byte* buffer, const int start/*=0*/) { + return (buffer[start] << 8) + buffer[start + 1]; +} + +long Msg::b32(const byte* buffer, const int start/*=0*/) { + long result = 0; + for (int i = 0; i < 4; i++) { + result <<= 8; + result |= (buffer[start + i] & 0xFF); + } + return result; +} + +unsigned long Msg::bu32(const byte* buffer, const int start/*=0*/) { + unsigned long result = 0; + for (int i = 0; i < 4; i++) { + result <<= 8; + result |= (buffer[start + i] & 0xFF); + } + return result; +} + +void Msg::publishError(const String& message) { + publishMRLCommError(message.c_str(), message.length()); +} + +void Msg::publishDebug(const String& message) { + if (debug){ + publishDebug(message.c_str(), message.length()); + } +} + +bool Msg::readMsg() { + // handle serial data begin + int bytesAvailable = serial->available(); + if (bytesAvailable > 0) { + //publishDebug("RXBUFF:" + String(bytesAvailable)); + // now we should loop over the available bytes .. not just read one by one. + for (int i = 0; i < bytesAvailable; i++) { + // read the incoming byte: + unsigned char newByte = serial->read(); + //publishDebug("RX:" + String(newByte)); + ++byteCount; + // checking first byte - beginning of message? + if (byteCount == 1 && newByte != MAGIC_NUMBER) { + publishError(F("error serial")); + // reset - try again + byteCount = 0; + // return false; + } + if (byteCount == 2) { + // get the size of message + // todo check msg < 64 (MAX_MSG_SIZE) + if (newByte > 64) { + // TODO - send error back + byteCount = 0; + continue; // GroG - I guess we continue now vs return false on error conditions? + } + msgSize = newByte; + } + if (byteCount > 2) { + // fill in msg data - (2) headbytes -1 (offset) + ioCmd[byteCount - 3] = newByte; + } + // if received header + msg + if (byteCount == 2 + msgSize) { + // we've reach the end of the command, just return true .. we've got it + byteCount = 0; + return true; + } + } + } // if Serial.available + // we only partially read a command. (or nothing at all.) + return false; +} + +void Msg::write(const unsigned char value) { + serial->write(value); +} + +void Msg::write(const unsigned char* buffer, int len) { + serial->write(len); + serial->write(buffer, len); +} + +void Msg::writestr(const char* buffer) { + serial->write(strlen(buffer)); + serial->write(buffer); +} + +void Msg::writebool(const bool value){ + if (value){ + write(0); + } else { + write(1); + } +} + +void Msg::writeb16(const int b16){ + write(b16 >> 8 & 0xFF); + write(b16 & 0xFF); +} + +void Msg::writeb32(const long b32){ + write(b32 >> 24 & 0xFF); + write(b32 >> 16 & 0xFF); + write(b32 >> 8 & 0xFF); + write(b32 & 0xFF); +} + +void Msg::writebu32(const unsigned long bu32){ + write(bu32 >> 24 & 0xFF); + write(bu32 >> 16 & 0xFF); + write(bu32 >> 8 & 0xFF); + write(bu32 & 0xFF); +} + +byte* Msg::getBuffer() { + return sendBuffer; +} + +int Msg::getBufferSize() { + return sendBufferSize; +} + +void Msg::reset() { + sendBufferSize = 0; +} + +void Msg::flush() { + return serial->flush(); +} + +void Msg::begin(HardwareSerial& hardwareSerial){ + serial = &hardwareSerial; +} diff --git a/Msg.h b/Msg.h new file mode 100644 index 0000000..598da08 --- /dev/null +++ b/Msg.h @@ -0,0 +1,125 @@ +/** + *
+ *
+	Welcome to Msg.h
+	Its created by running ArduinoMsgGenerator
+	which combines the MrlComm message schema (src/resource/Arduino/generate/arduinoMsg.schema)
+	with the cpp template (src/resource/Arduino/generate/Msg.template.cpp)
+
+	IDL Type Conversions
+
+	IDL        ARDUINO					Java							Range
+	none		byte/unsigned char		int (cuz Java byte bites)		1 byte - 0 to 255
+	boolean		boolean					boolean							0 1
+    b16			int						int (short)						2 bytes	-32,768 to 32,767
+    b32			long					int								4 bytes -2,147,483,648 to 2,147,483, 647
+    bu32		unsigned long			long							0 to 4,294,967,295
+    str			char*, size				String							variable length
+    []			byte[], size			int[]							variable length
+
+	All message editing should be done in the arduinoMsg.schema
+
+	The binary wire format of an Arduino is:
+
+	MAGIC_NUMBER|MSG_SIZE|METHOD_NUMBER|PARAM0|PARAM1 ...
+
+
+*/ + +#ifndef Msg_h +#define Msg_h + +#include +#include "ArduinoMsgCodec.h" + +// forward defines to break circular dependency +class MrlComm; + +class Msg { + +public: + bool debug = false; + +private: + // msg reading FIXME - rename recvBuffer + byte ioCmd[MAX_MSG_SIZE]; + + int byteCount = 0; + int msgSize = 0; + + int sendBufferSize = 0; + byte sendBuffer[MAX_MSG_SIZE]; + + // serial references + HardwareSerial* serial; + + // heartbeat + bool heartbeat; + unsigned long lastHeartbeatUpdate; + + // implements callback + MrlComm* mrlComm; + + // my singlton instance + static Msg* instance; + + // private constructor + Msg(); + +public: + ~Msg(); + static Msg* getInstance(MrlComm* mrlComm); + static Msg* getInstance(); + + // send buffering methods + void add(const int value); + void add16(const int value); + void add(unsigned long value); + byte* getBuffer(); + int getBufferSize(); + void reset(); + void flush(); + + // utility methods + static int b16(const unsigned char* buffer, const int start = 0); + static long b32(const unsigned char* buffer, const int start = 0); + static unsigned long bu32(const unsigned char* buffer, const int start = 0); + + // FIXME - remove publishBoardInfo() .. its generated + static void publishBoardInfo(); + void publishError(const String& message); + void publishDebug(const String& message); + + // generated send (PC <-- MrlComm) methods + void publishMRLCommError(const char* errorMsg, byte errorMsgSize); + void publishBoardInfo( byte version, byte boardType); + void publishAck( byte function); + void publishHeartbeat(); + void publishEcho( unsigned long sInt); + void publishCustomMsg(const byte* msg, byte msgSize); + void publishI2cData( byte deviceId, const byte* data, byte dataSize); + void publishAttachedDevice( byte deviceId, const char* deviceName, byte deviceNameSize); + void publishBoardStatus( int microsPerLoop, int sram, const byte* deviceSummary, byte deviceSummarySize); + void publishDebug(const char* debugMsg, byte debugMsgSize); + void publishPinArray(const byte* data, byte dataSize); + void publishSerialData( byte deviceId, const byte* data, byte dataSize); + void publishUltrasonicSensorData( byte deviceId, int echoTime); + + // handles all (PC --> MrlComm) methods + // void handle(int[] ioCmd); // send size too ? + void processCommand(); + + // io + void begin(HardwareSerial& hardwareSerial); + void write(const unsigned char value); + void writebool(const bool value); + void writeb16(const int value); + void writeb32(const long value); + void writebu32(const unsigned long value); + void write(const unsigned char* buffer, int len); + void writestr(const char* buffer); + bool readMsg(); + +}; + +#endif // Mrl_h diff --git a/Pin.h b/Pin.h index 357370a..a0213e7 100644 --- a/Pin.h +++ b/Pin.h @@ -1,16 +1,6 @@ #ifndef Pin_h #define Pin_h -// ECHO FINITE STATE MACHINE - NON BLOCKING PULSIN -#define ECHO_STATE_START 1 -#define ECHO_STATE_TRIG_PULSE_BEGIN 2 -#define ECHO_STATE_TRIG_PULSE_END 3 -#define ECHO_STATE_MIN_PAUSE_PRE_LISTENING 4 -#define ECHO_STATE_LISTENING 5 -#define ECHO_STATE_GOOD_RANGE 6 -#define ECHO_STATE_TIMEOUT 7 - - // Pin Types must be in sync // with Arduino.getMrlPinType