.NET nanoFramework SX127X LoRa library Registers

Over the years I have ported my HopeRF RFM9X(Now a generic Semtech SX127X ) Windows 10 IoT Core (May 2018) library to .NET microFramework(May 2018), Wilderness Labs Meadow(Jan 2020), GHI Electronics TinyCLR-OS(July 2020), .NET nanoFramework V1(May 2020) and .NET Core(Aug 2021).

All this madness started because I wasn’t confident the frequency calculation of the Emmellsoft Dragino.Lora code was correct. Over the last couple of years I have also found bugs in my Transmit Power, InvertIQ RX/TX with many others yet to be discovered.

For my updated .NET nanoFramework port I have mainly used a half a dozen Dragino LoRa shields for Arduino and Netduino 3 Wifi devices I had lying around. I have also tested the code with SparkFun LoRa Gateway-1-Channel (ESP32) and ST 32F769IDiscovery devices.

STM32F769IDiscovery, Netduino 3 Wifi, and SparkFun LoRa Gateway-1-Channel (ESP32) devices

The Dragino shield uses D10 for chip select, D2 for RFM9X DI0 interrupt and D9 for Reset.

Dragino Arduino LoRa Shield Schematic

Netduino 3 Wifi pin mapping

  • D10->CS->PB10
  • D9->RST->E5

ST 32F769IDiscovery pin mapping

D10->CS->PA11
D9->RST->PH6

Sparkfun ESP32 1 Channel Gateway Schematic

SparkFun LoRa Gateway-1-Channel (ESP32) pin mapping(SX127X reset is not connected)

  • CS->PB10

The first step was to confirm I could read a single(ShieldSPI) then scan all the Semtech SX1276 registers with the new nanoFramework System.Device.SPI Nuget (which was”inspired by” .Net Core System.Device.SPI)

namespace devMobile.IoT.SX127x.ShieldSPI
{
   using System;
   using System.Diagnostics;
   using System.Threading;

   using System.Device.Gpio;
   using System.Device.Spi;

#if ESP32_WROOM_32_LORA_1_CHANNEL
   using nanoFramework.Hardware.Esp32;
#endif

   public class Program
   {
      private const byte RegVersion = 0x42;
#if ESP32_WROOM_32_LORA_1_CHANNEL
      private const int SpiBusId = 1;
#endif
#if NETDUINO3_WIFI
      private const int SpiBusId = 2;
#endif
#if ST_STM32F769I_DISCOVERY
      private const int SpiBusId = 2;
#endif

      public static void Main()
      {
         GpioController gpioController = new GpioController();

#if ESP32_WROOM_32_LORA_1_CHANNEL // No reset line for this device as it isn't connected on SX127X
         int ledPinNumber = Gpio.IO17;
         int chipSelectLine = Gpio.IO16;
#endif
#if NETDUINO3_WIFI
         int ledPinNumber = PinNumber('A', 10);
         // Arduino D10->PB10
         int chipSelectLine = PinNumber('B', 10);
         // Arduino D9->PE5
         int resetPinNumber = PinNumber('E', 5);
#endif
#if ST_STM32F769I_DISCOVERY
         int ledPinNumber  = PinNumber('J', 5);
         // Arduino D10->PA11
         int chipSelectLine = PinNumber('A', 11);
         // Arduino D9->PH6
         int resetPinNumber = PinNumber('H', 6);
#endif
         Debug.WriteLine("devMobile.IoT.SX127x.ShieldSPI starting");

         try
         {
#if ESP32_WROOM_32_LORA_1_CHANNEL || NETDUINO3_WIFI || ST_STM32F769I_DISCOVERY
            // Setup the onboard LED
            gpioController.OpenPin(ledPinNumber, PinMode.Output);
#endif

#if NETDUINO3_WIFI || ST_STM32F769I_DISCOVERY
            // Setup the reset pin
            gpioController.OpenPin(resetPinNumber, PinMode.Output);
            gpioController.Write(resetPinNumber, PinValue.High);
#endif

#if ESP32_WROOM_32_LORA_1_CHANNEL
            Configuration.SetPinFunction(Gpio.IO12, DeviceFunction.SPI1_MISO);
            Configuration.SetPinFunction(Gpio.IO13, DeviceFunction.SPI1_MOSI);
            Configuration.SetPinFunction(Gpio.IO14, DeviceFunction.SPI1_CLOCK);
#endif

            var settings = new SpiConnectionSettings(SpiBusId, chipSelectLine)
            {
               ClockFrequency = 1000000,
               Mode = SpiMode.Mode0,// From SemTech docs pg 80 CPOL=0, CPHA=0
               SharingMode = SpiSharingMode.Shared,
            };

            using (SpiDevice device = SpiDevice.Create(settings))
            {
               Thread.Sleep(500);

               while (true)
               {
                  byte[] writeBuffer = new byte[] { RegVersion, 0x0 };
                  byte[] readBuffer = new byte[writeBuffer.Length];

                  device.TransferFullDuplex(writeBuffer, readBuffer);

                  Debug.WriteLine(String.Format("Register 0x{0:x2} - Value 0X{1:x2}", RegVersion, readBuffer[1]));

#if ESP32_WROOM_32_LORA_1_CHANNEL || NETDUINO3_WIFI || ST_STM32F769I_DISCOVERY
                  if ( gpioController.Read(ledPinNumber) == PinValue.High)
						{
                     gpioController.Write(ledPinNumber, PinValue.Low);
                  }
                  else
						{
                     gpioController.Write(ledPinNumber, PinValue.High);
                  }
#endif
                  Thread.Sleep(10000);
               }
            }
         }
         catch (Exception ex)
         {
            Debug.WriteLine(ex.Message);
         }
      }

#if NETDUINO3_WIFI || ST_STM32F769I_DISCOVERY
      static int PinNumber(char port, byte pin)
      {
         if (port < 'A' || port > 'J')
            throw new ArgumentException();

         return ((port - 'A') * 16) + pin;
      }
#endif
   }
}
Shield SPI Debug output
namespace devMobile.IoT.SX127x.RegisterScan
{
   using System;
   using System.Diagnostics;
   using System.Threading;

   using System.Device.Gpio;
   using System.Device.Spi;

#if ESP32_WROOM_32_LORA_1_CHANNEL
   using nanoFramework.Hardware.Esp32;
#endif

   public sealed class SX127XDevice
   {
      private readonly SpiDevice SX127XTransceiver;

      public SX127XDevice(int busId, int chipSelectLine)
      {

         var settings = new SpiConnectionSettings(busId, chipSelectLine)
         {
            ClockFrequency = 1000000,
            Mode = SpiMode.Mode0,// From SemTech docs pg 80 CPOL=0, CPHA=0
            SharingMode = SpiSharingMode.Shared
         };

         SX127XTransceiver = new SpiDevice(settings);
      }

      public SX127XDevice(int busId, int chipSelectLine, int resetPin)
      {
         var settings = new SpiConnectionSettings(busId, chipSelectLine)
         {
            ClockFrequency = 1000000,
            Mode = SpiMode.Mode0,// From SemTech docs pg 80 CPOL=0, CPHA=0
            SharingMode = SpiSharingMode.Shared
         };

         SX127XTransceiver = new SpiDevice(settings);

         // Factory reset pin configuration
         GpioController gpioController = new GpioController();
         gpioController.OpenPin(resetPin, PinMode.Output);

         gpioController.Write(resetPin, PinValue.Low);
         Thread.Sleep(20);
         gpioController.Write(resetPin, PinValue.High);
         Thread.Sleep(20);
      }

      public Byte RegisterReadByte(byte registerAddress)
      {
         byte[] writeBuffer = new byte[] { registerAddress, 0x0 };
         byte[] readBuffer = new byte[writeBuffer.Length];

         SX127XTransceiver.TransferFullDuplex(writeBuffer, readBuffer);

         return readBuffer[1];
      }
   }

   public class Program
   {
#if ESP32_WROOM_32_LORA_1_CHANNEL
      private const int SpiBusId = 1;
#endif
#if NETDUINO3_WIFI
      private const int SpiBusId = 2;
#endif
#if ST_STM32F769I_DISCOVERY
      private const int SpiBusId = 2;
#endif

      public static void Main()
      {
#if ESP32_WROOM_32_LORA_1_CHANNEL
         int chipSelectLine = Gpio.IO16;
#endif
#if NETDUINO3_WIFI
         // Arduino D10->PB10
         int chipSelectLine = PinNumber('B', 10);
         // Arduino D9->PE5
         int resetPinNumber = PinNumber('E', 5);
#endif
#if ST_STM32F769I_DISCOVERY
         // Arduino D10->PA11
         int chipSelectLine = PinNumber('A', 11);
         // Arduino D9->PH6
         int resetPinNumber = PinNumber('H', 6);
#endif

         Debug.WriteLine("devMobile.IoT.SX127x.RegisterScan starting");

         try
         {
#if NETDUINO3_WIFI || ST_STM32F769I_DISCOVERY
            SX127XDevice sx127XDevice = new SX127XDevice(SpiBusId, chipSelectLine, resetPinNumber);
#endif

#if ESP32_WROOM_32_LORA_1_CHANNEL
            Configuration.SetPinFunction(Gpio.IO12, DeviceFunction.SPI1_MISO);
            Configuration.SetPinFunction(Gpio.IO13, DeviceFunction.SPI1_MOSI);
            Configuration.SetPinFunction(Gpio.IO14, DeviceFunction.SPI1_CLOCK);

            SX127XDevice sx127XDevice = new SX127XDevice(SpiBusId, chipSelectLine);
#endif

            Thread.Sleep(500);

            while (true)
            {
               for (byte registerIndex = 0; registerIndex <= 0x42; registerIndex++)
               {
                  byte registerValue = sx127XDevice.RegisterReadByte(registerIndex);

                  Debug.WriteLine($"Register 0x{registerIndex:x2} - Value 0X{registerValue:x2}");
               }
               Debug.WriteLine("");

               Thread.Sleep(10000);
            }
         }
         catch (Exception ex)
         {
            Debug.WriteLine(ex.Message);
         }
      }

#if NETDUINO3_WIFI || ST_STM32F769I_DISCOVERY
      static int PinNumber(char port, byte pin)
      {
         if (port < 'A' || port > 'J')
            throw new ArgumentException();

         return ((port - 'A') * 16) + pin;
      }
#endif
   }
}
RegisterScan Debug Output

There is some SparkFun LoRa Gateway-1-Channel (ESP32) specific configuration to map the Serial Peripheral Interface(SPI) pins and an additional NuGet for ESP32 has to be added. For the initial versions I have not used more advanced .NET nanoFramework functionality like SpanByte.

.NET nanoFramework ValueChanged

If you have landed at this post you were most probably searching for issues updating .NET nanoFramework code that used ValueChanged to handle interrupts. Back in mid 2020 the initial version of my Semtech SX127X(HopeRF RFM9X) library used the Windows.Devices.Gpio Nuget package.

public Rfm9XDevice(string spiPort, int chipSelectPin, int resetPin, int interruptPin)
{
    //...
   
   // Interrupt pin for RX message & TX done notification 
   InterruptGpioPin = gpioController.OpenPin(interruptPin);
   InterruptGpioPin.SetDriveMode(GpioPinDriveMode.Input);

   InterruptGpioPin.ValueChanged += InterruptGpioPin_ValueChanged;
}

private void InterruptGpioPin_ValueChanged(object sender, GpioPinValueChangedEventArgs e)
{
   if (e.Edge != GpioPinEdge.RisingEdge)
   {
      return;
   }

   byte irqFlags = this.RegisterReadByte(0x12); // RegIrqFlags
   //...
}

Then in March 2022 I updated the CoreLibrary, Runtime.Events, System.Devices.GPIO, System.Devices.SPI NuGets.

I then fixed all the breaking changes (For the initial versions I have not updated the code to use SpanByte etc.).

public Rfm9XDevice(int spiBusId, int chipSelectPin, int resetPin, int interruptPin)
{
   //...

   // Interrupt pin for RX message & TX done notification 
   InterruptGpioPin = gpioController.OpenPin(interruptPin);
   InterruptGpioPin.SetPinMode(PinMode.Input);

   InterruptGpioPin.ValueChanged += InterruptGpioPin_ValueChanged;
}

private void InterruptGpioPin_ValueChanged(object sender, PinValueChangedEventArgs e)
{
   if (e.ChangeType != PinEventTypes.Rising)
   {
      return;
   }

   byte irqFlags = this.RegisterReadByte(0x12); // RegIrqFlags
   //...
}

While “soak testing” the ReceiveInterrupt application I noticed that sometimes when I started the application interrupts were not processed or processing stopped after a while.

Visual Studio Debugger output showing intermittent calling of InterruptGpioPin_ValueChanged

I then found the RangeTester application wouldn’t start or run reliably. My original code was based on the Widnows.Devices.GPIO sample so I updated it based on the System.Device.GPIO sample.

public Rfm9XDevice(int spiBusId, int chipSelectPin, int resetPin, int interruptPin)
{
   //...

   // Interrupt pin for RX message & TX done notification 
   gpioController.OpenPin(interruptPin,PinMode.InputPullDown);

   gpioController.RegisterCallbackForPinValueChangedEvent(interruptPin, PinEventTypes.Rising, InterruptGpioPin_ValueChanged);
}

private void InterruptGpioPin_ValueChanged(object sender, PinValueChangedEventArgs e)
{
   byte irqFlags = this.RegisterReadByte(0x12); // RegIrqFlags
   //...
}
Visual Studio Debugger output showing reliable calling of InterruptGpioPin_ValueChanged

If your Windows.Devices.GPIO based project is not reliably handling interrupts after upgrading to System.Device.GPIO and fixing any “breaking changes” the implementation most probably need to be updated to use RegisterCallbackForPinValueChangedEvent as well.

Seeed LoRa-E5 LowPower problem fix

I had been soak testing Seeed LoRa-E5 equipped TinyCLR and netNF devices for the last couple of weeks and after approximately two days they would stop sending data.

After a pointer to the LowPower section of the Seeed LoRa-E5 manual I realised my code could send the next command within 5ms.

Seeeduino LoRa-E5 AT Command document

I added a 5msec Sleep after the wakeup command had been sent

public Result Wakeup()
{
   // Wakeup the E5 Module
#if DIAGNOSTICS
   Debug.WriteLine($" {DateTime.UtcNow:hh:mm:ss} AT+LOWPOWER: WAKEUP");
#endif
   Result result = SendCommand("+LOWPOWER: WAKEUP", $"A", CommandTimeoutDefault);
   if (result != Result.Success)
   {
#if DIAGNOSTICS
      Debug.WriteLine($" {DateTime.UtcNow:hh:mm:ss} AT+LOWPOWER: WAKEUP failed {result}");
#endif
      return result;
   }

   // Thanks AndrewL for pointing out delay required in section 4.30 LOWPOWER
   Thread.Sleep(5);

   return Result.Success;
}

The updated code is has been reliably running on TinyCLR and netNF devices connected to The Things Industries for the last 4 days.

nanoFramework Seeed LoRa-E5 LoRaWAN library Part1

Basic connectivity

Over the weekend I have been working on a nanoFramework C# library for my LoRa-E5 Development Kit from Seeedstudio. My initial test rig is based on an STM32F691DISCOVERY board which has an Arduino Uno R3 format socket for a Grove Base Shield V2.0, which I then connected to my LoRa-E5 Development Kit with a Grove – Universal 4 Pin 20cm Unbuckled Cable(TX/RX reversed)

STM32F769I test rig with Seeedstudio Grove Base shield V2 and LoRa-E5 Development Kit

The code has compile time options for synchronous and asynchronous operation.

public class Program
{
   private const string SerialPortId = "COM6";

   public static void Main()
   {
      SerialDevice serialDevice;

      Debug.WriteLine("devMobile.IoT.SeeedLoRaE5.ShieldSerial starting");

      Debug.WriteLine(Windows.Devices.SerialCommunication.SerialDevice.GetDeviceSelector());

      try
      {
         serialDevice = SerialDevice.FromId(SerialPortId);

         // set parameters
         serialDevice.BaudRate = 9600;
         serialDevice.Parity = SerialParity.None;
         serialDevice.StopBits = SerialStopBitCount.One;
         serialDevice.Handshake = SerialHandshake.None;
         serialDevice.DataBits = 8;

         serialDevice.ReadTimeout = new TimeSpan(0, 0, 30);
         serialDevice.WriteTimeout = new TimeSpan(0, 0, 4);

         DataWriter outputDataWriter = new DataWriter(serialDevice.OutputStream);

#if SERIAL_SYNC_READ
         DataReader inputDataReader = new DataReader(serialDevice.InputStream);
#else
         serialDevice.DataReceived += SerialDevice_DataReceived;
#endif

         // set a watch char to be notified when it's available in the input stream
         // This doesn't appear to work with synchronous calls
         serialDevice.WatchChar = '\n';

         while (true)
         {
            uint bytesWritten = outputDataWriter.WriteString("AT+VER\r\n");
            Debug.WriteLine($"TX: {outputDataWriter.UnstoredBufferLength} bytes to output stream.");

            // calling the 'Store' method on the data writer actually sends the data
            uint txByteCount = outputDataWriter.Store();
            Debug.WriteLine($"TX: {txByteCount} bytes via {serialDevice.PortName}");

#if SERIAL_SYNC_READ
            uint bytesRead = inputDataReader.Load(50);

            Debug.WriteLine($"RXs :{bytesRead} bytes read from {serialDevice.PortName}");

            if (bytesRead > 0)
            {
               String response = inputDataReader.ReadString(bytesRead);
               Debug.WriteLine($"RX sync:{response}");
            }
#endif

            Thread.Sleep(20000);
         }
      }
      catch (Exception ex)
      {
         Debug.WriteLine(ex.Message);
      }
   }

   private static void SerialDevice_DataReceived(object sender, SerialDataReceivedEventArgs e)
   {
      switch (e.EventType)
      {
         case SerialData.Chars:
            //Debug.WriteLine("RX SerialData.Chars");
            break;

         case SerialData.WatchChar:
             Debug.WriteLine("RX: SerialData.WatchChar");
             SerialDevice serialDevice = (SerialDevice)sender;

            using (DataReader inputDataReader = new DataReader(serialDevice.InputStream))
            {
               inputDataReader.InputStreamOptions = InputStreamOptions.Partial;

               // read all available bytes from the Serial Device input stream
               uint bytesRead = inputDataReader.Load(serialDevice.BytesToRead);

               Debug.WriteLine($"RXa: {bytesRead} bytes read from {serialDevice.PortName}");

               if (bytesRead > 0)
               {
                  String response = inputDataReader.ReadString(bytesRead);
                  Debug.WriteLine($"RX:{response}");
               }
            }
            break;
         default:
            Debug.Assert(false, $"e.EventType {e.EventType} unknown");
            break;
      }
   }
}

I have reused a significant amount of code built for my nanoFramework RAK811 LoRaWAN library Part1 post.

The thread '<No Name>' (0x2) has exited with code 0 (0x0).
devMobile.IoT.SeeedLoRaE5.ShieldSerial starting
Ports available: COM5,COM6
TX: 8 bytes to output stream.
TX: 8 bytes via COM6
TX: 8 bytes to output stream.
TX: 8 bytes via COM6
RX: SerialData.WatchChar
RXa: 28 bytes read from COM6
RX:+VER: 4.0.11
+VER: 4.0.11

TX: 8 bytes to output stream.
TX: 8 bytes via COM6
RX: SerialData.WatchChar
RXa: 14 bytes read from COM6
RX:+VER: 4.0.11

TX: 8 bytes to output stream.
TX: 8 bytes via COM6
RX: SerialData.WatchChar
RXa: 14 bytes read from COM6
RX:+VER: 4.0.11

TX: 8 bytes to output stream.
TX: 8 bytes via COM6
RX: SerialData.WatchChar
RXa: 14 bytes read from COM6
RX:+VER: 4.0.11

The test rig confirmed that I had the right configuration for the hardware (TX-RX twist) and LoRa-E5 connection (serial port, baud rate, parity etc.)

Low Power Payload (LPP) Encoder

I originally started building my own Low Power Protocol(LPP) encoder because I could only find one other Github repository with a C# implementation. There hadn’t been any updates for a while and I wasn’t confident that I could make the code work on my nanoFramework and TinyCLR devices.

I started with the sample Mbed C code and did a largely mechanical conversion to C#. I then revisited some of the mathematics where floating point values were converted to an integer.

The original C++ code (understandably) had some language specific approaches which didn’t map well into C#. I then translated the code to C#

public void TemperatureAdd(byte channel, float celsius)
{
   if ((index + TemperatureSize) > buffer.Length)
   {
      throw new ApplicationException("TemperatureAdd insufficent buffer capacity");
   }

   short val = (short)(celsius * 10);

   buffer[index++] = channel;
   buffer[index++] = (byte)DataType.Temperature;
   buffer[index++] = (byte)(val >> 8);
   buffer[index++] = (byte)val;
}

One of my sensors was sending values with more decimal places than LPP supported and I noticed the value was not getting rounded e.g. 2.99 ->2.9 not 3.0 etc. So I revised my implementation to use Math.Round (which is supported by the nanoFramework and TinyCLR).

public void DigitalInputAdd(byte channel, bool value)
{
   #region Guard conditions
   if ((channel < Constants.ChannelMinimum) || (channel > Constants.ChannelMaximum))
   {
      throw new ArgumentException($"channel must be between {Constants.ChannelMinimum} and {Constants.ChannelMaximum}", "channel");
   }

   if ((index + Constants.DigitalInputSize) > buffer.Length)
   {
      throw new ApplicationException($"Datatype DigitalInput insufficent buffer capacity, {buffer.Length - index} bytes available");
   }
   #endregion

   buffer[index++] = channel;
   buffer[index++] = (byte)Enumerations.DataType.DigitalInput;

   // I know this is fugly but it works on all platforms
   if (value)
   {
      buffer[index++] = 1;
   }
   else
   {
     buffer[index++] = 0;
   }
 }

I then extracted out the channel and buffer size validation but I’m not certain this makes the code anymore readable/understandable

public void DigitalInputAdd(byte channel, bool value)
{
   IsChannelNumberValid(channel);
   IsBufferSizeSufficient(Enumerations.DataType.DigitalInput);

   buffer[index++] = channel;
   buffer[index++] = (byte)Enumerations.DataType.DigitalInput;

   // I know this is fugly but it works on all platforms
   if (value)
   {
      buffer[index++] = 1;
   }
   else
   {
      buffer[index++] = 0;
   }
}

The code runs on netCore, nanoFramework, and TinyCLRV2 just needs a few more unit tests and it will be ready for production. I started with an LPP encoder which I needed for one of my applications. I’m also working an approach for a decoder which will run on all my target platforms with minimal modification or compile time directives.

netNF Electric Longboard Part 4

The Rideable Prototype

After some experimentation I gave up on the radio control(RC) servo library for controlling my Longboard’s Electronic Speed Control(ESC).

My new longboard controller uses the following parts

  • Netduino 3 Wifi
  • Generic wireless wii nuchuk
  • generic Arduino protoshield

I reused the initial protoshield and only had to shift the PWM output to the ESC from pin 8 to pin 7.

FEZ Panda III Protoshield for longboard with RC Servo for testing
Protoshield for longboard RC Servo test
public class Program
{
   private const double PulseFrequency = 50.0;
   private const double PulseDurationMinimum = 0.05; // 1000uSec
   private const double PulseDurationMaximum = 0.1; // 2000uSec
   private const double WiiNunchukYMinimum = 0.0;
   private const double WiiNunchukYMaximum = 255.0;
   private const int ThrottleUpdatePeriod = 100;

   public static void Main()
   {
      Debug.WriteLine("devMobile.Longboard starting");
      Debug.WriteLine($"I2C:{I2cDevice.GetDeviceSelector()}");
      Debug.WriteLine($"PWM:{PwmController.GetDeviceSelector()}");

      try
      {
         Debug.WriteLine("LED Starting");
         GpioPin led = GpioController.GetDefault().OpenPin(PinNumber('A', 10));
         led.SetDriveMode(GpioPinDriveMode.Output);
         led.Write(GpioPinValue.Low);

         Debug.WriteLine("LED Starting");
         WiiNunchuk nunchuk = new WiiNunchuk("I2C1");

         Debug.WriteLine("ESC Starting");
         PwmController pwm = PwmController.FromId("TIM5");
         PwmPin pwmPin = pwm.OpenPin(PinNumber('A', 1));
         pwmPin.Controller.SetDesiredFrequency(PulseFrequency);
         pwmPin.Start();

         Debug.WriteLine("Thread.Sleep Starting");
         Thread.Sleep(2000);

         Debug.WriteLine("Mainloop Starting");
         while (true)
         {
            nunchuk.Read();

            double duration = Map(nunchuk.AnalogStickY, WiiNunchukYMinimum, WiiNunchukYMaximum, PulseDurationMinimum, PulseDurationMaximum);
            Debug.WriteLine($"Value:{nunchuk.AnalogStickY} Duration:{duration:F3}");

            pwmPin.SetActiveDutyCyclePercentage(duration);
            led.Toggle();
            Thread.Sleep(ThrottleUpdatePeriod);
         }
      }
      catch (Exception ex)
      {
         Debug.WriteLine(ex.Message);
      }
   }

   private static int PinNumber(char port, byte pin)
   {
      if (port < 'A' || port > 'J')
         throw new ArgumentException();

      return ((port - 'A') * 16) + pin;
   }

   private static double Map(double x, double inputMinimum, double inputMaximum, double outputMinimum, double outputMaximum)
   {
      return (x - inputMinimum) * (outputMaximum - outputMinimum) / (inputMaximum - inputMinimum) + outputMinimum;
   }
}

The nanoFramework code polls the wii nunchuk for the joystick position every 100mSec and then updates the PWM duty cycle.

By convention the ESSC PWM frequency is 50Hz (a pulse ever 20mSec) and the duration of the pulse is 1000uSec(minimum throttle) to 2000uSec(maximum throttle), note the change of units.

After converting to the same units there is a pulse every 20mSec and its duration is 1mSec too 2mSec. Then converting the durations to the active duty cycle percentage (for the PWM SetActiveDutyCyclePercentage) the duration of the pulse is 5% to 10%.

I need to re-calibrate the ESC for these durations and ensure that reverse is disabled. Then tinker with the brake (braking percent & percent drag brake) and acceleration(initial acceleration low, medium, high, very high) configurations of my ESC to make the longboard easier to ride.

Next I will look at configurable throttle maps (to make it easier for new and different weight users), then using one of the wii-nunchuk buttons for cruise control (keeping the throttle steady when riding is difficult) and how the software reacts when the connection with nunchuk fails

netNF Electric Longboard Part 3

Servo Control

The next step was to figure out how to operate a radio control(RC) servo as a proxy for an Electronic Speed Control(ESC).

My test rig uses (prices as at Aug 2020) the following parts

  • Netduino 3 Wifi
  • Grove-Base Shield V2.0 for Arduino USD4.45
  • Grove-Universal 4 Pin Bucked 20cm cable(5 PCs Pack) USD2.90
  • Grove-Servo USD5.90
  • Grove-Rotary Angle Sensor USD2.90

My servo test harness

public class Program
{
   public static void Main()
   {
      Debug.WriteLine("devMobile.Longboard.ServoTest starting");

      try
      {
         AdcController adc = AdcController.GetDefault();
         AdcChannel adcChannel = adc.OpenChannel(0);

         ServoMotor servo = new ServoMotor("TIM5", ServoMotor.ServoType.Positional, PinNumber('A', 0));
         servo.ConfigurePulseParameters(0.6, 2.3);

         while (true)
         {
            double value = adcChannel.ReadRatio();
            double position = Map(value, 0.0, 1.0, 0.0, 180);

            Debug.WriteLine($"Value: {value:F2} Position: {position:F1}");

            servo.Set(position);

            Thread.Sleep(100);
         }
      }
      catch (Exception ex)
      {
         Debug.WriteLine(ex.Message);
      }
   }

   private static int PinNumber(char port, byte pin)
   {
      if (port < 'A' || port > 'J')
         throw new ArgumentException();

      return ((port - 'A') * 16) + pin;
   }

   private static double Map(double x, double inputMinimum, double inputMaximum, double outputMinimum, double outputMaximum)
   {
      return (x - inputMinimum) * (outputMaximum - outputMinimum) / (inputMaximum - inputMinimum) + outputMinimum;
   }
}

The nanoFramework code polls for the rotary angle sensor for its position every 100mSec and then updates the servo.

The servo code was based on sample code provided by GHI Electronics for their TinyCLR which I had to adapt to work with the nanoFramework.

The next test rig will be getting the Netduino 3 software working my Longboard ESC and Lithium Polymer(LiPo) batteries.

netNF Electric Longboard Part 2

Analog Inputs & Pulse Width Modulation

The next step was to figure out how to configure a Pulse Width Modulation (PWM) output and an Analog Input so I could adjust the duty cycle and control the brightness of a Light Emitting Diode(LED).

Netduino 3 ADC & PWN test rig

My test rig uses (prices as at Aug 2020) the following parts

  • Netduino 3 Wifi
  • Grove-Base Shield V2.0 for Arduino USD4.45
  • Grove-Universal 4 Pin Bucked 5cm cable(5 PCs Pack) USD1.90
  • Grove-Universal 4 Pin Bucked 20cm cable(5 PCs Pack) USD2.90
  • Grove-LED Pack USD2.90
  • Grove-Rotary Angle Sensor USD2.90

My analog input test harness

 public class Program
   {
      public static void Main()
      {
         Debug.WriteLine("devMobile.Longboard.AdcTest starting");
         Debug.WriteLine(AdcController.GetDeviceSelector());

         try
         {
            AdcController adc = AdcController.GetDefault();
            AdcChannel adcChannel = adc.OpenChannel(0);

            while (true)
            {
               double value = adcChannel.ReadRatio();

               Debug.WriteLine($"Value: {value:F2}");

               Thread.Sleep(100);
            }
         }
         catch (Exception ex)
         {
            Debug.WriteLine(ex.Message);
         }
      }
   }

The nanoFramework code polls for the rotary angle sensor for its position value every 100mSec.

The setup to use for the Analog to Digital Convertor(ADC) port was determined by looking at the board.h and target_windows_devices_adc_config.cpp file.

//
// Copyright (c) 2018 The nanoFramework project contributors
// See LICENSE file in the project root for full license information.
//

#include <win_dev_adc_native_target.h>

const NF_PAL_ADC_PORT_PIN_CHANNEL AdcPortPinConfig[] = {
    
    // ADC1
    {1, GPIOC, 0, ADC_CHANNEL_IN10},
    {1, GPIOC, 1, ADC_CHANNEL_IN11},

    // ADC2
    {2, GPIOC, 2, ADC_CHANNEL_IN14},
    {2, GPIOC, 3, ADC_CHANNEL_IN15},

    // ADC3
    {3, GPIOC, 4, ADC_CHANNEL_IN12},
    {3, GPIOC, 5, ADC_CHANNEL_IN13},

    // these are the internal sources, available only at ADC1
    {1, NULL, 0, ADC_CHANNEL_SENSOR},
    {1, NULL, 0, ADC_CHANNEL_VREFINT},
    {1, NULL, 0, ADC_CHANNEL_VBAT},
};

const int AdcChannelCount = ARRAYSIZE(AdcPortPinConfig);

The call to AdcController.GetDeviceSelector() only returned one controller

The thread '<No Name>' (0x2) has exited with code 0 (0x0).
devMobile.Longboard.AdcTest starting
ADC1

After some experimentation it appears that only A0 & A1 work on a Netduino. (Aug 2020).

My PWM test harness

public class Program
{
   public static void Main()
   {
      Debug.WriteLine("devMobile.Longboard.PwmTest starting");
      Debug.WriteLine(PwmController.GetDeviceSelector());

      try
      {
         PwmController pwm = PwmController.FromId("TIM5");
         AdcController adc = AdcController.GetDefault();
         AdcChannel adcChannel = adc.OpenChannel(0);

         PwmPin pwmPin = pwm.OpenPin(PinNumber('A', 0));
         pwmPin.Controller.SetDesiredFrequency(1000);
         pwmPin.Start();

         while (true)
         {
            double value = adcChannel.ReadRatio();

            Debug.WriteLine(value.ToString("F2"));

            pwmPin.SetActiveDutyCyclePercentage(value);

            Thread.Sleep(100);
         }
      }
      catch (Exception ex)
      {
         Debug.WriteLine(ex.Message);
      }
   }

   private static int PinNumber(char port, byte pin)
   {
      if (port < 'A' || port > 'J')
         throw new ArgumentException();
      return ((port - 'A') * 16) + pin;
   }
}

I had to refer to the Netduino schematic to figure out pin mapping

With my test rig (with easy access to D0 thru D8) I found that only D2,D3,D7 and D8 work as PWM outputs.

The next test rig will be getting Servo working.

netNF Electric Longboard Part 1

Wiichuck connectivity

Roughly four years ago I build myself an electric longboard as summer transport. It initially had a controller built with a devDuino V2.2 which after a while I “upgraded” to a GHI Electronics .NET Microframework device.

Configuring the original netMF based longboard

Now that GHI Electronics no longer supports the FEZ Panda III I figured upgrading to a device that runs the nanoFramework would be a good compromise.

I control the speed of the longboard with a generic wireless wii nunchuk. So my first project is porting the .NET Micro Framework Toolbox code to the nanoFramework.

wireless controller test rig

My test rig uses (prices as at Aug 2020) the following parts

  • Netduino 3 Wifi
  • Grove-Base Shield V2.0 for Arduino USD4.45
  • Grove-Universal 4 Pin Bucked 5cm cable(5 PCs Pack) USD1.90
  • Grove-Nunchuck USD2.90
  • Generic wireless WII nunchuk

My changes were mainly related to the Inter Integrated Circuit(I2C) configuration and the reading+writing of registers.

/// <summary>
/// Initialises a new Wii Nunchuk
/// </summary>
/// <param name="busId">The unique identifier of the I²C to use.</param>
/// <param name="slaveAddress">The I²C address</param>
/// <param name="busSpeed">The bus speed, an enumeration that defaults to StandardMode</param>
/// <param name="sharingMode">The sharing mode, an enumeration that defaults to Shared.</param>
public WiiNunchuk(string busId, ushort slaveAddress = 0x52, I2cBusSpeed busSpeed = I2cBusSpeed.StandardMode, I2cSharingMode sharingMode = I2cSharingMode.Shared)
   {
      I2cTransferResult result;

      // This initialisation routine seems to work. I got it at http://wiibrew.org/wiki/Wiimote/Extension_Controllers#The_New_Way
      Device = I2cDevice.FromId(busId, new I2cConnectionSettings(slaveAddress)
      {
         BusSpeed = busSpeed,
         SharingMode = sharingMode,
      });

      result = Device.WritePartial(new byte[] { 0xf0, 0x55 });
      if (result.Status != I2cTransferStatus.FullTransfer)
      {
         throw new ApplicationException("Something went wrong reading the Nunchuk. Did you use proper pull-up resistors?");
      }

      result = Device.WritePartial(new byte[] { 0xfb, 0x00 });
      if (result.Status != I2cTransferStatus.FullTransfer)
      {
         throw new ApplicationException("Something went wrong reading the Nunchuk. Did you use proper pull-up resistors?");
      }

      this.Device.Write(new byte[] { 0xf0, 0x55 });
      this.Device.Write(new byte[] { 0xfb, 0x00 });
   }

   /// <summary>
   /// Reads all data from the nunchuk
   /// </summary>
   public void Read()
   {
      byte[] WaitWriteBuffer = { 0 };
      I2cTransferResult result;

      result = Device.WritePartial(WaitWriteBuffer);
      if (result.Status != I2cTransferStatus.FullTransfer)
      {
         throw new ApplicationException("Something went wrong reading the Nunchuk. Did you use proper pull-up resistors?");
      }

      byte[] ReadBuffer = new byte[6];
      result = Device.ReadPartial(ReadBuffer);
      if (result.Status != I2cTransferStatus.FullTransfer)
      {
         throw new ApplicationException("Something went wrong reading the Nunchuk. Did you use proper pull-up resistors?");
      }

      // Parses data according to http://wiibrew.org/wiki/Wiimote/Extension_Controllers/Nunchuck#Data_Format

      // Analog stick
      this.AnalogStickX = ReadBuffer[0];
      this.AnalogStickY = ReadBuffer[1];

      // Accelerometer
      ushort AX = (ushort)(ReadBuffer[2] << 2);
      ushort AY = (ushort)(ReadBuffer[3] << 2);
      ushort AZ = (ushort)(ReadBuffer[4] << 2);
      AZ += (ushort)((ReadBuffer[5] & 0xc0) >> 6); // 0xc0 = 11000000
      AY += (ushort)((ReadBuffer[5] & 0x30) >> 4); // 0x30 = 00110000
      AX += (ushort)((ReadBuffer[5] & 0x0c) >> 2); // 0x0c = 00001100
      this.AcceleroMeterX = AX;
      this.AcceleroMeterY = AY;
      this.AcceleroMeterZ = AZ;

      // Buttons
      ButtonC = (ReadBuffer[5] & 0x02) != 0x02;    // 0x02 = 00000010
      ButtonZ = (ReadBuffer[5] & 0x01) != 0x01;    // 0x01 = 00000001
}

The nanoFramework code polls for the joystick position and accelerometer values every 100mSec

public class Program
{
   public static void Main()
   {
      Debug.WriteLine("devMobile.Longboard.WiiNunchuckTest starting");
      Debug.WriteLine(I2cDevice.GetDeviceSelector());

      try
      {
         WiiNunchuk nunchuk = new WiiNunchuk("I2C1");

         while (true)
         {
            nunchuk.Read();

            Debug.WriteLine($"JoyX: {nunchuk.AnalogStickX} JoyY:{nunchuk.AnalogStickY} AX:{nunchuk.AcceleroMeterX} AY:{nunchuk.AcceleroMeterY} AZ:{nunchuk.AcceleroMeterZ} BtnC:{nunchuk.ButtonC} BtnZ:{nunchuk.ButtonZ}");

            Thread.Sleep(100);
         }
      }
      catch (Exception ex)
      {
         Debug.WriteLine(ex.Message);
      }
   }
}

The setup to use for the I2C port was determined by looking at the board.h and target_windows_devices_I2C_config.cpp file

//
// Copyright (c) 2018 The nanoFramework project contributors
// See LICENSE file in the project root for full license information.
//

#include <win_dev_i2c_native_target.h>

//////////
// I2C1 //
//////////

// pin configuration for I2C1
// port for SCL pin is: GPIOB
// port for SDA pin is: GPIOB
// SCL pin: is GPIOB_6
// SDA pin: is GPIOB_7
// GPIO alternate pin function is 4 (see alternate function mapping table in device datasheet)
I2C_CONFIG_PINS(1, GPIOB, GPIOB, 6, 7, 4)

Then checking this against the Netduino 3 Wifi schematic.

This image has an empty alt attribute; its file name is netduinoschematic-1.jpg

After some experimentation with how to detect if an I2C read or write had failed the debugging console output began displaying reasonable value

The thread '<No Name>' (0x2) has exited with code 0 (0x0).
devMobile.Longboard.WiiNunchuckTest starting
I2C1
JoyX: 128 JoyY:128 AX:520 AY:508 AZ:708 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:520 AY:504 AZ:716 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:524 AY:508 AZ:716 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:524 AY:536 AZ:708 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:516 AY:528 AZ:724 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:492 AY:524 AZ:720 BtnC:True BtnZ:False
JoyX: 128 JoyY:128 AX:508 AY:528 AZ:700 BtnC:True BtnZ:False
JoyX: 128 JoyY:128 AX:504 AY:532 AZ:716 BtnC:True BtnZ:False
JoyX: 128 JoyY:128 AX:512 AY:532 AZ:724 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:516 AY:532 AZ:712 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:520 AY:532 AZ:708 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:524 AY:532 AZ:708 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:480 AY:504 AZ:688 BtnC:True BtnZ:True
JoyX: 128 JoyY:128 AX:480 AY:520 AZ:728 BtnC:False BtnZ:True
JoyX: 128 JoyY:128 AX:512 AY:520 AZ:704 BtnC:False BtnZ:True
JoyX: 128 JoyY:128 AX:512 AY:548 AZ:708 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:504 AY:516 AZ:728 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:548 AY:536 AZ:704 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:500 AY:528 AZ:728 BtnC:True BtnZ:False
JoyX: 128 JoyY:128 AX:496 AY:524 AZ:716 BtnC:True BtnZ:False
JoyX: 128 JoyY:128 AX:528 AY:536 AZ:696 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:540 AY:540 AZ:720 BtnC:False BtnZ:False
JoyX: 128 JoyY:128 AX:500 AY:520 AZ:684 BtnC:False BtnZ:False
JoyX: 128 JoyY:0 AX:520 AY:508 AZ:696 BtnC:False BtnZ:False
JoyX: 29 JoyY:0 AX:488 AY:576 AZ:716 BtnC:False BtnZ:False
JoyX: 0 JoyY:128 AX:532 AY:540 AZ:700 BtnC:False BtnZ:False
JoyX: 0 JoyY:128 AX:492 AY:512 AZ:708 BtnC:False BtnZ:False
JoyX: 0 JoyY:128 AX:492 AY:516 AZ:708 BtnC:False BtnZ:False
JoyX: 0 JoyY:128 AX:504 AY:512 AZ:708 BtnC:False BtnZ:False
JoyX: 27 JoyY:128 AX:508 AY:520 AZ:700 BtnC:False BtnZ:False
JoyX: 106 JoyY:128 AX:504 AY:516 AZ:700 BtnC:False BtnZ:False
JoyX: 0 JoyY:128 AX:496 AY:520 AZ:700 BtnC:False BtnZ:False
JoyX: 0 JoyY:128 AX:512 AY:532 AZ:716 BtnC:False BtnZ:False
JoyX: 0 JoyY:128 AX:500 AY:516 AZ:708 BtnC:False BtnZ:False
JoyX: 85 JoyY:113 AX:500 AY:536 AZ:720 BtnC:False BtnZ:False
JoyX: 128 JoyY:110 AX:512 AY:532 AZ:712 BtnC:False BtnZ:False
JoyX: 128 JoyY:90 AX:516 AY:528 AZ:716 BtnC:False BtnZ:False
JoyX: 128 JoyY:43 AX:508 AY:468 AZ:660 BtnC:False BtnZ:False
JoyX: 128 JoyY:0 AX:508 AY:532 AZ:712 BtnC:False BtnZ:False
JoyX: 128 JoyY:0 AX:496 AY:524 AZ:716 BtnC:False BtnZ:False

The next test rig will be getting Pulse Width Modulation(PWM) working.

nanoFramework nRF24L01 library Part1

After porting then debugging Windows 10 IoT Core, .NetMF, Wilderness Labs Meadow and GHI Electronics TinyCLR nRF24L01P libraries I figured yet another port, this time to a nanoFramework powered devices should be low risk.

My initial test rig uses a Netduino 3 Wifi and an Embedded Coolness nRF24 shield as I didn’t need to use jumper wires.

//---------------------------------------------------------------------------------
// Copyright (c) July 2020, devMobile Software
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//
//---------------------------------------------------------------------------------
#define NETDUINO3_WIFI   // nanoff --target NETDUINO3_WIFI --update

namespace devMobile.IoT.nRf24L01.ModuleSPI
{
   using System;
   using System.Threading;
   using System.Diagnostics;
   using System.Text;
   using Windows.Devices.Gpio;
   using Windows.Devices.Spi;

   public class Program
   {
      const byte SETUP_AW = 0x03;
      const byte RF_CH = 0x05;
      const byte RX_ADDR_P0 = 0x0A;
      const byte R_REGISTER = 0b00000000;
      const byte W_REGISTER = 0b00100000;
      const string P0_Address = "ZYXWV";

#if NETDUINO3_WIFI
      private const string SpiBusId = "SPI2";
#endif

      public static void Main()
      {
#if NETDUINO3_WIFI
         // Arduino D7->PD7
         int chipSelectPinNumber = PinNumber('A', 1);
#endif
         Debug.WriteLine("devMobile.IoT.nRf24L01.ModuleSPI starting");

         Debug.WriteLine(Windows.Devices.Spi.SpiDevice.GetDeviceSelector());

         try
         {
            GpioController gpioController = GpioController.GetDefault();

            var settings = new SpiConnectionSettings(chipSelectPinNumber)
            {
               ClockFrequency = 2000000,
               Mode = SpiMode.Mode0,
               SharingMode = SpiSharingMode.Shared,
            };

            using (SpiDevice device = SpiDevice.FromId(SpiBusId, settings))
            {
               Debug.WriteLine("nrf24L01Device Device...");
               if (device == null)
               {
                  Debug.WriteLine("nrf24L01Device == null");
               }

               Thread.Sleep(100);

               Debug.WriteLine("ConfigureSpiPort Done...");
               Debug.WriteLine("");

               Thread.Sleep(500);
               try
               {
                  // Read the Address width
                  Debug.WriteLine("Read address width");
                  byte[] txBuffer1 = new byte[] { SETUP_AW | R_REGISTER, 0x0 };
                  byte[] rxBuffer1 = new byte[txBuffer1.Length];

                  Debug.WriteLine(" nrf24L01Device.TransferFullDuplex...SETUP_AW");
                  Debug.WriteLine(" txBuffer:" + BitConverter.ToString(txBuffer1));
                  device.TransferFullDuplex(txBuffer1, rxBuffer1);
                  Debug.WriteLine(" rxBuffer:" + BitConverter.ToString(rxBuffer1));

                  // Extract then adjust the address width
                  byte addressWidthValue = rxBuffer1[1];
                  addressWidthValue &= 0b00000011;
                  addressWidthValue += 2;
                  Debug.WriteLine($"Address width 0x{SETUP_AW:x2} - Value 0X{rxBuffer1[1]:x2} Value adjusted {addressWidthValue}");
                  Debug.WriteLine("");

                  // Write Pipe0 Receive address
                  Debug.WriteLine($"Write Pipe0 Receive Address {P0_Address}");
                  byte[] txBuffer2 = new byte[addressWidthValue + 1];
                  byte[] rxBuffer2 = new byte[txBuffer2.Length];
                  txBuffer2[0] = RX_ADDR_P0 | W_REGISTER;
                  Array.Copy(Encoding.UTF8.GetBytes(P0_Address), 0, txBuffer2, 1, addressWidthValue);

                  Debug.WriteLine(" nrf24L01Device.Write...RX_ADDR_P0");
                  Debug.WriteLine(" txBuffer:" + BitConverter.ToString(txBuffer2));
                  device.TransferFullDuplex(txBuffer2, rxBuffer2);
                  Debug.WriteLine("");

                  // Read Pipe0 Receive address
                  Debug.WriteLine("Read Pipe0 Receive address");
                  byte[] txBuffer3 = new byte[addressWidthValue + 1];
                  txBuffer3[0] = RX_ADDR_P0 | R_REGISTER;
                  byte[] rxBuffer3 = new byte[txBuffer3.Length];

                  Debug.WriteLine(" nrf24L01Device.TransferFullDuplex...RX_ADDR_P0");
                  Debug.WriteLine(" txBuffer:" + BitConverter.ToString(txBuffer3));
                  device.TransferFullDuplex(txBuffer3, rxBuffer3);
                  Debug.WriteLine(" rxBuffer:" + BitConverter.ToString(rxBuffer3));
                  Debug.WriteLine($"Address 0x{RX_ADDR_P0:x2} Address {UTF8Encoding.UTF8.GetString(rxBuffer3, 1, addressWidthValue)}");
                  Debug.WriteLine("");

                  // Read the RF Channel
                  Debug.WriteLine("RF Channel read 1");
                  byte[] txBuffer4 = new byte[] { RF_CH | R_REGISTER, 0x0 };
                  byte[] rxBuffer4 = new byte[txBuffer4.Length];

                  Debug.WriteLine(" nrf24L01Device.TransferFullDuplex...RF_CH");
                  Debug.WriteLine(" txBuffer:" + BitConverter.ToString(txBuffer4));
                  device.TransferFullDuplex(txBuffer4, rxBuffer4);
                  Debug.WriteLine(" rxBuffer:" + BitConverter.ToString(rxBuffer4));

                  byte rfChannel1 = rxBuffer4[1];
                  Debug.WriteLine($"RF Channel 1 0x{RF_CH:x2} - Value 0X{rxBuffer4[1]:x2} - Value adjusted {rfChannel1+2400}");
                  Debug.WriteLine("");

                  // Write the RF Channel
                  Debug.WriteLine("RF Channel write");
                  byte[] txBuffer5 = new byte[] { RF_CH | W_REGISTER, rfChannel1+=1};
                  byte[] rxBuffer5 = new byte[txBuffer5.Length];

                  Debug.WriteLine(" nrf24L01Device.Write...RF_CH");
                  Debug.WriteLine(" txBuffer:" + BitConverter.ToString(txBuffer5));
                  //device.Write(txBuffer5);
                  device.TransferFullDuplex(txBuffer5, rxBuffer5);
                  Debug.WriteLine("");

                  // Read the RF Channel
                  Debug.WriteLine("RF Channel read 2");
                  byte[] txBuffer6 = new byte[] { RF_CH | R_REGISTER, 0x0 };
                  byte[] rxBuffer6 = new byte[txBuffer6.Length];

                  Debug.WriteLine(" nrf24L01Device.TransferFullDuplex...RF_CH");
                  Debug.WriteLine(" txBuffer:" + BitConverter.ToString(txBuffer6));
                  device.TransferFullDuplex(txBuffer6, rxBuffer6);
                  Debug.WriteLine(" rxBuffer:" + BitConverter.ToString(rxBuffer6));

                  byte rfChannel2 = rxBuffer6[1];
                  Debug.WriteLine($"RF Channel 2 0x{RF_CH:x2} - Value 0X{rxBuffer6[1]:x2} - Value adjusted {rfChannel2+2400}");
                  Debug.WriteLine("");
               }
               catch (Exception ex)
               {
                  Debug.WriteLine("Configure Port0 " + ex.Message);
               }
            }
         }
         catch (Exception ex)
         {
            Debug.WriteLine(ex.Message);
         }
      }

#if NETDUINO3_WIFI
      static int PinNumber(char port, byte pin)
      {
         if (port < 'A' || port > 'J')
            throw new ArgumentException();

         return ((port - 'A') * 16) + pin;
      }
#endif
   }
}

After bit of tinkering with SPI configuration options and checking device.Write vs. device.TransferFullDuplex usage. I can reliably read and write my nRF24L01 device’s receive port address and channel configuration.

devMobile.IoT.nRf24L01.ModuleSPI starting
SPI1,SPI2,SPI3,SPI4
nrf24L01Device Device...
ConfigureSpiPort Done...

Read address width
 nrf24L01Device.TransferFullDuplex...SETUP_AW
 txBuffer:03-00
 rxBuffer:0E-03
Address width 0x03 - Value 0X03 Value adjusted 5

Write Pipe0 Receive Address ZYXWV
 nrf24L01Device.Write...RX_ADDR_P0
 txBuffer:2A-5A-59-58-57-56

Read Pipe0 Receive address
 nrf24L01Device.TransferFullDuplex...RX_ADDR_P0
 txBuffer:0A-00-00-00-00-00
 rxBuffer:0E-5A-59-58-57-56
Address 0x0A Address ZYXWV

RF Channel read 1
 nrf24L01Device.TransferFullDuplex...RF_CH
 txBuffer:05-00
 rxBuffer:0E-02
RF Channel 1 0x05 - Value 0X02 - Value adjusted 2402

RF Channel write
 nrf24L01Device.Write...RF_CH
 txBuffer:25-03

RF Channel read 2
 nrf24L01Device.TransferFullDuplex...RF_CH
 txBuffer:05-00
 rxBuffer:0E-03
RF Channel 2 0x05 - Value 0X03 - Value adjusted 2403

The thread '<No Name>' (0x1) has exited with code 0 (0x0).
Done.

Next step is to port my TinyCLR nRF24L01 library which is based on the Techfoonina Windows 10 IoT Core port which is based on .NetMF library by Gralin.