How to swith minim osd panels from a tx channel?

I know how to change panels from flight mode in the "change panel" drop down in the minim config software.

But I tried selecting chnl 7 from my tx to change panels and minim osd isn't acknowledging it. How does minim know what the channel values are? There is no servo plug into it. I assume it must be in the form of a mavlink command.

What to be done to get this to work?

Views: 4943

Reply to This

Replies to This Discussion

Ok, to simplify things, I connected the OSD Tx line to my FTDI's Rx line and dumped the raw serial communication data with my Linux. (Do yourself a favor if you try this: issue an "stty -F /dev/ttyUSB0 57600 raw" command to capture raw serial data. If you dd or cat the tty device data into a file, some bytes will be interpreted as terminal control caracters and the file will contain a mess. :) )
Here is the result:
This is the only and entire packet that is sent by the OSD to my Ardupilot.
As you can see, the third request is the data stream request for stream #3, which is the RC_CHANNELS stream.
https://mavlink.io/en/messages/common.html#MAV_DATA_STREAM_RC_CHANNELS

"fe 06 03 63 63 42 02 00 01 01 03 01 6e 42"

fe - Mavlink 1 frame marker
06 - payload length
03 - sequence number (this is the third packet sent)
63 - sender system id
63 - sender component id

42 - message id (#66 decimal - REQUEST_DATA_STREAM)
  02 - requested message rate, L byte
  00 - requested message rate, H byte

  01 - target system id
  01 - target component id
  03 - requested data stream id (MAV_DATA_STREAM_RC_CHANNELS)
  01 - start_stop (1 to start sending, 0 to stop sending)
6e checksum L byte
42 checksum H byte

(https://mavlink.io/en/guide/serialization.html#v1_packet_format)

I captured the data on the Rx line of the OSD, and I have found the RC_CHANNELS messages sent by the Ardupilot (system 01, component 01) regularly:

Radio turned off:
FS LN SQ SS SC MI TS32LH RCLH1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 CC RS CSLH
fe 2a 26 01 01 41 0e280000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 00 00 678c

Radio turned on:
fe 2a 1f 01 01 41 961a0000 db05 da05 2e04 da05 9106 2b06 2904 2904 2904 db05 db05 db05 ea05 ea05 ea05 ea05 0000 0000 10 00 3d0c
(This is a 12ch radio, so the last 4 0x05ea are made up by the Ardupilot, I guess...)

FS - Frame start marker
LN - Payload length (bytes between message id and checksum)
SQ - Frame sequence number
SS - Sender system ID
SC - Sender component ID
MI - Message ID
TSLH - Timestamp (since bootup), low byte first
RCLH - Channel value, low byte first
CC - Number of channels (channel count)
RS - RSSI (system dependent value) (255 - unknown)
CSLH - Checksum (CRC, actually), low byte first

Interesting addendum: the time diff between such two messages are exactly 0x1f4 (500). Since the frequency requested was 0x0002 (Hz), this means that the
values correctly reported twice per second as requested and the timestamp value is in millisecs.
Since it is reported using 32 bits, one MUST have to restart its copter/plane autopilot after every 49 days of continuos operation or else it might fail
even during mid-flight! (Copyright by Matt Parker. ;) )

If anyone is interested in CRC:
Checksum is a CRC-16/MCRF4XX value, always computed from all bytes except the frame start marker. Also, one extra byte salt appended at the end.
The salt is an individual (not unique, but constant) value for all message types. The value is generated from the official message name by a specified algorhythm.
Pre-generated values can be looked up from arrays present in all kind of implementation available.
Here is the C one: https://github.com/mavlink/c_library_v1/blob/master/common/common.h (look for the MAVLINK_MESSAGE_CRCS array)
The message ID in our case is 0x41 = 65, so look up the 66th element in this array.
(Message id numbering starts with 0, so the 1st array element belongs to message #0, the 2nd element to message #1, and so on...)
I help you, the 66th value is 118 = 0x76.
So if you upload for example 2a260101410e280000000000000000000000000000000000000000000000000000000000000000000000000000000076 to
https://crccalc.com/ and select hex as the input type,
you will actually get 0x8C67 in the CRC-16/MCRF4XX row if you click on the "Calc CRC-16" button, and that is not a coincidence! :)

The REQUEST_DATA_STREAM(#66) message stream_ids the OSD sends:

stream_id messages associated
01 - raw sensors: IMU_RAW(#26), GPS_RAW(#24), GPS_STATUS(#25)
02 - extended status: GPS_STATUS(#25), CONTROL_STATUS(?), AUX_STATUS(?)
03 - rc channels: RC_CHANNELS_SCALED(#34), RC_CHANNELS_RAW(#35), SERVO_OUTPUT_RAW(#36)
06 - LOCAL_POSITION(#32,#64,#89), GLOBAL_POSITION/GLOBAL_POSITION_INT(#24,#33,#63)
0a - autopilot dependent
0b - autopilot dependent
0c - autopilot dependent

Distinct messages required (excerpt of above):
#24 0x18
#25 0x19
#26 0x1a
#32 0x20
#33 0x21
#34 0x22
#35 0x23
#36 0x24
#63 0x3f
#64 0x40
#89 0x59

As it turned out, the Ardupilot sends a bunch of mesages by default, not just the heartbeat.
The rate of those messages can be set: http://ardupilot.org/copter/_images/mp_telemetry_rate.png
Messages sent by Ardupilot on its own (without request, captured during ~20sec period):
0x00 - HEARTBEAT
0x01 -
0x18 - GPS_RAW (needed by OSD)
0x1b
0x1d
0x1e
0x21 - GLOBAL_POSITION_INT (needed by OSD)
0x23 - RC_CHANNELS_RAW (needed by OSD)
0x24 - SERVO_OUTPUT_RAW (needed by OSD)
0x2a
0x3e
0x41 - RC_CHANNELS
0x4a
0x6f - (sent only once)
0x74 - (sent two times)
0x7d
0x96 - (sent only once)
0x98
0xb2
0xb6
0xfd

Obviously, when OSD's Tx is connected, all the messages belonging to streams required are reported periodically.
RC_CHANNELS_RAW and is one of those messages.
Messages sent by autopilot with OSD connected (captured during ~10sec period):
0x00 - HEARTBEAT
0x01 -
0x02 -
0x16 -
0x18 -
0x1b -
0x1d -
0x1e -
0x21 -
0x23 -
0x24 -
0x2a -
0x3e -
0x41 -
0x4a -
0x6f - (sent only once)
0x74 - (sent only once)
0x7d -
0x84 -
0x93 -
0x96 - (sent only once)
0x98 -
0xa3 -
0xa5 -
0xad -
0xb2 -
0xb6 -
0xc1 -
0xf1 -
0xfd -
0xfe - (sent only once)

Note: There are some messages which are sent once, or a few times only, during the test period.
This indicates that there are some events that triggers the sending of such messages, since one can not provide less than 1Hz period
in a request.

Some off-topic about my personal problem of connecting multiple devices to the same mavlink serial port with an Y cable follows:

I checked what exactly my radio's telemetry module sends and it turned out that it only requires 0x01,0x03,0xa streams,
which are the SUBSET of what the osd module request!
(Although, with slightly different rate settings: 2,2,10(osd) vs 2,5,5(radio), but I can live with that and more importantly, my radio also happy with those rates. :) )
So it turned out I'm lucky, I can share the same telemetry port with my receiver's telemetry and OSD module using a simple custom Y cable, wiring the radio telemetry as a passive "listener" only (radio telemetry Tx not connected).
The other telemetry port on my PixHawk is used for GroundControl communication. (Unfortunately that's all, only two of the 5 serial ports of PixHawk (named TELEM1,TELEM2,GPS,SERIAL4,SERIAL5) can be used for telemetry connection, because Ardupilot allows only two of them to get associated with MAVLINK communication.)

BTW, my configuration:
Autopilot hardware: PixHawk 1. https://docs.px4.io/en/flight_controller/pixhawk.html
Autopilot software: ArduPilot (ArduCopter V3.6.7)
OSD hw: MinimOSD Micro
OSD sw: microminim.ardupilot.multirotor.hex (ver1.9.1.1 - available at https://github.com/ShikOfTheRa/scarab-osd/releases)
Radio telemetry hw: RadioLink's R12DS receiver with a PRM-03 telemetry module

OSD flashed with MW_OSD_GUI software. (There is a link to it on the firmware download site.)
It requires a cheap FTDI hardware available almost everywhere... (https://i0.wp.com/dronesdecarreras.com/wp-content/uploads/2015/10/M...)
(MinimOSD is a good design: one side of it is pin compatible with the FTDI board. You have to care about only not to flip the board accidentally when connecting. :) )

Ardupilot software is flashed into PixHawk with QGroundControl, using a simple USB cable. (One can use MissionPlanner software also,
but I prefer QGroundControl, since it is available on all platforms, even on android. So I can use my mobile phone as ground control and telemetry display
during flight...)

Summary:
- RC CHANNEL data IS sent through Mavlink to OSD. Moreover, it is sent by default, so even if the OSD is connected as a passive device (only its Rx is connected to the Autopilot's Tx), it should be able to react to radio switch changes. (At least mine works perfectly. However I had to configure OSD configurator to use a 3-state switch assigned to channel 10 to change display modes instead of RSSI value possibly reported on channel 8 - which is the default. See attached screenshots.)
- Connecting two mavlink devices to one telemetry port is simple, but only one of them can have its Tx line connected to Autopilot's Rx. Practically the one with the broadest stream request set.
If other streams are required (because the connected devices reuest mutually exclusive streams and/or the defaults sent by the autopilot are not sufficient), there are still alternatives:
- One can take advantage of flow control and build a simple circuit that enables CTS pins of the connected devices one-by one, so only one device will use Tx line at a time. (Unfortunately neither minimOSD, nor PRM-03 does not support flow control. So in my particular case it wasn't an option.)
- Set the missing streams rate in autopilot (through a GroundControl software). See SR1_xxx, SR2_xxx, SR3_xxx parameters at http://ardupilot.org/copter/docs/parameters.html
Thus the autopilot will send them by default.
- Build a complex microcontroller circuitry with some rerasonable amount of ram that acts as an UART router.
It accepst serial data on multiple connections parallel, stores them temporarily and send them in series to autopilot asap. :)

Sorry guys for the long posts, and for the many off-topics, but I thought if someone else finds this topic because he/she has the same question, he/she has the right to get an as detailed answer as possible. Too many info always can be skipped, but slightly not enough usually does not help at all...

Reply to Discussion

RSS

Groups

Season Two of the Trust Time Trial (T3) Contest 
A list of all T3 contests is here. The current round, the Vertical Horizontal one, is here

© 2019   Created by Chris Anderson.   Powered by

Badges  |  Report an Issue  |  Terms of Service