Forwarding RC channels through I2c

Hello everybody,

I am having some trouble forwarding the RC channels through I2c to an arduino. The data flow looks like this:

RCreceiver- Pixhawx6x - I2c- arduino -servos

When the drone is flying, the pixhawk should control the propellers as usual. When landed, the forwarding of the RC-channels should allow an arduino board to control 4 Servos. The servos include some control logic whose driver is already available for Arduino.

I wrote an I2C driver that subscribes to the uOrb rc_channels topic, and forwards it to arduino (the slave in the i2c bus). It took me some time, but I think I got it right. I am a newbie to Nuttx, but C++ is my friend. Using the terminal I launch my driver:

arduino start -X
arduino status

Using my I2c debugger, I see the status of my board, everything is ok. The problem is that the uOrb poll function does not return anything.

Later I found that the task rc_input fails to start. Right after booting my FMU I type dmesg to find two weird lines:

INFO [rc_input] valid device required
ERROR [rc_input] Task start failed (-1)

I am not sure, but I think rc_input takes the raw rc channels from the receiver and translates it to some valid ranges (trimming?) and publishes in the uOrb topic. If rc_input fails to start my code cannot receive anything through uOrb, right?

So, what am I missing?
Any help would be appreciated.

For completeness, here is my RunImpl function and how I declared some variables:


int _rc_channels_sub_fd; 
px4_pollfd_struct_t _fds[1];
_rc_channels_sub_fd = orb_subscribe(ORB_ID(rc_channels));
_fds[0].fd = _rc_channels_sub_fd;
_fds[0].events = POLLIN;

void
Arduino::RunImpl()
{
	struct rc_channels_s rc_t;
	
	int poll_ret = px4_poll(_fds, 1, 1000);

	if ( poll_ret > 0 ) {
		orb_copy(ORB_ID(rc_channels), _rc_channels_sub_fd, &rc_t);
		
		_roll  = rc_t.channels[0];
		_pitch = rc_t.channels[1];
		_yaw   = rc_t.channels[2];

		PX4_INFO("Rc channels:\t%lu\t%lu\t%lu", _roll, _pitch, _yaw);
	}
	else{
		PX4_ERR("Nothing received!");
	}
	
	/* To scale from 0..255 -> 0..15 shift right by 4 bits */
	const uint8_t msg[6] = {
		SUB_ADDR_ROLL,  static_cast<uint8_t> (_roll  >> 4 ) ,
		SUB_ADDR_PITCH, static_cast<uint8_t> (_pitch >> 4 ),
		SUB_ADDR_YAW,   static_cast<uint8_t> (_yaw   >> 4 )
	};

	int ret = transfer(msg, sizeof(msg), nullptr, 0);
	if (ret != OK) 
		PX4_ERR("Error sending");

	/* re-queue ourselves to run again later */
	ScheduleDelayed(TRANSMISSION_RATE);
}

Hi!

Thanks for the nice write up! I’m puzzled why rc_input would fail to start, unless maybe it’s meant to fail but RC will be received by the PX4IO side, the other smaller processor.

What’s the PX4 version that you’re using?

When you do listener rc_input do you see data? Do you see it in uorb top? And can you see RC arriving in QGC?

Thank you for your fast reply. Oh, nice to know there is a secondary processor, pretty convenient.

A little more about my workflow. I am using the Pixhawk 6x from Holybro. I downloaded pretty recently the PX4 repository from github. It is nice to talk to you Julian.

commit 7be327967507955628087fa4aa36e8be1506996c (HEAD -> main)
Author: Julian Oes <julian@oes.ch>
Date:   Mon Mar 13 16:57:57 2023 +1300

I am using docker to build my bin file:

./Tools/docker_run.sh 'make px4_fmu-v6x_default'

Then, with Qgroundcontrol I flash the pixhawk using the bin file under:

build/px4_fmu-v6x_default.bin

I successfully calibrated the rc channels using Q ground control. The GUI displays correctly the state of both joysticks. I tried to listen to the rc_input topic:

nsh> listener rc_input
Topic rc_input did not match any known topics

I tried to launch rc_input manually, defining the device with the -d flag

nsh> rc_input start -d /dev/ttyS3
nsh> rc_input status
INFO  [rc_input] Max update rate: 250 Hz
INFO  [rc_input] UART device: /dev/ttyS3
INFO  [rc_input] UART RX bytes: 2
INFO  [rc_input] RC state: searching for signal: CRSF
rc_input: cycle time: 1623 events, 11629us elapsed, 7.17us avg, min 4us max 579us 21.926us rms
rc_input: publish interval: 0 events, 0.00us avg, min 0us max 0us 0.000us rms
nsh> listener rc_channels
never published

I noticed that the default parameter in rc_input does not work. If I omit the -d flag when starting rc_input I get the error I see on dmesg after startup:

nsh> rc_input start
INFO  [rc_input] valid device required
ERROR [rc_input] Task start failed (-1)

I am probably missing some configuration when building my firmware?

Some other tests:

nsh> listener rc_input
Topic rc_input did not match any known topics
nsh>uorb top
***
rate_ctrl_status                  0    1  807  1   24 
rtl_time_estimate                 0    4    1  1   24
***

The output of px4io troubles me. There are lines that say that SBUS out is disabled. But how can this be if Qground control displays correctly the status of my rc transmitter?
I don’t know if the firmware I create has an effect on Px4IO.

nsh> px4io status
protocol 2147483648 hardware 2147483648 bootloader 2147483648 buffer 2147483648B crc 0x21474836482147483648
2147483648 controls 2147483648 actuators 2147483648 R/C inputs 2147483648 analog inputs
 px4io_status
    timestamp: 517925098 (2758.053467 seconds ago)
    voltage_v: 0.00000
    rssi_v: 1.08700
    free_memory_bytes: 1824
    pwm: [900, 900, 900, 900, 900, 900, 900, 900]
    pwm_disarmed: [900, 900, 900, 900, 900, 900, 900, 900]
    pwm_failsafe: [900, 900, 900, 900, 900, 900, 900, 900]
    pwm_rate_hz: [400, 400, 400, 0, 0, 0, 0, 0]
    raw_inputs: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
    status_arm_sync: True
    status_failsafe: False
    status_fmu_initialized: False
    status_fmu_ok: False
    status_init_ok: True
    status_outputs_armed: False
    status_raw_pwm: False
    status_rc_ok: False
    status_rc_dsm: False
    status_rc_ppm: False
    status_rc_sbus: False
    status_rc_st24: False
    status_rc_sumd: False
    status_safety_button_event: False
    alarm_pwm_error: False
    alarm_rc_lost: True
    arming_failsafe_custom: True
    arming_fmu_armed: False
    arming_fmu_prearmed: False
    arming_force_failsafe: False
    arming_io_arm_ok: True
    arming_lockdown: False
    arming_termination_failsafe: False


0 raw R/C inputs
ADC inputs
features 0x0000
sbus rate 2147483648
debuglevel 2147483648

IMU heater off
INFO  [mixer_module] Param prefix: PWM_MAIN
control latency: 0 events, 0us elapsed, 0.00us avg, min 0us max 0us 0.000us rms
Channel Configuration:
Channel 0: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000
Channel 1: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000
Channel 2: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000
Channel 3: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000
Channel 4: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000
Channel 5: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000
Channel 6: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000
Channel 7: func:   0, value: 0, failsafe: 900, disarmed: 900, min: 1000, max: 2000

Unfortunately, when I try to enable sbus:

nsh> px4io sbus2_out
ERROR [px4io] S.BUS v2 failed (-1)
nsh> px4io sbus1_out
ERROR [px4io] S.BUS v1 failed (-1)

:expressionless:

As a side question, what is left to do to make my driver run at start up?

Well, after I issued all the commands I described on my last post, I did a reboot. I connected to QgroundControl, I checked all RC channels and I came back to the terminal. Something changed:

nsh> listener input_rc

TOPIC: input_rc
 input_rc
    timestamp: 340406311 (0.004635 seconds ago)
    timestamp_last_signal: 340405748
    rssi: 39
    rssi_dbm: nan
    rc_lost_frame_count: 0
    rc_total_frame_count: 25328
    rc_ppm_frame_length: 0
    values: [1500, 1498, 1932, 1500, 1065, 1932, 1933, 1065, 1933, 1932, 1542, 1542, 1514, 1514, 1514, 1514, 998, 998]
    channel_count: 18
    rc_failsafe: False
    rc_lost: False
    input_source: 4
    link_quality: -1
nsh> px4io status
protocol 5 hardware 2 bootloader 3 buffer 64B crc 0x428240645
8 controls 8 actuators 18 R/C inputs 2 analog inputs
 px4io_status
    timestamp: 585959201 (0.158724 seconds ago)
    voltage_v: 0.00000
    rssi_v: 1.08700
    free_memory_bytes: 1824
    pwm: [900, 900, 900, 900, 900, 900, 900, 900]
    pwm_disarmed: [900, 900, 900, 900, 900, 900, 900, 900]
    pwm_failsafe: [900, 900, 900, 900, 900, 900, 900, 900]
    pwm_rate_hz: [400, 400, 400, 0, 0, 0, 0, 0]
    raw_inputs: [1500, 1498, 1932, 1500, 1065, 1932, 1933, 1065, 1933, 1932, 1542, 1542, 1514, 1514, 1514, 1514, 998, 998]
    status_arm_sync: True
    status_failsafe: False
    status_fmu_initialized: False
    status_fmu_ok: False
    status_init_ok: True
    status_outputs_armed: False
    status_raw_pwm: False
    status_rc_ok: True
    status_rc_dsm: False
    status_rc_ppm: False
    status_rc_sbus: True
    status_rc_st24: False
    status_rc_sumd: False
    status_safety_button_event: False
    alarm_pwm_error: False
    alarm_rc_lost: False
    arming_failsafe_custom: True
    arming_fmu_armed: False
    arming_fmu_prearmed: False
    arming_force_failsafe: False
    arming_io_arm_ok: True
    arming_lockdown: False
    arming_termination_failsafe: False

However rc_input refuses to start.

nsh> rc_input start
INFO  [rc_input] valid device required
ERROR [rc_input] Task start failed (-1)
nsh> rc_input start -d /dev/ttyS3
nsh> rc_input status
INFO  [rc_input] Max update rate: 250 Hz
INFO  [rc_input] UART device: /dev/ttyS3
INFO  [rc_input] UART RX bytes: 2
INFO  [rc_input] RC state: searching for signal: SUMD
rc_input: cycle time: 1183 events, 8781us elapsed, 7.42us avg, min 4us max 971us 30.656us rms
rc_input: publish interval: 0 events, 0.00us avg, min 0us max 0us 0.000us rms

Sigh! What an adventure!

I chose /dev/ttyS3 because it is the default device. Probably in version 6x Holybro changed something.

Finally! something came out from the listener!

nsh> listener rc_channels -n 1

TOPIC: rc_channels
 rc_channels
    timestamp: 1216043449 (0.007279 seconds ago)
    timestamp_last_valid: 0
    channels: [0.00000, -0.00000, -0.00000, 0.00000, -1.00000, 0.86122, 1.00000, -1.00000, 1.00000, 1.00000, 0.08399, 0.08399, 0.02799, 0.02799, 0.02799, 0.02799, -1.00000, -1.00000]
    frame_drop_count: 0
    channel_count: 18
    function: [2, 0, 1, 3, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1]
    rssi: 39
    signal_lost: False

Sometimes it is important to be asked the right questions. Thank you Julian. It is working now.

I bought a debug adapter from holybro. My j-link is getting back in business. The Qgroundcontrol programming procedure takes too long.

Just one question, how can I make my driver launch automatically?

Thanks for all that info.

That’s odd that by default RC input does not work. Can you confirm what sort of receiver you’re using and to what connector it is connected? I will test this next week with my Pixhawk 6X and make sure it is correct and working. From your report it looks like something might not be configured right.

You can add the start command to the startup script, e.g. here:

Or if you want to only add it specifically to the Pixhawk 6X:

One thing is that RC might be expected from the PX4IO side but maybe the IO doesn’t recognize it as it should.

If you disable the IO altogether using SYS_USE_IO then it might work via the main/FMU processor.

Thank you for your help.

Here is the radio that I am using: AT9S PRO 12 channels transmitter for racing drone, fixed wing, helicopter, glider, cars and boats It is connected to the Pixhawk using SBUS.

Later today I will try to modify the SYS_USE_IO parameter. I will tell you how it goes.

Looks like something is not right: