miw01
(Masafumi Miwa)
April 26, 2021, 11:24am
1
Dear all,
I have a question about RC override with GamePad.
Is it possible to specify RC channels to override?
For example, I would like to control the aircraft with a radio-controlled transmitter while controlling the camera with the GamePad button.
Thank you.
miw01
(Masafumi Miwa)
April 27, 2021, 2:18am
3
Oh really.
I’ll check around GCS_MAVLINK.cpp and modify it.
Thank you.
miw01
(Masafumi Miwa)
April 27, 2021, 6:57am
4
I modified GCS_Common.cpp, and built Copter-4.0.7.
When RC 9ch is more than 1700, 1-4 ch values of radio control are added to 1-4 ch of GamePad.
When RC 9ch is less than 1700 or there is no radio control signal, it remains the GamePad signal.
When I checked the operation, it worked as expected.
I used Durandal connected to PC by usb, R7008SB, 14SG, and InterLink controller connected to PC and tested on Mission Planner.
void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg)
{
if(msg.sysid != sysid_my_gcs()) {
return; // Only accept control from our gcs
}
const uint32_t tnow = AP_HAL::millis();
mavlink_rc_channels_override_t packet;
mavlink_msg_rc_channels_override_decode(&msg, &packet);
if (hal.rcin->read(CH_9) > 1700){
packet.chan1_raw += hal.rcin->read(CH_1) - rc().channel(0)->get_radio_trim();
packet.chan2_raw += hal.rcin->read(CH_2) - rc().channel(1)->get_radio_trim();
packet.chan3_raw += hal.rcin->read(CH_3) - rc().channel(2)->get_radio_trim();
packet.chan4_raw += hal.rcin->read(CH_4) - rc().channel(3)->get_radio_trim();
}
I added the last if statement.
Is there any software problem?
Thank you.
miw01
(Masafumi Miwa)
April 27, 2021, 7:07am
5
I thought that it means no radio control signal when hal.rcin->read(CH_9) returns 0.
Is it correct?
miw01
(Masafumi Miwa)
April 27, 2021, 11:32pm
6
This is based on the mix function of Futaba’s trainer mode.
yes this is possible.
in latest ardupilot you need to set all the normal RC transmitter channels to UINT16_MAX in mission planner, so they are ignored, and then the gymbal channels as normal
packet.chan11_raw,
packet.chan12_raw,
packet.chan13_raw,
packet.chan14_raw,
packet.chan15_raw,
packet.chan16_raw
};
for (uint8_t i=0; i<8; i++) {
// Per MAVLink spec a value of UINT16_MAX means to ignore this field.
if (override_data[i] != UINT16_MAX) {
RC_Channels::set_override(i, override_data[i], tnow);
}
}
for (uint8_t i=8; i<ARRAY_SIZE(override_data); i++) {
// Per MAVLink spec a value of zero or UINT16_MAX means to
// ignore this field.
if (override_data[i] != 0 && override_data[i] != UINT16_MAX) {
// per the mavlink spec, a value of UINT16_MAX-1 means
// return the field to RC radio values:
const uint16_t value = override_data[i] == (UINT16_MAX-1) ? 0 : override_data[i];