Commit bda18db3 authored by Bryan Godbolt's avatar Bryan Godbolt

fixed an issue with integration of latest pixhawk changes

parent 84b4fb48
......@@ -34,6 +34,11 @@
SimulinkParameterName="Gain"
QGCParamID="AIL_KD"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Attitude_Controller/PID_AIL/Angle_Norm/Max_Min_Angle/"
SimulinkParameterName="Constant Value"
QGCParamID="ANG_AIL_MAX"
/>
<!-- Elevator Control Parameters -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Attitude_Controller/PID_ELE/kp/"
......@@ -50,6 +55,11 @@
SimulinkParameterName="Gain"
QGCParamID="ELE_KD"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Attitude_Controller/PID_ELE/Angle_Norm/Max_Min_Angle/"
SimulinkParameterName="Constant Value"
QGCParamID="ANG_ELE_MAX"
/>
</Block>
<!-- Paremters for the Pilot Input/Raw RC block -->
......
......@@ -41,7 +41,9 @@ OpalLink::OpalLink() :
componentID(1),
params(NULL),
opalInstID(101),
sendRCValues(false)
sendRCValues(false),
sendRawController(false),
sendPosition(false)
{
start(QThread::LowPriority);
......@@ -134,13 +136,13 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
}
}
break;
case MAVLINK_MSG_ID_REQUEST_RC_CHANNELS:
{
mavlink_request_rc_channels_t rc;
mavlink_msg_request_rc_channels_decode(&msg, &rc);
this->sendRCValues = static_cast<bool>(rc.enabled);
}
break;
// case MAVLINK_MSG_ID_REQUEST_RC_CHANNELS:
// {
// mavlink_request_rc_channels_t rc;
// mavlink_msg_request_rc_channels_decode(&msg, &rc);
// this->sendRCValues = static_cast<bool>(rc.enabled);
// }
// break;
#ifdef MAVLINK_ENABLED_UALBERTA_MESSAGES
case MAVLINK_MSG_ID_RADIO_CALIBRATION:
{
......@@ -217,18 +219,39 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
}
break;
#endif
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
{
mavlink_request_data_stream_t stream;
mavlink_msg_request_data_stream_decode(&msg, &stream);
switch (stream.req_stream_id)
{
case 4:
case 0: // All data types
break;
case 1: // Raw Sensor Data
break;
case 2: // extended system status
break;
case 3: // rc channel data
sendRCValues = (stream.start_stop == 1?true:false);
break;
case 4: // raw controller
if (stream.start_stop == 1)
sendRawController = true;
else
sendRawController = false;
break;
case 5: // raw sensor fusion
break;
case 6: // position
sendPosition = (stream.start_stop == 1?true:false);
break;
case 7: // extra 1
break;
case 8: // extra 2
break;
case 9: // extra 3
break;
default:
qDebug() << __FILE__ << __LINE__ << "Received Unknown Data Strem Request with ID" << stream.req_stream_id;
}
......@@ -239,6 +262,7 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
qDebug() << "OpalLink::writeBytes(): Unknown mavlink packet";
}
}
#endif
}
}
......@@ -311,17 +335,19 @@ void OpalLink::getSignals()
if (returnVal == EOK )
{
/* Send position info to qgroundcontrol */
mavlink_message_t local_position;
mavlink_msg_local_position_pack(systemID, componentID, &local_position,
(*timestep)*1000000,
values[OpalRT::X_POS],
values[OpalRT::Y_POS],
values[OpalRT::Z_POS],
values[OpalRT::X_VEL],
values[OpalRT::Y_VEL],
values[OpalRT::Z_VEL]);
receiveMessage(local_position);
if (sendPosition)
{
mavlink_message_t local_position;
mavlink_msg_local_position_pack(systemID, componentID, &local_position,
(*timestep)*1000000,
values[OpalRT::X_POS],
values[OpalRT::Y_POS],
values[OpalRT::Z_POS],
values[OpalRT::X_VEL],
values[OpalRT::Y_VEL],
values[OpalRT::Z_VEL]);
receiveMessage(local_position);
}
/* send attitude info to qgroundcontrol */
mavlink_message_t attitude;
mavlink_msg_attitude_pack(systemID, componentID, &attitude,
......
......@@ -157,6 +157,7 @@ protected:
bool sendRCValues;
bool sendRawController;
bool sendPosition;
};
#endif // OPALLINK_H
......@@ -955,10 +955,6 @@ void UAS::enableRCChannelDataTransmission(bool enabled)
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
#elif defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
mavlink_message_t msg;
mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
sendMessage(msg);
#endif
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment