Commit db00ea6e authored by pixhawk's avatar pixhawk

Added Extra Message Checkboxes

parent 5d7774ee
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -714,6 +714,94 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
sendMessage(msg);
}
void UAS::enablePositionTransmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 6;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::enableExtra1Transmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 7;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::enableExtra2Transmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 8;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::enableExtra3Transmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 9;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::setParameter(int component, QString id, float value)
{
mavlink_message_t msg;
......
......@@ -202,6 +202,10 @@ public slots:
void enableRCChannelDataTransmission(bool enabled);
void enableRawControllerDataTransmission(bool enabled);
void enableRawSensorFusionTransmission(bool enabled);
void enablePositionTransmission(bool enabled);
void enableExtra1Transmission(bool enabled);
void enableExtra2Transmission(bool enabled);
void enableExtra3Transmission(bool enabled);
/** @brief Update the system state */
void updateState();
......
......@@ -12,6 +12,10 @@ QGCSensorSettingsWidget::QGCSensorSettingsWidget(UASInterface* uas, QWidget *par
connect(ui->sendControllerCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableRawControllerDataTransmission(bool)));
connect(ui->sendExtendedCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtendedSystemStatusTransmission(bool)));
connect(ui->sendRCCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableRCChannelDataTransmission(bool)));
connect(ui->sendPositionCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enablePositionTransmission(bool)));
connect(ui->sendExtra1CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra1Transmission(bool)));
connect(ui->sendExtra2CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra2Transmission(bool)));
connect(ui->sendExtra3CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra3Transmission(bool)));
}
QGCSensorSettingsWidget::~QGCSensorSettingsWidget()
......
......@@ -54,6 +54,34 @@
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QCheckBox" name="sendPositionCheckBox">
<property name="text">
<string>Send position setpoint and estimate</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QCheckBox" name="sendExtra1CheckBox">
<property name="text">
<string>Send Extra1</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QCheckBox" name="sendExtra2CheckBox">
<property name="text">
<string>Send Extra2</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QCheckBox" name="sendExtra3CheckBox">
<property name="text">
<string>Send Extra3</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
......
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