test

Dependencies:   mbed Watchdog

Dependents:   STM32-MC_node

Files at this revision

API Documentation at this revision

Comitter:
nestedslk
Date:
Sat Jul 18 14:59:04 2020 +0000
Parent:
3:96fcb3b041eb
Child:
5:97117a837d2c
Commit message:
testing version

Changed in this revision

AS5045/AS5045.cpp Show annotated file Show diff for this revision Revisions of this file
AS5045/AS5045.h Show annotated file Show diff for this revision Revisions of this file
E18_D80NK/E18_D80NK.cpp Show annotated file Show diff for this revision Revisions of this file
E18_D80NK/E18_D80NK.h Show annotated file Show diff for this revision Revisions of this file
JSN_SR04/JSN_SR04.cpp Show annotated file Show diff for this revision Revisions of this file
RS485/RS485.cpp Show annotated file Show diff for this revision Revisions of this file
RS485/RS485.h Show annotated file Show diff for this revision Revisions of this file
RS485/mbed/.bld/bldrc Show diff for this revision Revisions of this file
global.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/AS5045/AS5045.cpp	Tue Jul 07 15:02:22 2020 +0000
+++ b/AS5045/AS5045.cpp	Sat Jul 18 14:59:04 2020 +0000
@@ -1,5 +1,5 @@
 #include "AS5045.h"
-
+//we have 5040
 /** Constructor
  *
  *	@param CS Pin number for the digital output
@@ -7,16 +7,18 @@
  *	@note
  *		PinName CS is the digital output pin number
  */
+ 
+ 
+ Timer timer_enc;
 AS5045::AS5045(PinName CS) :
   _spi(NC,D12, D13),	// MBED SPI init
   _cs(CS)				// Digital output pin init
 {
 	// Set SPI bitwidth
-	_spi.format(9,2);
+	_spi.format(9, 2);
 
 	// Set SPI frequency
-	_spi.frequency(SPI_FREQ);
-
+	_spi.frequency(50000);//SPI_FREQ);
 	// Set the digital output high
 	_cs = 1;
 }
@@ -28,21 +30,29 @@
  */
 int AS5045::getPosition()
 {
-	int upper,		// Upper part of the tick amount integer
-		lower;		// Lower part of the tick amount integer
+	unsigned int upper,		// Upper part of the tick amount integer
+				lower;		// Lower part of the tick amount integer
 
 	// Set the chip select pin low
 	_cs = 0;
-
+	timer_enc.reset();
+        timer_enc.start();
+	wait_ms(5);
 	// Read data from the encoder
- 	upper = _spi.write(0x00);
- 	lower = _spi.write(0x00);
+ 	upper = (_spi.write(0x00)) ;
+ 	lower = (_spi.write(0x00));
+ 	
+// 	lower = lower >> 6;   
+//    upper = (upper >> 6)+lower;
+//   upper = upper & 0xffc0;
+   upper = upper >> 6;
 
 	// Set the chip select pin high
  	_cs = 1;
-
+wait_ms(5);
  	// Return full 9-bits tick amount
-	return ((upper << 3)+(lower >> 6));
+	return upper; 
+	//return upper ;
 }
 
 /** Convert position of the encoder to degrees
--- a/AS5045/AS5045.h	Tue Jul 07 15:02:22 2020 +0000
+++ b/AS5045/AS5045.h	Sat Jul 18 14:59:04 2020 +0000
@@ -16,7 +16,7 @@
   SPI _spi;												// MBED SPI instance
   DigitalOut _cs;										// MBED digital output pin
 
-  static const float MAX_VALUE = 4095;			// Maximum possible encoder position value (ticks for full rotation)
+  static const float MAX_VALUE = 1024;			// Maximum possible encoder position value (ticks for full rotation)
   static const float RESOLUTION = 0.08789;	// Encoder resolution (0.08789 degrees per tick)
   static const float SPI_FREQ = 500000;		// Frequency of the SPI bus
 };
--- a/E18_D80NK/E18_D80NK.cpp	Tue Jul 07 15:02:22 2020 +0000
+++ b/E18_D80NK/E18_D80NK.cpp	Sat Jul 18 14:59:04 2020 +0000
@@ -2,4 +2,4 @@
 
 E18_D80NK::E18_D80NK(PinName inputPin) : input(inputPin) {}
 
-bool E18_D80NK::checkObstacle(void) { return (bool) input; }
+int E18_D80NK::checkObstacle(void) { return (int) input; }
--- a/E18_D80NK/E18_D80NK.h	Tue Jul 07 15:02:22 2020 +0000
+++ b/E18_D80NK/E18_D80NK.h	Sat Jul 18 14:59:04 2020 +0000
@@ -15,5 +15,5 @@
 	/** Check if there is an obstacle in front of the sensor
 	 * @return - if there's an obstacle return 0, otherwise - 1
 	 */
-	bool checkObstacle(void);
+	int checkObstacle(void);
 };
--- a/JSN_SR04/JSN_SR04.cpp	Tue Jul 07 15:02:22 2020 +0000
+++ b/JSN_SR04/JSN_SR04.cpp	Sat Jul 18 14:59:04 2020 +0000
@@ -81,7 +81,7 @@
 void JSN_SR04::startMeasurement() {
 	// Trigger the sensor (by a signal described in the datasheet)
    trigger = 1;
-   triggerTimeout.attach_us(this, &JSN_SR04::turnOffTrigger, 10);
+   triggerTimeout.attach_us(this, &JSN_SR04::turnOffTrigger, 100); 
 
 	// Start to measure a response
    echo.rise(this, &JSN_SR04::startTimer);
--- a/RS485/RS485.cpp	Tue Jul 07 15:02:22 2020 +0000
+++ b/RS485/RS485.cpp	Sat Jul 18 14:59:04 2020 +0000
@@ -1,18 +1,144 @@
 #include "RS485.h"
-
-RS485::RS485(PinName tx, PinName rx, PinName mode, const char *name) : Serial( tx, rx, name), m_modePin(mode)
-{   
-    m_modePin = 0;
+#include <stdarg.h>
+ 
+typedef unsigned int word;
+typedef uint8_t byte;
+typedef uint8_t boolean;
+typedef void (*voidFuncPtr)(void);
+Timer lapse;
+    const byte STX = '\2';
+    const byte ETX = '\3';
+ 
+RS485::RS485(PinName tx, PinName rx, PinName dere)
+    : BufferedSerial(tx, rx)
+{
+    return;
 }
-
-int RS485::_getc() { 
-    return _base_getc();
-}
-
-int RS485::_putc(int c) {
-    m_modePin = 1;
-    int ret = _base_putc(c);
-    m_modePin = 0;
-    return ret;
-}
-   
+    
+ 
+byte RS485::crc8(const byte *addr, byte len)
+{
+  byte crc = 0;
+  while (len--)
+    {
+    byte inbyte = *addr++;
+    for (byte i = 8; i; i--)
+      {
+      byte mix = (crc ^ inbyte) & 0x01;
+      crc >>= 1;
+      if (mix)
+        crc ^= 0x8C;
+      inbyte >>= 1;
+      }  // end of for
+    }  // end of while
+  return crc;
+}  // end of crc8
+ 
+void RS485::sendComplemented( const byte what)
+{
+  byte c ;
+  // first nibble
+  c = what >> 4;
+  putc((c << 4) | (c ^ 0x0F));
+ 
+  // second nibble
+  c = what & 0x0F;
+  putc((c << 4) | (c ^ 0x0F));
+}  // end of sendComplemented
+ 
+ 
+void RS485::sendMsg(const byte * data, const byte length)
+{
+  putc(STX);  // STX
+  for (byte i = 0; i < length; i++)
+    sendComplemented (data[i]);
+  putc(ETX);  // ETX
+  sendComplemented(crc8(data, length));
+}  // end of sendMsg
+ 
+// receive a message, maximum "length" bytes, timeout after "timeout" clock_mseconds
+// if nothing received, or an error (eg. bad CRC, bad data) return 0
+// otherwise, returns length of received data
+byte RS485::recvMsg (byte * data,                    // buffer to receive into
+              const byte length,              // maximum buffer size
+              unsigned long timeout)          // clock_mseconds before timing out
+  {
+ 
+  unsigned long start_time = lapse.read_ms();
+ 
+  bool have_stx = false;
+ 
+  // variables below are set when we get an STX
+  bool have_etx;
+  byte input_pos;
+  bool first_nibble;
+  byte current_byte;
+ 
+  while (lapse.read_ms() - start_time < timeout)
+    {
+    if (readable() > 0)
+      {
+      byte inByte = getc();
+ 
+      switch (inByte)
+        {
+ 
+        case STX:   // start of text
+          have_stx = true;
+          have_etx = false;
+          input_pos = 0;
+          first_nibble = true;
+          start_time = lapse.read_ms();  // reset timeout period
+          break;
+ 
+        case ETX:   // end of text
+          have_etx = true;
+          break;
+ 
+        default:
+          // wait until packet officially starts
+          if (!have_stx)
+            break;
+ 
+          // check byte is in valid form (4 bits followed by 4 bits complemented)
+          if ((inByte >> 4) != ((inByte & 0x0F) ^ 0x0F) )
+            return 0;  // bad character
+ 
+          // convert back
+          inByte >>= 4;
+ 
+          // high-order nibble?
+          if (first_nibble)
+            {
+            current_byte = inByte;
+            first_nibble = false;
+            break;
+            }  // end of first nibble
+ 
+          // low-order nibble
+          current_byte <<= 4;
+          current_byte |= inByte;
+          first_nibble = true;
+ 
+          // if we have the ETX this must be the CRC
+          if (have_etx)
+            {
+            if (crc8 (data, input_pos) != current_byte)
+              return 0;  // bad crc
+            return input_pos;  // return received length
+            }  // end if have ETX already
+ 
+          // keep adding if not full
+          if (input_pos < length)
+            data [input_pos++] = current_byte;
+          else
+            return 0;  // overflow
+          break;
+ 
+        }  // end of switch
+      }  // end of incoming data
+    } // end of while not timed out
+ 
+  return 0;  // timeout
+} // end of recvMsg
+  
\ No newline at end of file
--- a/RS485/RS485.h	Tue Jul 07 15:02:22 2020 +0000
+++ b/RS485/RS485.h	Sat Jul 18 14:59:04 2020 +0000
@@ -1,23 +1,60 @@
-#include <mbed.h>
-class RS485 : public Serial
+#ifndef RS485_H
+#define RS485_H
+ 
+#include "BufferedSerial.h"
+#include "mbed.h"
+
+class RS485 : public BufferedSerial
 {
+private:
+    typedef unsigned int word;
+    typedef uint8_t byte;
+    typedef uint8_t boolean;
+    typedef void (*voidFuncPtr)(void);
+    
 public:
-    /** Create a RS485 Serial port using MAX485, connected to the specified transmit and receive pins
-     *
+    /** Create a BufferedSerial port, connected to the specified transmit and receive pins
      *  @param tx Transmit pin
      *  @param rx Receive pin
-     *  @param mode Rx TX Mode pin
-     *
-     *  @note
-     *    Either tx or rx may be specified as NC if unused
+     *  @param dere Enable pin, this pin should be connected to !RE and DE
+     *  @note uses BufferedSerial
      */
-    RS485(PinName tx, PinName rx, PinName mode, const char *name=NULL);
+    RS485(PinName tx, PinName rx, PinName dere);
+ 
+    /** calculate 8-bit CRC
+    *  cyclic redundancy check
+    *  @param addr byte pointer of information to use (typical an byte array)
+    *  @param len length of byte of information were converting
+    *  @return the CRC byte
+    */
+    static byte crc8 (const byte *addr, byte len);
+    
+    /** sendComplemented byte
+    *  send a byte complemented, repeated
+    *       only values sent would be (in hex):
+    *       0F, 1E, 2D, 3C, 4B, 5A, 69, 78, 87, 96, A5, B4, C3, D2, E1, F0
+    *  @what the byte to complement
+    */
+    void sendComplemented (const byte what);
     
-protected:    
-    virtual int _putc(int c);
-    virtual int _getc();
-
-private:
-    DigitalOut m_modePin;
-         
-};
\ No newline at end of file
+    /** send message
+    *  cyclic redundancy check
+    *  @param data the data to be sent through RS485
+    *  @param length length of the data 
+    *  @note puts STX at start, ETX at end, and add CRC
+    */   
+    void sendMsg (const byte * data, const byte length);
+    
+    /** receive message
+    *  reads serial port and populates data
+    *  @param data buffer to receive into
+    *  @param length length of the data 
+    *  @param timeout clock_mseconds before timing out
+    *  @return the number of bytes received
+    *  
+    */
+    byte recvMsg (byte * data, const byte length, unsigned long timeout);
+      
+ 
+};
+#endif
\ No newline at end of file
--- a/RS485/mbed/.bld/bldrc	Tue Jul 07 15:02:22 2020 +0000
+++ /dev/null	Thu Jan 01 00:00:00 1970 +0000
@@ -1,1 +0,0 @@
-https://os.mbed.com/users/mbed_official/code/mbed/builds/65be27845400
\ No newline at end of file
--- a/global.h	Tue Jul 07 15:02:22 2020 +0000
+++ b/global.h	Sat Jul 18 14:59:04 2020 +0000
@@ -8,9 +8,11 @@
 #include "AS5045.h"
 #include "E18_D80NK.h"
 
-#define TEST_ULTRASONIC 1
+#define BLINKING_RATE     500
+
+#define TEST_ULTRASONIC 0
 #define TEST_ENCODERS   0
-#define TEST_IR         0
+#define TEST_IR         1
 
 // rs-485 pins
 #define UART1_TX    PB_6
@@ -39,9 +41,12 @@
 #define TRIG_PB15_OUT   PB_15
 #define TRIG_PB14_OUT   PB_14
 
+//ir obstacle pins
+#define IR1_PB12_OUT   PB_12
+#define IR2_PB13_OUT   PB_13
 
 
 
-
+#define DEBUG_LED   PC_13
 
 #endif /* GLOBAL_H_ */
\ No newline at end of file
--- a/main.cpp	Tue Jul 07 15:02:22 2020 +0000
+++ b/main.cpp	Sat Jul 18 14:59:04 2020 +0000
@@ -1,63 +1,122 @@
 #include <global.h>
 
 Serial pc(UART1_TX, UART1_RX);
-Timer timer; 
+Timer timer;
 
-int main() {
+int main()
+{
+//
+    DigitalOut led(DEBUG_LED);
+    DigitalOut led2(DE_TXD_1, 1); // activate transmitting rs485-1
+//   led = false;
+//   while (true) {
+//        led = !led;
+//        wait_ms(BLINKING_RATE);
+//        pc.printf("Distance:");
+//    }
+//
 
 #if TEST_ULTRASONIC
-
+    int time_to_check_us = 1000;
     JSN_SR04 sensor1(TIM1_CH2, TRIG_PA8_OUT);
-    JSN_SR04 sensor2(TIM1_CH2, TRIG_PB15_OUT);
-    JSN_SR04 sensor3(TIM1_CH2, TRIG_PB14_OUT);
-    sensor1.setRanges(10, 110);
-    sensor2.setRanges(10, 110);
-    sensor3.setRanges(10, 110);
-    pc.printf("Min. range = %g cm\n\rMax. range = %g cm\n\r",sensor1.getMinRange(), sensor1.getMaxRange());
+//    JSN_SR04 sensor1(TIM1_CH2, TRIG_PB14_OUT); //no triger signal
+//    JSN_SR04 sensor1(TIM1_CH2, TRIG_PB15_OUT);
+    sensor1.setRanges(30, 200);
+//    sensor2.setRanges(30, 200);
+//    sensor3.setRanges(30, 200);
+//    pc.printf("Min. range = %g cm\n\r",sensor1.getMinRange());
     while(true) {
-         timer.reset();
-          timer.start();
-          sensor1.startMeasurement();
-          sensor2.startMeasurement();
-          sensor3.startMeasurement();
-          while(!sensor1.isNewDataReady() || !sensor2.isNewDataReady() || !sensor3.isNewDataReady()) {
-              // wait for new data
-              // waiting time depends on the distance
-          }
-          pc.printf("Distance: %5.1f mm %5.1f mm %5.1f mm \r\n", sensor1.getDistance_mm(),sensor2.getDistance_mm(),sensor3.getDistance_mm());
-          timer.stop();
-          wait_ms(50 - timer.read_ms()); // time the loop
-      }
-  
+        timer.reset();
+        timer.start();
+        sensor1.startMeasurement();
+        while (sensor1.isNewDataReady() == false && timer.read_ms() < time_to_check_us) {
+//           pc.printf("c1");
+           // if (sensor1.isNewDataReady() == true) {
+//                pc.printf("Distance1: %5.1f mm \r\n", sensor1.getDistance_cm());
+//            }
+        }
+        //timer.reset();
+//        timer.start();
+////        pc.printf("\r\n");
+//        sensor2.startMeasurement();
+//        while (sensor2.isNewDataReady() == false && timer.read_ms() < time_to_check_us) {
+////                pc.printf("c2");
+//        }  
+//        timer.reset();
+//        timer.start();
+//        pc.printf("\r\n");
+        //sensor3.startMeasurement();
+//        while (sensor3.isNewDataReady() == false && timer.read_ms() < time_to_check_us) {
+//                pc.printf("c3");
+//        }       
+//        
+//        pc.printf("\r\n");         
+//        pc.printf("Distance1: %5.1f mm -- Distance2: %5.1f mm -- -- Distance3: %5.1f mm \r\n", sensor1.getDistance_cm()), sensor2.getDistance_cm(), sensor3.getDistance_cm());
+        pc.printf("Distance1: %5.1f mm \r\n", sensor1.getDistance_cm());
+
+        timer.stop();
+//        wait_ms(150 - timer.read_ms());
+
+        //
+//          timer.reset();
+//          timer.start();
+//
+//          sensor2.startMeasurement();
+//          pc.printf("Distance2: %5.1f mm \r\n", sensor2.getDistance_cm());
+//
+//          timer.stop();
+//          wait_ms(500 - timer.read_ms());
+//
+//          timer.reset();
+//          timer.start();
+//
+//          sensor3.startMeasurement();
+//          pc.printf("Distance3: %5.1f mm \r\n", sensor3.getDistance_cm());
+//
+//          timer.stop();
+        //wait_ms(500 - timer.read_ms()); // time the loop
+
+//
+//          wait_ms(500 - timer.read_ms()); // time the loop
+
+    }
+
 #endif
 
 #if TEST_ENCODERS
-
-   AS5045Controller encoder_1(SP1_NSS1);
-   AS5045Controller encoder_2(SP1_NSS2); 
-   while(1)
-   {
-        int encoder_1_Value = encoder_1.Read();
+int min1_value = 2000;
+int max1_value = 0;
+    AS5045 encoder_1(SP1_NSS1);
+    AS5045 encoder_2(SP1_NSS2);
+    while(1) {
+        led = !led;
+        int encoder_1_Value = encoder_1.getPosition();
+        wait_ms(30);
+        int encoder_2_Value = encoder_2.getPosition();
+        wait_ms(30);
+        //encoder_1_Value =
+        //if( encoder_1_Value.IsValid() && encoder_2_Value.IsValid() )
+        
+        if(encoder_1_Value < min1_value) min1_value = encoder_1_Value;
+        if(encoder_1_Value > max1_value) max1_value = encoder_1_Value;
+        pc.printf("Sensor Values = %d --- %d \n\r",encoder_1_Value, encoder_2_Value ); //
+        //else
+        //pc.printf("Invalid data read");
 
-        int encoder_2_Value = encoder_2.Read();
-        if( encoder_1_Value.IsValid() && encoder_2_Value.IsValid() )
-            pc.printf("Sensor Values = %d\n\r",encoder_1_Value ,encoder_2_Value  );
-        else
-            pc.printf("Invalid data read");
- 
-        Thread::wait(2);
-   }
-  
-#endif 
+        //wait_ms(50);
+    }
+
+#endif
 
 # if TEST_IR
-
-    E18_D80NK infared (<your pin>);
+    //E18_D80NK infared1 (IR1_PB12_OUT);
+//    E18_D80NK infared2 (IR2_PB13_OUT);
+//    while (true) {
+//        pc.printf ("Is there any obstacle: %d ---- %d ",  infared1.checkObstacle(),infared2.checkObstacle() );
+//        pc.printf ("\n\r");
+//    }
 
-    while (true) {
-        pc.printf ("Is there any obstacle:", infared.checkObstacle ());
-    }
-    
+
 #endif
 
 }