6#include <QtNetwork/QHostAddress>
12ESP8266ComponentController::ESP8266ComponentController(QObject *parent)
14 , _baud(getParameterFact(componentID(), QStringLiteral(
"UART_BAUDRATE")))
15 , _ver(getParameterFact(componentID(), QStringLiteral(
"SW_VER")))
16 , _ssid1(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSID1")))
17 , _ssid2(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSID2")))
18 , _ssid3(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSID3")))
19 , _ssid4(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSID4")))
20 , _pwd1(getParameterFact(componentID(), QStringLiteral(
"WIFI_PASSWORD1")))
21 , _pwd2(getParameterFact(componentID(), QStringLiteral(
"WIFI_PASSWORD2")))
22 , _pwd3(getParameterFact(componentID(), QStringLiteral(
"WIFI_PASSWORD3")))
23 , _pwd4(getParameterFact(componentID(), QStringLiteral(
"WIFI_PASSWORD4")))
24 , _ssidsta1(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSIDSTA1"), false))
25 , _ssidsta2(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSIDSTA2"), false))
26 , _ssidsta3(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSIDSTA3"), false))
27 , _ssidsta4(getParameterFact(componentID(), QStringLiteral(
"WIFI_SSIDSTA4"), false))
28 , _pwdsta1(getParameterFact(componentID(), QStringLiteral(
"WIFI_PWDSTA1"), false))
29 , _pwdsta2(getParameterFact(componentID(), QStringLiteral(
"WIFI_PWDSTA2"), false))
30 , _pwdsta3(getParameterFact(componentID(), QStringLiteral(
"WIFI_PWDSTA3"), false))
31 , _pwdsta4(getParameterFact(componentID(), QStringLiteral(
"WIFI_PWDSTA4"), false))
35 for (
int i = 1; i < 12; i++) {
36 _channels.append(QString::number(i));
40 (void) connect(_ssid4, &
Fact::valueChanged,
this, &ESP8266ComponentController::_ssidChanged);
41 (void) connect(_pwd4, &
Fact::valueChanged,
this, &ESP8266ComponentController::_passwordChanged);
42 (void) connect(_baud, &
Fact::valueChanged,
this, &ESP8266ComponentController::_baudChanged);
43 (void) connect(_ver, &
Fact::valueChanged,
this, &ESP8266ComponentController::_versionChanged);
46ESP8266ComponentController::~ESP8266ComponentController()
51QString ESP8266ComponentController::version()
const
53 const uint32_t uv = getParameterFact(componentID(), QStringLiteral(
"SW_VER"))->rawValue().toUInt();
54 const QString versionString = QStringLiteral(
"%1.%2.%3").arg(uv >> 24).arg((uv >> 16) & 0xFF).arg(uv & 0xFFFF);
58QString ESP8266ComponentController::wifiIPAddress()
60 if (_ipAddress.isEmpty()) {
61 if (parameterExists(componentID(), QStringLiteral(
"WIFI_IPADDRESS"))) {
62 const QHostAddress address(qFromBigEndian(getParameterFact(componentID(), QStringLiteral(
"WIFI_IPADDRESS"))->rawValue().toUInt()));
63 _ipAddress = address.toString();
65 _ipAddress = QStringLiteral(
"192.168.4.1");
72QString ESP8266ComponentController::wifiSSID()
const
74 const uint32_t s1 = _ssid1->rawValue().toUInt();
75 const uint32_t s2 = _ssid2->rawValue().toUInt();
76 const uint32_t s3 = _ssid3->rawValue().toUInt();
77 const uint32_t s4 = _ssid4->rawValue().toUInt();
80 (void) memcpy(&tmp[0], &s1,
sizeof(uint32_t));
81 (void) memcpy(&tmp[4], &s2,
sizeof(uint32_t));
82 (void) memcpy(&tmp[8], &s3,
sizeof(uint32_t));
83 (void) memcpy(&tmp[12], &s4,
sizeof(uint32_t));
88void ESP8266ComponentController::setWifiSSID(
const QString &ssid)
const
91 (void) memset(tmp, 0,
sizeof(tmp));
92 const std::string sid = ssid.toStdString();
93 (void) strncpy(tmp, sid.c_str(),
sizeof(tmp) - 1);
96 (void) memcpy(&u, &tmp[0],
sizeof(uint32_t));
97 _ssid1->setRawValue(QVariant(u));
98 (void) memcpy(&u, &tmp[4],
sizeof(uint32_t));
99 _ssid2->setRawValue(QVariant(u));
100 (void) memcpy(&u, &tmp[8],
sizeof(uint32_t));
101 _ssid3->setRawValue(QVariant(u));
102 (void) memcpy(&u, &tmp[12],
sizeof(uint32_t));
103 _ssid4->setRawValue(QVariant(u));
106QString ESP8266ComponentController::wifiPassword()
const
108 const uint32_t s1 = _pwd1->rawValue().toUInt();
109 const uint32_t s2 = _pwd2->rawValue().toUInt();
110 const uint32_t s3 = _pwd3->rawValue().toUInt();
111 const uint32_t s4 = _pwd4->rawValue().toUInt();
114 (void) memcpy(&tmp[0], &s1,
sizeof(uint32_t));
115 (void) memcpy(&tmp[4], &s2,
sizeof(uint32_t));
116 (void) memcpy(&tmp[8], &s3,
sizeof(uint32_t));
117 (void) memcpy(&tmp[12], &s4,
sizeof(uint32_t));
122void ESP8266ComponentController::setWifiPassword(
const QString &password)
const
125 (void) memset(tmp, 0,
sizeof(tmp));
126 const std::string pwd = password.toStdString();
127 (void) strncpy(tmp, pwd.c_str(),
sizeof(tmp) - 1);
130 (void) memcpy(&u, &tmp[0],
sizeof(uint32_t));
131 _pwd1->setRawValue(QVariant(u));
132 (void) memcpy(&u, &tmp[4],
sizeof(uint32_t));
133 _pwd2->setRawValue(QVariant(u));
134 (void) memcpy(&u, &tmp[8],
sizeof(uint32_t));
135 _pwd3->setRawValue(QVariant(u));
136 (void) memcpy(&u, &tmp[12],
sizeof(uint32_t));
137 _pwd4->setRawValue(QVariant(u));
140QString ESP8266ComponentController::wifiSSIDSta()
const
142 if (!parameterExists(componentID(),
"WIFI_SSIDSTA1")) {
146 const uint32_t s1 = _ssidsta1->rawValue().toUInt();
147 const uint32_t s2 = _ssidsta2->rawValue().toUInt();
148 const uint32_t s3 = _ssidsta3->rawValue().toUInt();
149 const uint32_t s4 = _ssidsta4->rawValue().toUInt();
152 (void) memcpy(&tmp[0], &s1,
sizeof(uint32_t));
153 (void) memcpy(&tmp[4], &s2,
sizeof(uint32_t));
154 (void) memcpy(&tmp[8], &s3,
sizeof(uint32_t));
155 (void) memcpy(&tmp[12], &s4,
sizeof(uint32_t));
160void ESP8266ComponentController::setWifiSSIDSta(
const QString &ssid)
const
162 if (!parameterExists(componentID(),
"WIFI_SSIDSTA1")) {
167 (void) memset(tmp, 0,
sizeof(tmp));
168 const std::string sid = ssid.toStdString();
169 (void) strncpy(tmp, sid.c_str(),
sizeof(tmp) - 1);
172 (void) memcpy(&u, &tmp[0],
sizeof(uint32_t));
173 _ssidsta1->setRawValue(QVariant(u));
174 (void) memcpy(&u, &tmp[4],
sizeof(uint32_t));
175 _ssidsta2->setRawValue(QVariant(u));
176 (void) memcpy(&u, &tmp[8],
sizeof(uint32_t));
177 _ssidsta3->setRawValue(QVariant(u));
178 (void) memcpy(&u, &tmp[12],
sizeof(uint32_t));
179 _ssidsta4->setRawValue(QVariant(u));
182QString ESP8266ComponentController::wifiPasswordSta()
const
184 if (!parameterExists(componentID(), QStringLiteral(
"WIFI_PWDSTA1"))) {
188 const uint32_t s1 = _pwdsta1->rawValue().toUInt();
189 const uint32_t s2 = _pwdsta2->rawValue().toUInt();
190 const uint32_t s3 = _pwdsta3->rawValue().toUInt();
191 const uint32_t s4 = _pwdsta4->rawValue().toUInt();
194 (void) memcpy(&tmp[0], &s1,
sizeof(uint32_t));
195 (void) memcpy(&tmp[4], &s2,
sizeof(uint32_t));
196 (void) memcpy(&tmp[8], &s3,
sizeof(uint32_t));
197 (void) memcpy(&tmp[12], &s4,
sizeof(uint32_t));
202void ESP8266ComponentController::setWifiPasswordSta(
const QString &password)
const
204 if (!parameterExists(componentID(), QStringLiteral(
"WIFI_PWDSTA1"))) {
209 (void) memset(tmp, 0,
sizeof(tmp));
210 const std::string pwd = password.toStdString();
211 (void) strncpy(tmp, pwd.c_str(),
sizeof(tmp) - 1);
214 (void) memcpy(&u, &tmp[0],
sizeof(uint32_t));
215 _pwdsta1->setRawValue(QVariant(u));
216 (void) memcpy(&u, &tmp[4],
sizeof(uint32_t));
217 _pwdsta2->setRawValue(QVariant(u));
218 (void) memcpy(&u, &tmp[8],
sizeof(uint32_t));
219 _pwdsta3->setRawValue(QVariant(u));
220 (void) memcpy(&u, &tmp[12],
sizeof(uint32_t));
221 _pwdsta4->setRawValue(QVariant(u));
224int ESP8266ComponentController::baudIndex()
const
226 const int b = getParameterFact(componentID(), QStringLiteral(
"UART_BAUDRATE"))->rawValue().toInt();
242void ESP8266ComponentController::setBaudIndex(
int idx)
const
244 if ((idx >= 0) && (idx != baudIndex())) {
262 _baud->setRawValue(baud);
266void ESP8266ComponentController::reboot()
268 _waitType = WAIT_FOR_REBOOT;
274void ESP8266ComponentController::restoreDefaults()
276 _waitType = WAIT_FOR_RESTORE;
282void ESP8266ComponentController::_reboot()
const
285 qCDebug(ESP8266ComponentControllerLog) <<
"_reboot()";
288void ESP8266ComponentController::_restoreDefaults()
const
291 qCDebug(ESP8266ComponentControllerLog) <<
"_restoreDefaults()";
294void ESP8266ComponentController::_mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode)
296 Q_UNUSED(vehicleId); Q_UNUSED(failureCode);
298 if (component != componentID()) {
302 if (result != MAV_RESULT_ACCEPTED) {
303 qCWarning(ESP8266ComponentControllerLog) <<
"ESP8266ComponentController command" << command <<
"rejected.";
307 if (((_waitType == WAIT_FOR_REBOOT) && (command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN)) || ((_waitType == WAIT_FOR_RESTORE) && (command == MAV_CMD_PREFLIGHT_STORAGE))) {
308 _waitType = WAIT_FOR_NOTHING;
310 qCDebug(ESP8266ComponentControllerLog) <<
"_commandAck for" << command;
311 if (command == MAV_CMD_PREFLIGHT_STORAGE) {
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Used for handling missing Facts from C++ code.
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
void refreshAllParameters(uint8_t componentID=MAV_COMP_ID_ALL)
Re-request the full set of parameters from the autopilot.
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
ParameterManager * parameterManager()
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)