diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc index f6c241ae53cd1f2166d72bd6a8ac492d7acdd67d..962df646476d4a4497fce17bf0f7106679f1c346 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc @@ -55,12 +55,7 @@ FlightModesComponentController::FlightModesComponentController(void) : _init(); _validateConfiguration(); - connect(_uas, &UASInterface::remoteControlChannelRawChanged, this, &FlightModesComponentController::_remoteControlChannelRawChanged); -} - -FlightModesComponentController::~FlightModesComponentController() -{ - disconnect(_uas, &UASInterface::remoteControlChannelRawChanged, this, &FlightModesComponentController::_remoteControlChannelRawChanged); + connect(_vehicle, &Vehicle::rcChannelsChanged, this, &FlightModesComponentController::_rcChannelsChanged); } void FlightModesComponentController::_init(void) @@ -209,27 +204,29 @@ void FlightModesComponentController::_validateConfiguration(void) } } -/// @brief This routine is called whenever a raw value for an RC channel changes. -/// @param chan RC channel on which signal is coming from (0-based) -/// @param fval Current value for channel -void FlightModesComponentController::_remoteControlChannelRawChanged(int chan, float fval) +/// Connected to Vehicle::rcChannelsChanged signal +void FlightModesComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]) { - Q_ASSERT(chan >= 0 && chan <= _chanMax); - - if (fval < _rgRCMin[chan]) { - fval= _rgRCMin[chan]; - } - if (fval > _rgRCMax[chan]) { - fval= _rgRCMax[chan]; - } - - float percentRange = (fval - _rgRCMin[chan]) / (float)(_rgRCMax[chan] - _rgRCMin[chan]); - if (_rgRCReversed[chan]) { - percentRange = 1.0 - percentRange; + for (int channel=0; channel _rgRCMax[channel]) { + channelValue= _rgRCMax[channel]; + } + + float percentRange = (channelValue - _rgRCMin[channel]) / (float)(_rgRCMax[channel] - _rgRCMin[channel]); + if (_rgRCReversed[channel]) { + percentRange = 1.0 - percentRange; + } + + _rcValues[channel] = percentRange; + } } - _rcValues[chan] = percentRange; - _recalcModeSelections(); emit switchLiveRangeChanged(); diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.h b/src/AutoPilotPlugins/PX4/FlightModesComponentController.h index 091f0de115dd9d77c3cfaf6e9cb48b97a3d73cfc..9070de31c9d045e19d2e5a64d05505d2377f2506 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.h +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.h @@ -43,7 +43,6 @@ class FlightModesComponentController : public FactPanelController public: FlightModesComponentController(void); - ~FlightModesComponentController(); Q_PROPERTY(bool validConfiguration MEMBER _validConfiguration CONSTANT) Q_PROPERTY(QString configurationErrors MEMBER _configurationErrors CONSTANT) @@ -183,7 +182,7 @@ signals: void modeRowsChanged(void); private slots: - void _remoteControlChannelRawChanged(int chan, float fval); + void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]); private: double _switchLiveRange(const QString& param); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 925f9ab821e6ac084a7db1e28986a3e4d2e0f1d8..d4c281cde89573df54dd7e0f1e333a9e49b07023 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -119,10 +119,10 @@ Vehicle::Vehicle(LinkInterface* link, setLatitude(_uas->getLatitude()); setLongitude(_uas->getLongitude()); - connect(_uas, &UAS::latitudeChanged, this, &Vehicle::setLatitude); - connect(_uas, &UAS::longitudeChanged, this, &Vehicle::setLongitude); - connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady); - connect(_uas, &UAS::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged); + connect(_uas, &UAS::latitudeChanged, this, &Vehicle::setLatitude); + connect(_uas, &UAS::longitudeChanged, this, &Vehicle::setLongitude); + connect(_uas, &UAS::imageReady, this, &Vehicle::_imageReady); + connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged); _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _autopilotPlugin = _autopilotPluginManager->newAutopilotPluginForVehicle(this); @@ -211,12 +211,18 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes _firmwarePlugin->adjustMavlinkMessage(&message); switch (message.msgid) { - case MAVLINK_MSG_ID_HOME_POSITION: - _handleHomePosition(message); - break; - case MAVLINK_MSG_ID_HEARTBEAT: - _handleHeartbeat(message); - break; + case MAVLINK_MSG_ID_HOME_POSITION: + _handleHomePosition(message); + break; + case MAVLINK_MSG_ID_HEARTBEAT: + _handleHeartbeat(message); + break; + case MAVLINK_MSG_ID_RC_CHANNELS: + _handleRCChannels(message); + break; + case MAVLINK_MSG_ID_RC_CHANNELS_RAW: + _handleRCChannelsRaw(message); + break; } emit mavlinkMessageReceived(message); @@ -281,6 +287,89 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message) } } +void Vehicle::_handleRCChannels(mavlink_message_t& message) +{ + mavlink_rc_channels_t channels; + + mavlink_msg_rc_channels_decode(&message, &channels); + + uint16_t* _rgChannelvalues[cMaxRcChannels] = { + &channels.chan1_raw, + &channels.chan2_raw, + &channels.chan3_raw, + &channels.chan4_raw, + &channels.chan5_raw, + &channels.chan6_raw, + &channels.chan7_raw, + &channels.chan8_raw, + &channels.chan9_raw, + &channels.chan10_raw, + &channels.chan11_raw, + &channels.chan12_raw, + &channels.chan13_raw, + &channels.chan14_raw, + &channels.chan15_raw, + &channels.chan16_raw, + &channels.chan17_raw, + &channels.chan18_raw, + }; + int pwmValues[cMaxRcChannels]; + + for (int i=0; i 0) - emit remoteControlChannelRawChanged(0, channels.chan1_raw); - if (channels.chan2_raw != UINT16_MAX && channels.chancount > 1) - emit remoteControlChannelRawChanged(1, channels.chan2_raw); - if (channels.chan3_raw != UINT16_MAX && channels.chancount > 2) - emit remoteControlChannelRawChanged(2, channels.chan3_raw); - if (channels.chan4_raw != UINT16_MAX && channels.chancount > 3) - emit remoteControlChannelRawChanged(3, channels.chan4_raw); - if (channels.chan5_raw != UINT16_MAX && channels.chancount > 4) - emit remoteControlChannelRawChanged(4, channels.chan5_raw); - if (channels.chan6_raw != UINT16_MAX && channels.chancount > 5) - emit remoteControlChannelRawChanged(5, channels.chan6_raw); - if (channels.chan7_raw != UINT16_MAX && channels.chancount > 6) - emit remoteControlChannelRawChanged(6, channels.chan7_raw); - if (channels.chan8_raw != UINT16_MAX && channels.chancount > 7) - emit remoteControlChannelRawChanged(7, channels.chan8_raw); - if (channels.chan9_raw != UINT16_MAX && channels.chancount > 8) - emit remoteControlChannelRawChanged(8, channels.chan9_raw); - if (channels.chan10_raw != UINT16_MAX && channels.chancount > 9) - emit remoteControlChannelRawChanged(9, channels.chan10_raw); - if (channels.chan11_raw != UINT16_MAX && channels.chancount > 10) - emit remoteControlChannelRawChanged(10, channels.chan11_raw); - if (channels.chan12_raw != UINT16_MAX && channels.chancount > 11) - emit remoteControlChannelRawChanged(11, channels.chan12_raw); - if (channels.chan13_raw != UINT16_MAX && channels.chancount > 12) - emit remoteControlChannelRawChanged(12, channels.chan13_raw); - if (channels.chan14_raw != UINT16_MAX && channels.chancount > 13) - emit remoteControlChannelRawChanged(13, channels.chan14_raw); - if (channels.chan15_raw != UINT16_MAX && channels.chancount > 14) - emit remoteControlChannelRawChanged(14, channels.chan15_raw); - if (channels.chan16_raw != UINT16_MAX && channels.chancount > 15) - emit remoteControlChannelRawChanged(15, channels.chan16_raw); - if (channels.chan17_raw != UINT16_MAX && channels.chancount > 16) - emit remoteControlChannelRawChanged(16, channels.chan17_raw); - if (channels.chan18_raw != UINT16_MAX && channels.chancount > 17) - emit remoteControlChannelRawChanged(17, channels.chan18_raw); - } break; - // TODO: (gg 20150420) PX4 Firmware does not seem to send this message. Don't know what to do about it. - case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: - { - mavlink_rc_channels_scaled_t channels; - mavlink_msg_rc_channels_scaled_decode(&message, &channels); - - const unsigned int portWidth = 8; // XXX magic number - - emit remoteControlRSSIChanged(channels.rssi); - if (static_cast(channels.chan1_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f); - if (static_cast(channels.chan2_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 1, channels.chan2_scaled/10000.0f); - if (static_cast(channels.chan3_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 2, channels.chan3_scaled/10000.0f); - if (static_cast(channels.chan4_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 3, channels.chan4_scaled/10000.0f); - if (static_cast(channels.chan5_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 4, channels.chan5_scaled/10000.0f); - if (static_cast(channels.chan6_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 5, channels.chan6_scaled/10000.0f); - if (static_cast(channels.chan7_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 6, channels.chan7_scaled/10000.0f); - if (static_cast(channels.chan8_scaled) != UINT16_MAX) - emit remoteControlChannelScaledChanged(channels.port * portWidth + 7, channels.chan8_scaled/10000.0f); - } - break; case MAVLINK_MSG_ID_PARAM_VALUE: { mavlink_param_value_t rawValue; diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 24f5b8148c792b56e540e20626539cb828ec1da2..4fabdcdc5596a065799729064088e25226777b35 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -302,13 +302,6 @@ signals: /** @brief Differential pressure / airspeed status changed */ void airspeedStatusChanged(bool supported, bool enabled, bool ok); - /** @brief Value of a remote control channel (raw) */ - void remoteControlChannelRawChanged(int channelId, float raw); - /** @brief Value of a remote control channel (scaled)*/ - void remoteControlChannelScaledChanged(int channelId, float normalized); - /** @brief Remote control RSSI changed (0% - 100%)*/ - void remoteControlRSSIChanged(uint8_t rssi); - /** * @brief Localization quality changed * @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization