Commit df7c060b authored by James Goppert's avatar James Goppert

Added datarate spin box's

parent a50b0425
...@@ -883,7 +883,7 @@ void UAS::readParametersFromStorage() ...@@ -883,7 +883,7 @@ void UAS::readParametersFromStorage()
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableAllDataTransmission(bool enabled) void UAS::enableAllDataTransmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -893,9 +893,11 @@ void UAS::enableAllDataTransmission(bool enabled) ...@@ -893,9 +893,11 @@ void UAS::enableAllDataTransmission(bool enabled)
stream.req_stream_id = MAV_DATA_STREAM_ALL; stream.req_stream_id = MAV_DATA_STREAM_ALL;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
// All messages will be send with their default rate // All messages will be send with their default rate
// TODO: use 0 to turn off and get rid of enable/disable? will require
// a different magic flag for turning on defaults, possibly something really high like 1111 ?
stream.req_message_rate = 0; stream.req_message_rate = 0;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -907,7 +909,7 @@ void UAS::enableAllDataTransmission(bool enabled) ...@@ -907,7 +909,7 @@ void UAS::enableAllDataTransmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableRawSensorDataTransmission(bool enabled) void UAS::enableRawSensorDataTransmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -915,9 +917,9 @@ void UAS::enableRawSensorDataTransmission(bool enabled) ...@@ -915,9 +917,9 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS; stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSORS;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -929,7 +931,7 @@ void UAS::enableRawSensorDataTransmission(bool enabled) ...@@ -929,7 +931,7 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableExtendedSystemStatusTransmission(bool enabled) void UAS::enableExtendedSystemStatusTransmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -937,9 +939,9 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled) ...@@ -937,9 +939,9 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS; stream.req_stream_id = MAV_DATA_STREAM_EXTENDED_STATUS;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 10; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -951,7 +953,7 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled) ...@@ -951,7 +953,7 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableRCChannelDataTransmission(bool enabled) void UAS::enableRCChannelDataTransmission(int rate)
{ {
#if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES) #if defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
mavlink_message_t msg; mavlink_message_t msg;
...@@ -963,9 +965,9 @@ void UAS::enableRCChannelDataTransmission(bool enabled) ...@@ -963,9 +965,9 @@ void UAS::enableRCChannelDataTransmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS; stream.req_stream_id = MAV_DATA_STREAM_RC_CHANNELS;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -978,7 +980,7 @@ void UAS::enableRCChannelDataTransmission(bool enabled) ...@@ -978,7 +980,7 @@ void UAS::enableRCChannelDataTransmission(bool enabled)
#endif #endif
} }
void UAS::enableRawControllerDataTransmission(bool enabled) void UAS::enableRawControllerDataTransmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -986,9 +988,9 @@ void UAS::enableRawControllerDataTransmission(bool enabled) ...@@ -986,9 +988,9 @@ void UAS::enableRawControllerDataTransmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER; stream.req_stream_id = MAV_DATA_STREAM_RAW_CONTROLLER;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -1000,7 +1002,7 @@ void UAS::enableRawControllerDataTransmission(bool enabled) ...@@ -1000,7 +1002,7 @@ void UAS::enableRawControllerDataTransmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableRawSensorFusionTransmission(bool enabled) void UAS::enableRawSensorFusionTransmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -1008,9 +1010,9 @@ void UAS::enableRawSensorFusionTransmission(bool enabled) ...@@ -1008,9 +1010,9 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION; stream.req_stream_id = MAV_DATA_STREAM_RAW_SENSOR_FUSION;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -1022,7 +1024,7 @@ void UAS::enableRawSensorFusionTransmission(bool enabled) ...@@ -1022,7 +1024,7 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enablePositionTransmission(bool enabled) void UAS::enablePositionTransmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -1030,9 +1032,9 @@ void UAS::enablePositionTransmission(bool enabled) ...@@ -1030,9 +1032,9 @@ void UAS::enablePositionTransmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_POSITION; stream.req_stream_id = MAV_DATA_STREAM_POSITION;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -1044,7 +1046,7 @@ void UAS::enablePositionTransmission(bool enabled) ...@@ -1044,7 +1046,7 @@ void UAS::enablePositionTransmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableExtra1Transmission(bool enabled) void UAS::enableExtra1Transmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -1052,9 +1054,9 @@ void UAS::enableExtra1Transmission(bool enabled) ...@@ -1052,9 +1054,9 @@ void UAS::enableExtra1Transmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_EXTRA1; stream.req_stream_id = MAV_DATA_STREAM_EXTRA1;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -1066,7 +1068,7 @@ void UAS::enableExtra1Transmission(bool enabled) ...@@ -1066,7 +1068,7 @@ void UAS::enableExtra1Transmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableExtra2Transmission(bool enabled) void UAS::enableExtra2Transmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -1074,9 +1076,9 @@ void UAS::enableExtra2Transmission(bool enabled) ...@@ -1074,9 +1076,9 @@ void UAS::enableExtra2Transmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_EXTRA2; stream.req_stream_id = MAV_DATA_STREAM_EXTRA2;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
...@@ -1088,7 +1090,7 @@ void UAS::enableExtra2Transmission(bool enabled) ...@@ -1088,7 +1090,7 @@ void UAS::enableExtra2Transmission(bool enabled)
sendMessage(msg); sendMessage(msg);
} }
void UAS::enableExtra3Transmission(bool enabled) void UAS::enableExtra3Transmission(int rate)
{ {
// Buffers to write data to // Buffers to write data to
mavlink_message_t msg; mavlink_message_t msg;
...@@ -1096,9 +1098,9 @@ void UAS::enableExtra3Transmission(bool enabled) ...@@ -1096,9 +1098,9 @@ void UAS::enableExtra3Transmission(bool enabled)
// Select the message to request from now on // Select the message to request from now on
stream.req_stream_id = MAV_DATA_STREAM_EXTRA3; stream.req_stream_id = MAV_DATA_STREAM_EXTRA3;
// Select the update rate in Hz the message should be send // Select the update rate in Hz the message should be send
stream.req_message_rate = 200; stream.req_message_rate = rate;
// Start / stop the message // Start / stop the message
stream.start_stop = (enabled) ? 1 : 0; stream.start_stop = (rate) ? 1 : 0;
// The system which should take this command // The system which should take this command
stream.target_system = uasId; stream.target_system = uasId;
// The component / subsystem which should take this command // The component / subsystem which should take this command
......
...@@ -223,16 +223,16 @@ public slots: ...@@ -223,16 +223,16 @@ public slots:
/** @brief Read parameters from permanent storage */ /** @brief Read parameters from permanent storage */
void readParametersFromStorage(); void readParametersFromStorage();
void enableAllDataTransmission(bool enabled); void enableAllDataTransmission(int rate);
void enableRawSensorDataTransmission(bool enabled); void enableRawSensorDataTransmission(int rate);
void enableExtendedSystemStatusTransmission(bool enabled); void enableExtendedSystemStatusTransmission(int rate);
void enableRCChannelDataTransmission(bool enabled); void enableRCChannelDataTransmission(int rate);
void enableRawControllerDataTransmission(bool enabled); void enableRawControllerDataTransmission(int rate);
void enableRawSensorFusionTransmission(bool enabled); void enableRawSensorFusionTransmission(int rate);
void enablePositionTransmission(bool enabled); void enablePositionTransmission(int rate);
void enableExtra1Transmission(bool enabled); void enableExtra1Transmission(int rate);
void enableExtra2Transmission(bool enabled); void enableExtra2Transmission(int rate);
void enableExtra3Transmission(bool enabled); void enableExtra3Transmission(int rate);
/** @brief Update the system state */ /** @brief Update the system state */
void updateState(); void updateState();
......
...@@ -221,7 +221,7 @@ public slots: ...@@ -221,7 +221,7 @@ public slots:
virtual void setSelected() = 0; virtual void setSelected() = 0;
virtual void enableAllDataTransmission(bool enabled) = 0; virtual void enableAllDataTransmission(bool enabled) = 0;
virtual void enableRawSensorDataTransmission(bool enabled) = 0; virtual void enableRawSensorDataTransmission(bool enabled, int rate = 0) = 0;
virtual void enableExtendedSystemStatusTransmission(bool enabled) = 0; virtual void enableExtendedSystemStatusTransmission(bool enabled) = 0;
virtual void enableRCChannelDataTransmission(bool enabled) = 0; virtual void enableRCChannelDataTransmission(bool enabled) = 0;
virtual void enableRawControllerDataTransmission(bool enabled) = 0; virtual void enableRawControllerDataTransmission(bool enabled) = 0;
......
...@@ -37,14 +37,15 @@ QGCSensorSettingsWidget::QGCSensorSettingsWidget(UASInterface* uas, QWidget *par ...@@ -37,14 +37,15 @@ QGCSensorSettingsWidget::QGCSensorSettingsWidget(UASInterface* uas, QWidget *par
ui(new Ui::QGCSensorSettingsWidget) ui(new Ui::QGCSensorSettingsWidget)
{ {
ui->setupUi(this); ui->setupUi(this);
connect(ui->sendRawCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableRawSensorDataTransmission(bool))); // XXX: This might be a bad idea sending a message every time the value changes
connect(ui->sendControllerCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableRawControllerDataTransmission(bool))); connect(ui->spinBox_rawSensor, SIGNAL(valueChanged(int)), mav, SLOT(enableRawSensorDataTransmission(int)));
connect(ui->sendExtendedCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtendedSystemStatusTransmission(bool))); connect(ui->spinBox_controller, SIGNAL(valueChanged(int)), mav, SLOT(enableRawControllerDataTransmission(int)));
connect(ui->sendRCCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableRCChannelDataTransmission(bool))); connect(ui->spinBox_extended, SIGNAL(valueChanged(int)), mav, SLOT(enableExtendedSystemStatusTransmission(int)));
connect(ui->sendPositionCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enablePositionTransmission(bool))); connect(ui->spinBox_rc, SIGNAL(valueChanged(int)), mav, SLOT(enableRCChannelDataTransmission(int)));
connect(ui->sendExtra1CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra1Transmission(bool))); connect(ui->spinBox_position, SIGNAL(valueChanged(int)), mav, SLOT(enablePositionTransmission(int)));
connect(ui->sendExtra2CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra2Transmission(bool))); connect(ui->spinBox_extra1, SIGNAL(valueChanged(int)), mav, SLOT(enableExtra1Transmission(int)));
connect(ui->sendExtra3CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra3Transmission(bool))); connect(ui->spinBox_extra2, SIGNAL(valueChanged(int)), mav, SLOT(enableExtra2Transmission(int)));
connect(ui->spinBox_extra3, SIGNAL(valueChanged(int)), mav, SLOT(enableExtra3Transmission(int)));
// Calibration // Calibration
connect(ui->rcCalButton, SIGNAL(clicked()), mav, SLOT(startRadioControlCalibration())); connect(ui->rcCalButton, SIGNAL(clicked()), mav, SLOT(startRadioControlCalibration()));
......
...@@ -6,7 +6,7 @@ ...@@ -6,7 +6,7 @@
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>231</width> <width>237</width>
<height>221</height> <height>221</height>
</rect> </rect>
</property> </property>
...@@ -75,7 +75,7 @@ ...@@ -75,7 +75,7 @@
<item row="0" column="0"> <item row="0" column="0">
<widget class="QGroupBox" name="groupBox"> <widget class="QGroupBox" name="groupBox">
<property name="title"> <property name="title">
<string>Activate Extended Output</string> <string>Data Stream Rates (Hz)</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout_2"> <layout class="QGridLayout" name="gridLayout_2">
<property name="leftMargin"> <property name="leftMargin">
...@@ -97,70 +97,114 @@ ...@@ -97,70 +97,114 @@
<number>2</number> <number>2</number>
</property> </property>
<item row="0" column="0"> <item row="0" column="0">
<widget class="QCheckBox" name="sendRawCheckBox"> <widget class="QSpinBox" name="spinBox_rawSensor">
<property name="enabled"> <property name="maximum">
<bool>true</bool> <number>10000</number>
</property> </property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label">
<property name="text"> <property name="text">
<string>RAW Sensors</string> <string>Raw Sensor</string>
</property> </property>
<property name="checked"> </widget>
<bool>false</bool> </item>
<item row="1" column="0">
<widget class="QSpinBox" name="spinBox_extended">
<property name="maximum">
<number>10000</number>
</property> </property>
<property name="tristate"> </widget>
<bool>false</bool> </item>
<item row="4" column="0">
<widget class="QSpinBox" name="spinBox_position">
<property name="maximum">
<number>10000</number>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="1"> <item row="5" column="0">
<widget class="QCheckBox" name="sendRCCheckBox"> <widget class="QSpinBox" name="spinBox_controller">
<property name="enabled"> <property name="maximum">
<bool>true</bool> <number>10000</number>
</property> </property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="label_2">
<property name="text"> <property name="text">
<string>RC Values</string> <string>Extended</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="0"> <item row="4" column="1">
<widget class="QCheckBox" name="sendPositionCheckBox"> <widget class="QLabel" name="label_3">
<property name="text"> <property name="text">
<string>Position CTRL</string> <string>Position</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="0"> <item row="5" column="1">
<widget class="QCheckBox" name="sendControllerCheckBox"> <widget class="QLabel" name="label_4">
<property name="text"> <property name="text">
<string>Attitude CTRL</string> <string>Controller</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="1"> <item row="0" column="2">
<widget class="QCheckBox" name="sendExtra1CheckBox"> <widget class="QSpinBox" name="spinBox_rc">
<property name="maximum">
<number>10000</number>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QSpinBox" name="spinBox_extra1">
<property name="maximum">
<number>10000</number>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QSpinBox" name="spinBox_extra2">
<property name="maximum">
<number>10000</number>
</property>
</widget>
</item>
<item row="5" column="2">
<widget class="QSpinBox" name="spinBox_extra3">
<property name="maximum">
<number>10000</number>
</property>
</widget>
</item>
<item row="0" column="3">
<widget class="QLabel" name="label_5">
<property name="text"> <property name="text">
<string>Send Extra1</string> <string>RC Values</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="0"> <item row="1" column="3">
<widget class="QCheckBox" name="sendExtendedCheckBox"> <widget class="QLabel" name="label_6">
<property name="text"> <property name="text">
<string>Attitude</string> <string>Extra 1</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="1"> <item row="4" column="3">
<widget class="QCheckBox" name="sendExtra2CheckBox"> <widget class="QLabel" name="label_7">
<property name="text"> <property name="text">
<string>Send Extra2</string> <string>Extra 2</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="5" column="1"> <item row="5" column="3">
<widget class="QCheckBox" name="sendExtra3CheckBox"> <widget class="QLabel" name="label_8">
<property name="text"> <property name="text">
<string>Send Extra3</string> <string>Extra 3</string>
</property> </property>
</widget> </widget>
</item> </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