rizacelik / SBUS-transmitter-and-receiver

10 stars 2 forks source link

Regarding sbus signal #1

Open Harshhhh16 opened 4 months ago

Harshhhh16 commented 4 months ago

hello bro i connect and run all the code and diagram in proper way but there is no sbus signal receiver in inav please help i also connect bc547 transistor with 4.7k & 10k resistor please help me :)

rizacelik commented 4 months ago

The SBUS signal is inverted in this application. You will not use anything additional. You can connect the signal output directly to the card. See the diagram below.

image

Harshhhh16 commented 4 months ago

ohhh Thank You That's What i need and i have two more doubt

  1. how can we find out our transmitter and receiver connected properly or not means there is any serial monitor command ?
  2. how many channel can we convert to SBUS ?? it's 14 channel can we converted and if yes then how is possible ??
rizacelik commented 4 months ago

Good question.

In the setup section of the code, make D2 and D3 pins as comment lines. As follows. / ch1.attach(2); // Sorvo or ESC output D2 ch2.attach(3); // Sorvo or ESC output D3 /

Then comment the following lines at the end of the code. / ch1.writeMicroseconds(rcChannels[0]); ch2.writeMicroseconds(rcChannels[1]); /

Add the following lines at the beginning of the code.

#include <SoftwareSerial.h>

// Set up a new SoftwareSerial object
SoftwareSerial mySerial = SoftwareSerial(2, 3);

In the Setup section, mySerial.begin(9600); add the line.

void setup() {
     // Set the baud rate for the SoftwareSerial object
     mySerial.begin(9600);

     mySerial.print("ch1: ");
     mySerial.print(rcChannels[0]);
     mySerial.print(" ch2: ");
     mySerial.print(rcChannels[1]);
     mySerial.print(" ch3: ");
     mySerial.print(rcChannels[2]);
     mySerial.print(" ch4: ");
     mySerial.print(rcChannels[3]);
     mySerial.print(" ch5: ");
     mySerial.print(rcChannels[4]);
     mySerial.print(" ch6: ");
     mySerial.print(rcChannels[5]);
     mySerial.print(" ch7: ");
     mySerial.println(rcChannels[6]);

The entire code will be as follows. You reinstate the above changes when your receiver is running. When you connect the STM32F411 borad to the SBUS input, you can see whether your receiver is receiving a signal.

#include <SPI.h>
#include <nRF24L01.h>
#include <RF24.h>
#include <Servo.h>

#include <SoftwareSerial.h>

// Set up a new SoftwareSerial object
SoftwareSerial mySerial =  SoftwareSerial(2, 3);

#define RC_CHANNEL_MIN 990
#define RC_CHANNEL_MAX 2010

#define SBUS_MIN_OFFSET 173
#define SBUS_MID_OFFSET 992
#define SBUS_MAX_OFFSET 1811
#define SBUS_CHANNEL_NUMBER 16
#define SBUS_PACKET_LENGTH 25
#define SBUS_FRAME_HEADER 0x0f
#define SBUS_FRAME_FOOTER 0x00
#define SBUS_FRAME_FOOTER_V2 0x04
#define SBUS_STATE_FAILSAFE 0x08
#define SBUS_STATE_SIGNALLOSS 0x04
#define SBUS_UPDATE_RATE 15  //ms

Servo ch1;
Servo ch2;
Servo ch3;
Servo ch4;
Servo ch5;
Servo ch6;
Servo ch7;

struct joystick {
  byte potLX;
  byte potLY;
  byte potRX;
  byte potRY;
  byte analog1;
  byte analog2;
  byte analog3;
  byte aux1;
  byte aux2;
  byte aux3;
  byte aux4;
  byte aux5;
};

joystick data;

const uint64_t pipeOut = 000322;

RF24 radio(9, 8);

// Default value

void ResetData() {
  data.potLX = 0;
  data.potLY = 127;
  data.potRX = 127;
  data.potRY = 127;
  data.analog1 = 0;
  data.analog2 = 0;
  data.analog3 = 0;
  data.aux1 = 0;
  data.aux2 = 0;
  data.aux3 = 0;
  data.aux4 = 0;
  data.aux5 = 0;
}

void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe) {

  static int output[SBUS_CHANNEL_NUMBER] = { 0 };

  /*
     * Map 1000-2000 with middle at 1500 chanel values to
     * 173-1811 with middle at 992 S.BUS protocol requires
     */
  for (uint8_t i = 0; i < SBUS_CHANNEL_NUMBER; i++) {
    output[i] = map(channels[i], RC_CHANNEL_MIN, RC_CHANNEL_MAX, SBUS_MIN_OFFSET, SBUS_MAX_OFFSET);
  }

  uint8_t stateByte = 0x00;
  if (isSignalLoss) {
    stateByte |= SBUS_STATE_SIGNALLOSS;
  }
  if (isFailsafe) {
    stateByte |= SBUS_STATE_FAILSAFE;
  }
  packet[0] = SBUS_FRAME_HEADER;  //Header

  packet[1] = (uint8_t)(output[0] & 0x07FF);
  packet[2] = (uint8_t)((output[0] & 0x07FF) >> 8 | (output[1] & 0x07FF) << 3);
  packet[3] = (uint8_t)((output[1] & 0x07FF) >> 5 | (output[2] & 0x07FF) << 6);
  packet[4] = (uint8_t)((output[2] & 0x07FF) >> 2);
  packet[5] = (uint8_t)((output[2] & 0x07FF) >> 10 | (output[3] & 0x07FF) << 1);
  packet[6] = (uint8_t)((output[3] & 0x07FF) >> 7 | (output[4] & 0x07FF) << 4);
  packet[7] = (uint8_t)((output[4] & 0x07FF) >> 4 | (output[5] & 0x07FF) << 7);
  packet[8] = (uint8_t)((output[5] & 0x07FF) >> 1);
  packet[9] = (uint8_t)((output[5] & 0x07FF) >> 9 | (output[6] & 0x07FF) << 2);
  packet[10] = (uint8_t)((output[6] & 0x07FF) >> 6 | (output[7] & 0x07FF) << 5);
  packet[11] = (uint8_t)((output[7] & 0x07FF) >> 3);
  packet[12] = (uint8_t)((output[8] & 0x07FF));
  packet[13] = (uint8_t)((output[8] & 0x07FF) >> 8 | (output[9] & 0x07FF) << 3);
  packet[14] = (uint8_t)((output[9] & 0x07FF) >> 5 | (output[10] & 0x07FF) << 6);
  packet[15] = (uint8_t)((output[10] & 0x07FF) >> 2);
  packet[16] = (uint8_t)((output[10] & 0x07FF) >> 10 | (output[11] & 0x07FF) << 1);
  packet[17] = (uint8_t)((output[11] & 0x07FF) >> 7 | (output[12] & 0x07FF) << 4);
  packet[18] = (uint8_t)((output[12] & 0x07FF) >> 4 | (output[13] & 0x07FF) << 7);
  packet[19] = (uint8_t)((output[13] & 0x07FF) >> 1);
  packet[20] = (uint8_t)((output[13] & 0x07FF) >> 9 | (output[14] & 0x07FF) << 2);
  packet[21] = (uint8_t)((output[14] & 0x07FF) >> 6 | (output[15] & 0x07FF) << 5);
  packet[22] = (uint8_t)((output[15] & 0x07FF) >> 3);

  packet[23] = stateByte;          //Flags byte
  packet[24] = SBUS_FRAME_FOOTER;  //Footer
}

uint8_t sbusPacket[SBUS_PACKET_LENGTH];
int rcChannels[SBUS_CHANNEL_NUMBER];

uint32_t currentMillis = 0;
uint32_t sbusTime = 0;

unsigned long lastRecvTime = 0;
unsigned long now = 0;

void setup() {
  mySerial.begin(9600);

  //ch1.attach(2);  // Sorvo or ESC output D2
  //ch2.attach(3);  // Sorvo or ESC output D3
  ch3.attach(4);  // Sorvo or ESC output D4
  ch4.attach(5);  // Sorvo or ESC output D5
  ch5.attach(6);  // Sorvo or ESC output D6
  ch6.attach(7);  // Sorvo or ESC output D6
  ch7.attach(10); // Sorvo or ESC output D10

  ResetData();  // Defaukt channel value
  delay(1000);

  radio.begin();
  radio.openReadingPipe(1,pipeOut);
  radio.setChannel(125);
  radio.setAutoAck(false);
  radio.setDataRate(RF24_250KBPS);
  radio.setPALevel(RF24_PA_MAX);
  radio.startListening();

  delay(1000);
  for (uint8_t i = 0; i < SBUS_CHANNEL_NUMBER; i++) {
    rcChannels[i] = 1500;
    if(i == 2)  rcChannels[i] = 1000;
  }
  delay(1000);
  Serial.begin(100000, SERIAL_8E2); 
}

void loop() {

  if (radio.available()) {
    radio.read(&data, sizeof(joystick));
    lastRecvTime = millis();
  } 

  now = millis();
  if (now - lastRecvTime > 1000) {
    ResetData();
  }

 int randNumber = 1;

  rcChannels[0] = map(data.potRY, 0, 255, 1000, 2000);
  rcChannels[1] = map(255 - data.potRX, 0, 255, 1000, 2000);
  rcChannels[2] = map(data.potLX, 0, 255, 1000, 2000);
  rcChannels[3] = map(data.potLY, 0, 255, 1000, 2000);
  rcChannels[4] = map(data.analog1, 0, 255, 1000, 2000);
  rcChannels[5] = map(data.analog2, 0, 255, 1000, 2000);
  rcChannels[6] = map(data.analog3, 0, 255, 1000, 2000);
  rcChannels[7] = map(data.aux1, 0, 1, 1000, 2000);
  rcChannels[8] = map(data.aux2, 0, 1, 1000, 2000);
  rcChannels[9] = map(data.aux3, 0, 1, 1000, 2000);
  rcChannels[10] = map(data.aux4, 0, 1, 1000, 2000);
  rcChannels[11] = map(data.aux5, 0, 1, 1000, 2000);

  currentMillis = millis();

  if (currentMillis > sbusTime) {
    sbusPreparePacket(sbusPacket, rcChannels, false, false);
    Serial.write(sbusPacket, SBUS_PACKET_LENGTH);
    sbusTime = currentMillis + SBUS_UPDATE_RATE;

    // Write the PWM signal

    //ch1.writeMicroseconds(rcChannels[0]);
    //ch2.writeMicroseconds(rcChannels[1]);
    ch3.writeMicroseconds(rcChannels[2]);
    ch4.writeMicroseconds(rcChannels[3]);
    ch5.writeMicroseconds(rcChannels[4]);
    ch6.writeMicroseconds(rcChannels[5]);
    ch7.writeMicroseconds(rcChannels[6]);

    mySerial.print("ch1: ");
    mySerial.print(rcChannels[0]);
    mySerial.print(" ch2: ");
    mySerial.print(rcChannels[1]);
    mySerial.print(" ch3: ");
    mySerial.print(rcChannels[2]);
    mySerial.print(" ch4: ");
    mySerial.print(rcChannels[3]);
    mySerial.print(" ch5: ");
    mySerial.print(rcChannels[4]);
    mySerial.print(" ch6: ");
    mySerial.print(rcChannels[5]);
    mySerial.print(" ch7: ");
    mySerial.println(rcChannels[6]);
  }
}
Harshhhh16 commented 4 months ago

Thank you so much brother one last how many channel can we add to this sbus receiver ???

rizacelik commented 4 months ago

For the transmitter.

Pin A7 and pin D10 are just idle. So you can add 2 more channels. A7 pin is analog. So byte analog4; You can add the variable. D10 pin is digital. This pin byte aux6; You can add the variable. It should be like below.

struct joystick {
   byte potLX;
   byte potLY;
   byte potRX;
   byte potRY;
   byte analog1;
   byte analog2;
   byte analog3;
byte analog4;
   byte aux1;
   byte aux2;
   byte aux3;
   byte aux4;
   byte aux5;
byte aux6;
};

Defining an entry for D10 pin in the Setup section

pinMode(10, INPUT_PULLUP);

Analog reading for A7 pin

joystickData.analog4 = map(analogRead(A7), 0, 1023, 0, 255);

Reading D10 pin

   if (digitalRead(10)) {
     bitWrite(joystickData.aux6, 0, 0);
   } else {
     bitWrite(joystickData.aux6, 0, 1);
   }

COPLETE CODE

#include <SPI.h>
#include <nRF24L01.h>
#include <RF24.h>

struct joystick {
  byte potLX;
  byte potLY;
  byte potRX;
  byte potRY;
  byte analog1;
  byte analog2;
  byte analog3;
  byte analog4;
  byte aux1;
  byte aux2;
  byte aux3;
  byte aux4;
  byte aux5;
  byte aux6;
};

joystick joystickData;

RF24 radio(9, 8); // CE, CSN;

const uint64_t pipeOut = 000322;

void setup() {

  Serial.begin(9600);

  pinMode(2, INPUT_PULLUP); 
  pinMode(3, INPUT_PULLUP);
  pinMode(4, INPUT_PULLUP); 
  pinMode(5, INPUT_PULLUP);
  pinMode(6, INPUT_PULLUP); 
  pinMode(10, INPUT_PULLUP); 

  radio.begin();
  radio.openWritingPipe(pipeOut);
  radio.setChannel(125);
  radio.setAutoAck(false);
  radio.setDataRate(RF24_250KBPS);
  radio.setPALevel(RF24_PA_MAX);
  radio.stopListening();

}

void loop() {

  int x = constrain(1023 - analogRead(A3), 513, 1023);
  joystickData.potLX = map(x , 513, 1023, 0, 255);
  joystickData.potLY = map(analogRead(A2), 0, 1023, 0, 255);
  joystickData.potRX = map(analogRead(A1), 0, 1023, 0, 255);
  joystickData.potRY = map(analogRead(A0), 0, 1023, 0, 255);

  joystickData.analog1 = map(analogRead(A4), 0, 1023, 0, 255);
  joystickData.analog2 = map(analogRead(A5), 0, 1023, 0, 255);
  joystickData.analog3 = map(analogRead(A6), 0, 1023, 0, 255);
  joystickData.analog4 = map(analogRead(A7), 0, 1023, 0, 255);

  if (digitalRead(2)) {
    bitWrite(joystickData.aux1, 0, 0);
  } else {
    bitWrite(joystickData.aux1, 0, 1);
  }

  if (digitalRead(3)) {
    bitWrite(joystickData.aux2, 0, 0);
  } else {
    bitWrite(joystickData.aux2, 0, 1);
  }

  if (digitalRead(4)) {
    bitWrite(joystickData.aux3, 0, 0);
  } else {
    bitWrite(joystickData.aux3, 0, 1);
  }

  if (digitalRead(5)) {
    bitWrite(joystickData.aux4, 0, 0);
  } else {
    bitWrite(joystickData.aux4, 0, 1);
  }

  if (digitalRead(6)) {
    bitWrite(joystickData.aux5, 0, 0);
  } else {
    bitWrite(joystickData.aux5, 0, 1);
  }

  if (digitalRead(10)) {
    bitWrite(joystickData.aux6, 0, 0);
  } else {
    bitWrite(joystickData.aux6, 0, 1);
  }

Serial.print("LX:");
Serial.print(joystickData.potLX); 
Serial.print(" LY:");
Serial.print(joystickData.potLY); 
Serial.print(" RX:");
Serial.print(joystickData.potRX); 
Serial.print(" RY:");
Serial.print(joystickData.potRY); 
Serial.print("   A1:");
Serial.print(analogRead(A4)); 
Serial.print(" A2:");
Serial.print(analogRead(A5)); 
Serial.print(" A3:");
Serial.print(analogRead(A6)); 

Serial.print("   B1:");
Serial.print(digitalRead(3)); 
Serial.print(" B2:");
Serial.print(digitalRead(4)); 
Serial.print(" B3:");
Serial.print(digitalRead(5)); 
Serial.print(" B4:");
Serial.print(digitalRead(6)); 
Serial.print(" B5:");
Serial.println(digitalRead(7)); 

  // Send write data to RF
  radio.write(&joystickData, sizeof(joystick));
  //delay(50);

}
rizacelik commented 4 months ago

Receiver Complete Code Add A7 and D10 pins.

#include <SPI.h>
#include <nRF24L01.h>
#include <RF24.h>
#include <Servo.h>

#include <SoftwareSerial.h>

// Set up a new SoftwareSerial object
SoftwareSerial mySerial =  SoftwareSerial(2, 3);

#define RC_CHANNEL_MIN 990
#define RC_CHANNEL_MAX 2010

#define SBUS_MIN_OFFSET 173
#define SBUS_MID_OFFSET 992
#define SBUS_MAX_OFFSET 1811
#define SBUS_CHANNEL_NUMBER 16
#define SBUS_PACKET_LENGTH 25
#define SBUS_FRAME_HEADER 0x0f
#define SBUS_FRAME_FOOTER 0x00
#define SBUS_FRAME_FOOTER_V2 0x04
#define SBUS_STATE_FAILSAFE 0x08
#define SBUS_STATE_SIGNALLOSS 0x04
#define SBUS_UPDATE_RATE 15  //ms

Servo ch1;
Servo ch2;
Servo ch3;
Servo ch4;
Servo ch5;
Servo ch6;
Servo ch7;

struct joystick {
  byte potLX;
  byte potLY;
  byte potRX;
  byte potRY;
  byte analog1;
  byte analog2;
  byte analog3;
  byte analog4;
  byte aux1;
  byte aux2;
  byte aux3;
  byte aux4;
  byte aux5;
  byte aux6;
};

joystick data;

const uint64_t pipeOut = 000322;

RF24 radio(9, 8);

// Default value

void ResetData() {
  data.potLX = 0;
  data.potLY = 127;
  data.potRX = 127;
  data.potRY = 127;
  data.analog1 = 0;
  data.analog2 = 0;
  data.analog3 = 0;
  data.analog4 = 0;
  data.aux1 = 0;
  data.aux2 = 0;
  data.aux3 = 0;
  data.aux4 = 0;
  data.aux5 = 0;
  data.aux6 = 0;
}

void sbusPreparePacket(uint8_t packet[], int channels[], bool isSignalLoss, bool isFailsafe) {

  static int output[SBUS_CHANNEL_NUMBER] = { 0 };

  /*
     * Map 1000-2000 with middle at 1500 chanel values to
     * 173-1811 with middle at 992 S.BUS protocol requires
     */
  for (uint8_t i = 0; i < SBUS_CHANNEL_NUMBER; i++) {
    output[i] = map(channels[i], RC_CHANNEL_MIN, RC_CHANNEL_MAX, SBUS_MIN_OFFSET, SBUS_MAX_OFFSET);
  }

  uint8_t stateByte = 0x00;
  if (isSignalLoss) {
    stateByte |= SBUS_STATE_SIGNALLOSS;
  }
  if (isFailsafe) {
    stateByte |= SBUS_STATE_FAILSAFE;
  }
  packet[0] = SBUS_FRAME_HEADER;  //Header

  packet[1] = (uint8_t)(output[0] & 0x07FF);
  packet[2] = (uint8_t)((output[0] & 0x07FF) >> 8 | (output[1] & 0x07FF) << 3);
  packet[3] = (uint8_t)((output[1] & 0x07FF) >> 5 | (output[2] & 0x07FF) << 6);
  packet[4] = (uint8_t)((output[2] & 0x07FF) >> 2);
  packet[5] = (uint8_t)((output[2] & 0x07FF) >> 10 | (output[3] & 0x07FF) << 1);
  packet[6] = (uint8_t)((output[3] & 0x07FF) >> 7 | (output[4] & 0x07FF) << 4);
  packet[7] = (uint8_t)((output[4] & 0x07FF) >> 4 | (output[5] & 0x07FF) << 7);
  packet[8] = (uint8_t)((output[5] & 0x07FF) >> 1);
  packet[9] = (uint8_t)((output[5] & 0x07FF) >> 9 | (output[6] & 0x07FF) << 2);
  packet[10] = (uint8_t)((output[6] & 0x07FF) >> 6 | (output[7] & 0x07FF) << 5);
  packet[11] = (uint8_t)((output[7] & 0x07FF) >> 3);
  packet[12] = (uint8_t)((output[8] & 0x07FF));
  packet[13] = (uint8_t)((output[8] & 0x07FF) >> 8 | (output[9] & 0x07FF) << 3);
  packet[14] = (uint8_t)((output[9] & 0x07FF) >> 5 | (output[10] & 0x07FF) << 6);
  packet[15] = (uint8_t)((output[10] & 0x07FF) >> 2);
  packet[16] = (uint8_t)((output[10] & 0x07FF) >> 10 | (output[11] & 0x07FF) << 1);
  packet[17] = (uint8_t)((output[11] & 0x07FF) >> 7 | (output[12] & 0x07FF) << 4);
  packet[18] = (uint8_t)((output[12] & 0x07FF) >> 4 | (output[13] & 0x07FF) << 7);
  packet[19] = (uint8_t)((output[13] & 0x07FF) >> 1);
  packet[20] = (uint8_t)((output[13] & 0x07FF) >> 9 | (output[14] & 0x07FF) << 2);
  packet[21] = (uint8_t)((output[14] & 0x07FF) >> 6 | (output[15] & 0x07FF) << 5);
  packet[22] = (uint8_t)((output[15] & 0x07FF) >> 3);

  packet[23] = stateByte;          //Flags byte
  packet[24] = SBUS_FRAME_FOOTER;  //Footer
}

uint8_t sbusPacket[SBUS_PACKET_LENGTH];
int rcChannels[SBUS_CHANNEL_NUMBER];

uint32_t currentMillis = 0;
uint32_t sbusTime = 0;

unsigned long lastRecvTime = 0;
unsigned long now = 0;

void setup() {
  mySerial.begin(9600);

  //ch1.attach(2);  // Sorvo or ESC output D2
  //ch2.attach(3);  // Sorvo or ESC output D3
  ch3.attach(4);  // Sorvo or ESC output D4
  ch4.attach(5);  // Sorvo or ESC output D5
  ch5.attach(6);  // Sorvo or ESC output D6
  ch6.attach(7);  // Sorvo or ESC output D6
  ch7.attach(10); // Sorvo or ESC output D10

  ResetData();  // Defaukt channel value
  delay(1000);

  radio.begin();
  radio.openReadingPipe(1,pipeOut);
  radio.setChannel(125);
  radio.setAutoAck(false);
  radio.setDataRate(RF24_250KBPS);
  radio.setPALevel(RF24_PA_MAX);
  radio.startListening();

  delay(1000);
  for (uint8_t i = 0; i < SBUS_CHANNEL_NUMBER; i++) {
    rcChannels[i] = 1500;
    if(i == 2)  rcChannels[i] = 1000;
  }
  delay(1000);
  Serial.begin(100000, SERIAL_8E2); 
}

void loop() {

  if (radio.available()) {
    radio.read(&data, sizeof(joystick));
    lastRecvTime = millis();
  } 

  now = millis();
  if (now - lastRecvTime > 1000) {
    ResetData();
  }

 int randNumber = 1;

  rcChannels[0] = map(data.potRY, 0, 255, 1000, 2000);
  rcChannels[1] = map(255 - data.potRX, 0, 255, 1000, 2000);
  rcChannels[2] = map(data.potLX, 0, 255, 1000, 2000);
  rcChannels[3] = map(data.potLY, 0, 255, 1000, 2000);
  rcChannels[4] = map(data.analog1, 0, 255, 1000, 2000);
  rcChannels[5] = map(data.analog2, 0, 255, 1000, 2000);
  rcChannels[6] = map(data.analog3, 0, 255, 1000, 2000);
  rcChannels[7] = map(data.analog3, 0, 255, 1000, 2000);
  rcChannels[8] = map(data.aux1, 0, 1, 1000, 2000);
  rcChannels[9] = map(data.aux2, 0, 1, 1000, 2000);
  rcChannels[10] = map(data.aux3, 0, 1, 1000, 2000);
  rcChannels[11] = map(data.aux4, 0, 1, 1000, 2000);
  rcChannels[12] = map(data.aux5, 0, 1, 1000, 2000);
  rcChannels[13] = map(data.aux5, 0, 1, 1000, 2000);

  currentMillis = millis();

  if (currentMillis > sbusTime) {
    sbusPreparePacket(sbusPacket, rcChannels, false, false);
    Serial.write(sbusPacket, SBUS_PACKET_LENGTH);
    sbusTime = currentMillis + SBUS_UPDATE_RATE;

    // Write the PWM signal

    //ch1.writeMicroseconds(rcChannels[0]);
    //ch2.writeMicroseconds(rcChannels[1]);
    ch3.writeMicroseconds(rcChannels[2]);
    ch4.writeMicroseconds(rcChannels[3]);
    ch5.writeMicroseconds(rcChannels[4]);
    ch6.writeMicroseconds(rcChannels[5]);
    ch7.writeMicroseconds(rcChannels[6]);

    mySerial.print("ch1: ");
    mySerial.print(rcChannels[0]);
    mySerial.print(" ch2: ");
    mySerial.print(rcChannels[1]);
    mySerial.print(" ch3: ");
    mySerial.print(rcChannels[2]);
    mySerial.print(" ch4: ");
    mySerial.print(rcChannels[3]);
    mySerial.print(" ch5: ");
    mySerial.print(rcChannels[4]);
    mySerial.print(" ch6: ");
    mySerial.print(rcChannels[5]);
    mySerial.print(" ch7: ");
    mySerial.println(rcChannels[6]);
  }
}
rizacelik commented 4 months ago

You can work with a total of 14 channels. It has 16 channel support, but only 14 channels can be programmed with Arduino nano pins.

Harshhhh16 commented 4 months ago

Thank you so much for your'e time i will build it and love from india 🥇

Harshhhh16 commented 4 months ago

hello bro when i tested 12 vhannel code and add servo motor to pin D2 & D3 the signal is transfer smoothly but sbus output is not showing in inav please help :(

Screenshot 2024-04-12 104029 Screenshot 2024-04-12 104104

rizacelik commented 4 months ago

please select UART2 Serial Rx

image

Harshhhh16 commented 4 months ago

When I select it automatic disable? What’s the problem ? Yesterday i select it but there is no this problem :(

rizacelik commented 4 months ago

I don't understand You chose URAT2 and it didn't work?

Harshhhh16 commented 4 months ago

When i select URAT2 and press save and reboot then its not select URAT2 why this problem coming?

rizacelik commented 4 months ago

Just select Serial Rx. Save then switch to the Receiver tab. Test it. If you have another receiver, you can try that too.

Harshhhh16 commented 4 months ago

thank you brother it's work :) how to reverse the channel ??

rizacelik commented 4 months ago

There is no inversion. You use it directly. Look at the diagram I gave you.

Harshhhh16 commented 4 months ago

there is 2 reverse channel , i connect the throttle pin in A4 , yaw pin in A3 and Roll in A0, Pitch in A1 but there is throttle pin is in reverse when i up the throttle in inav that is goes down value and similarly with roll how can i fix the problem ??

rizacelik commented 4 months ago

only for Transmitter

Add this function to your code.

int invert_map(int val, int lower, int middle, int upper, bool reverse) {
   val = constrain(val, lower, upper);
   if (val < middle) {
      val = map(val, lower, middle, 0, 128);
   } else {
      val = map(val, middle, upper, 128, 255);
   }
   return (reverse ? 255 - val : val);
}

Example usage to invert the value coming from pin A3.

joystickData.potLX = invert_map( analogRead(A3), 0, 512, 1023, true );

"true" means it will be inverted.

Harshhhh16 commented 4 months ago

thank you so much bro it's solve the problem......

Harshhhh16 commented 4 months ago

Hello first upon sorry for to much questioning my last doubt is i build stm32 fc and this tx & rx but there is some delay in signal what's the problem? and also range is also getting less around 20m i check nrf module and replace it but it didn't work can you find out what's the problem for getting 3/4s delay and less range ???

rizacelik commented 4 months ago

Share pictures of the transmitter and receiver. You need to see how you do it.

Possible problems.

  1. There may be a lack of 7-12 volt supply to the Arduino Nano power input. Use 9V batteries.

  2. You did not insulate your transmitter with aluminum foil. Be careful not to short circuit the foil. Do not let it touch the bare parts of the module. Your module may burn.

  3. The power coming to the module must be 3.3v. You may not have used the LM1117GS 3.3V I used in the circuit for this.