ArduPlane 3.7.1 , graupner GR 16 receiver and sumd protocol

I was flying a small Piper Cub fitted with an APM 2.6 , arduplane and a Graupner radio. To be able to use new software release, I switched to a PixHawk controler.

I decided to connect the Pixhawk and the GR 16 receiver with the DSM interface and the setting SUMDOF08 of the receiver.

But the pixhawk stays in failsafe with these settings. I did some check with a GR12L and it was ok.

After some investigations, I found that on power on, the GR 16 receiver was sending frame with failsafe flag on (=> frame are starting with A8 81 and not A8 01 for a normal frame) up to the connection establishment with the transmitter. After that if the connection is lost, sumd frame are not transmitted.

This is not the case on GR12L : there is not sumd frame transmitted between power on an transmitter connection establishment.

After digging into the code I found that sumd frame with falisafe bit on ( beginning with A8 81) was not recognized as sumd frame (file sumd.c). I think in this case the algorithm concludes that the sumd protocol is not used and lock on another one : this is the reason of my problem.

After modification of sumd.c , sumd.h and controls.c , it is possible to :

  • recognize and decode sumd frame with failsafe bit on
  • set or clear the pixhawk failsafe status with this information.

The issue seems to be solved.

I will try to post detailed modification in a next message.

Benoit

I have some difficulties to extract with git the modification I have done.
=> I can propose unix diff of modifications.
Is there a probability to have them embedded in the master ?

sumd.h and sumd.c are from the ardupilot/modules/PX4Firmware/src/lib/rc directory
controls.c is from the ardupilot/modules/PX4Firmware/src/modules/px4iofirmware directory

diff original/sumd.h modifie/sumd.h
96a97

  • @param failsafe pointer to a boolean where the decoded failsafe flag is written back to
    105c106
    < uint16_t *channels, uint16_t max_chan_count);

  	 uint16_t *channels, bool *failsafe, uint16_t max_chan_count);

diff original/sumd.c modifie/sumd.c
112c112
< int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels,

int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, bool *failsafe,
146c146
< if (byte == SUMD_ID_SUMD || byte == SUMD_ID_SUMH) {


  if (byte == SUMD_ID_SUMD || byte == SUMD_ID_FAILSAFE || byte == SUMD_ID_SUMH) {

312a313,315

  	/* failsafe flag */
  	*failsafe= ( _rxpacket.status == SUMD_ID_FAILSAFE );

diff original/controls.c modifie/controls.c
136a137

bool sumd_failsafe_flag;
145c146
< &sumd_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS));


  				    &sumd_channel_count,  r_raw_rc_values, &sumd_failsafe_flag, PX4IO_RC_INPUT_CHANNELS));

155c156
< r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);

  if (sumd_failsafe_flag) r_raw_rc_flags |= (PX4IO_P_RAW_RC_FLAGS_FAILSAFE); else r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);

Hi Sandre Benoit, I have started to imlement a Pixhawk 2.1 on a RC plane and I do also have Graupner RC equipment and a GR-12L receiver.
Do you know if I can “just” use this receiver and connect it with RC IN on the Pixhawk? Or is the Graupner GR-12L signal not usable for a Pixhawk? And if so what do I need to change?
Thank you very much in advance for every response - of course from other users as well!!!
Alexander

Hello Alexander,

yes it is working with a 12L, tested a few month ago. Use the DSM input, not RCIN.

But if you want to use the MAVlink to HOTT telemetry converter :

http://mediamax.pro/MAVLink2HoTT/

https://discuss.ardupilot.org/t/mavlink-to-hott-telemetry-converter-for-graupner-rc-users/9899/41

the good solution is to use a GR16 (unfortunately more expensive)

Benoit

To detail, HOTT decoder seems to have been reworked.

It is now working well without Ardupilot corrections.

Benoit

Hi Benoit, I thank you very much for your responses. Unfortunately, the Pixhawk 2.1 has no DSM socket (in comparison to Pixhawk 4 for example).
I checked that the GR-12L receiver gives a PPM signal on channel 6 but no chance to receive anything during calibration of the radio controls. Can you imagine any solution?
Best regards,
Alexander

The following page
https://docs.px4.io/master/en/flight_controller/pixhawk-2.html
explains that the DSM input (Spektrum DSM receiver) is present
Benoit