Commit 81ccc01d authored by pixhawk's avatar pixhawk

Minor improvements throughout the application to improve usability

parent ca9e82a3
...@@ -121,8 +121,8 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -121,8 +121,8 @@ void MAVLinkSimulationMAV::mainloop()
pos.alt = z*1000.0; pos.alt = z*1000.0;
pos.lat = y*1E7; pos.lat = y*1E7;
pos.lon = x*1E7; pos.lon = x*1E7;
pos.vx = 0; pos.vx = sin(yaw)*10.0f;
pos.vy = 0; pos.vy = cos(yaw)*10.0f;
pos.vz = 0; pos.vz = 0;
mavlink_msg_global_position_int_encode(systemid, MAV_COMP_ID_IMU, &msg, &pos); mavlink_msg_global_position_int_encode(systemid, MAV_COMP_ID_IMU, &msg, &pos);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
...@@ -164,18 +164,21 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -164,18 +164,21 @@ void MAVLinkSimulationMAV::mainloop()
control_status.control_pos_xy = 1; control_status.control_pos_xy = 1;
control_status.control_pos_yaw = 1; control_status.control_pos_yaw = 1;
control_status.control_pos_z = 1; control_status.control_pos_z = 1;
control_status.gps_fix = 2; // 2D GPS fix
control_status.position_fix = 3; // 3D fix from GPS + barometric pressure
control_status.vision_fix = 0; // no fix from vision system
mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status); mavlink_msg_control_status_encode(systemid, MAV_COMP_ID_IMU, &ret, &control_status);
link->sendMAVLinkMessage(&ret); link->sendMAVLinkMessage(&ret);
// Send actual controller outputs // Send actual controller outputs
// This message just shows the direction // This message just shows the direction
// and magnitude of the control output // and magnitude of the control output
mavlink_position_controller_output_t pos; // mavlink_position_controller_output_t pos;
pos.x = sin(yaw)*127.0f; // pos.x = sin(yaw)*127.0f;
pos.y = cos(yaw)*127.0f; // pos.y = cos(yaw)*127.0f;
pos.z = 0; // pos.z = 0;
mavlink_msg_position_controller_output_encode(systemid, MAV_COMP_ID_IMU, &ret, &pos); // mavlink_msg_position_controller_output_encode(systemid, MAV_COMP_ID_IMU, &ret, &pos);
link->sendMAVLinkMessage(&ret); // link->sendMAVLinkMessage(&ret);
// Send a named value with name "FLOAT" and 0.5f as value // Send a named value with name "FLOAT" and 0.5f as value
......
...@@ -50,9 +50,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -50,9 +50,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (message.sysid == uasId) if (message.sysid == uasId)
{ {
QString uasState; // QString uasState;
QString stateDescription; // QString stateDescription;
QString patternPath; // QString patternPath;
switch (message.msgid) switch (message.msgid)
{ {
case MAVLINK_MSG_ID_RAW_AUX: case MAVLINK_MSG_ID_RAW_AUX:
...@@ -155,22 +155,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -155,22 +155,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow()); emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
} }
break; break;
case MAVLINK_MSG_ID_CONTROL_STATUS:
{
mavlink_control_status_t status;
mavlink_msg_control_status_decode(&message, &status);
// Emit control status vector
emit attitudeControlEnabled(static_cast<bool>(status.control_att));
emit positionXYControlEnabled(static_cast<bool>(status.control_pos_xy));
emit positionZControlEnabled(static_cast<bool>(status.control_pos_z));
emit positionYawControlEnabled(static_cast<bool>(status.control_pos_yaw));
// Emit localization status vector
emit localizationChanged(this, status.position_fix);
emit visionLocalizationChanged(this, status.vision_fix);
emit gpsLocalizationChanged(this, status.gps_fix);
}
break;
default: default:
// Do nothing // Do nothing
break; break;
......
...@@ -349,6 +349,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -349,6 +349,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
} }
break; break;
case MAVLINK_MSG_ID_CONTROL_STATUS:
{
mavlink_control_status_t status;
mavlink_msg_control_status_decode(&message, &status);
// Emit control status vector
emit attitudeControlEnabled(static_cast<bool>(status.control_att));
emit positionXYControlEnabled(static_cast<bool>(status.control_pos_xy));
emit positionZControlEnabled(static_cast<bool>(status.control_pos_z));
emit positionYawControlEnabled(static_cast<bool>(status.control_pos_yaw));
// Emit localization status vector
emit localizationChanged(this, status.position_fix);
emit visionLocalizationChanged(this, status.vision_fix);
emit gpsLocalizationChanged(this, status.gps_fix);
}
break;
case MAVLINK_MSG_ID_RAW_IMU: case MAVLINK_MSG_ID_RAW_IMU:
{ {
mavlink_raw_imu_t raw; mavlink_raw_imu_t raw;
...@@ -480,6 +496,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -480,6 +496,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time); emit valueChanged(uasId, "gps z speed", "m/s", speedZ, time);
emit globalPositionChanged(this, longitude, latitude, altitude, time); emit globalPositionChanged(this, longitude, latitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time); emit speedChanged(this, speedX, speedY, speedZ, time);
emit valueChanged(uasId, "gpsspeed", "m/s", sqrt(speedX*speedX+speedY*speedY+speedZ*speedZ), time);
// Set internal state // Set internal state
if (!positionLock) if (!positionLock)
{ {
...@@ -506,15 +523,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -506,15 +523,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "latitude", "deg", pos.lat, time); emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
emit valueChanged(uasId, "longitude", "deg", pos.lon, time); emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
// FIXME REMOVE
longitude = pos.lon;
latitude = pos.lat;
altitude = pos.alt;
emit globalPositionChanged(this, longitude, latitude, altitude, time);
if (pos.fix_type > 0) if (pos.fix_type > 0)
{ {
emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time); emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
emit valueChanged(uasId, "gpsspeed", "m/s", pos.v, time);
// Check for NaN // Check for NaN
int alt = pos.alt; int alt = pos.alt;
...@@ -560,9 +572,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -560,9 +572,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_raw_pressure_t pressure; mavlink_raw_pressure_t pressure;
mavlink_msg_raw_pressure_decode(&message, &pressure); mavlink_msg_raw_pressure_decode(&message, &pressure);
quint64 time = this->getUnixTime(0); quint64 time = this->getUnixTime(0);
emit valueChanged(uasId, "abs pressure", "hP", pressure.press_abs, time); emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
emit valueChanged(uasId, "diff pressure 1", "hP", pressure.press_diff1, time); emit valueChanged(uasId, "diff pressure 1", "hPa", pressure.press_diff1, time);
emit valueChanged(uasId, "diff pressure 2", "hP", pressure.press_diff2, time); emit valueChanged(uasId, "diff pressure 2", "hPa", pressure.press_diff2, time);
} }
break; break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW: case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
...@@ -1017,7 +1029,7 @@ void UAS::forwardMessage(mavlink_message_t message) ...@@ -1017,7 +1029,7 @@ void UAS::forwardMessage(mavlink_message_t message)
{ {
if(serial != links->at(i)) if(serial != links->at(i))
{ {
qDebug()<<"Forwarding Over link: "<<serial->getName()<<" "<<serial; qDebug()<<"Antenna tracking: Forwarding Over link: "<<serial->getName()<<" "<<serial;
sendMessage(serial, message); sendMessage(serial, message);
} }
} }
......
This diff is collapsed.
...@@ -248,6 +248,8 @@ protected: ...@@ -248,6 +248,8 @@ protected:
// Data indicators // Data indicators
bool setPointKnown; ///< Controller setpoint known status flag bool setPointKnown; ///< Controller setpoint known status flag
bool positionSetPointKnown; ///< Position setpoint known status flag
bool userSetPointSet;
private: private:
}; };
......
...@@ -210,6 +210,8 @@ void MainWindow::setDefaultSettingsForAp() ...@@ -210,6 +210,8 @@ void MainWindow::setDefaultSettingsForAp()
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_UAS_LIST,VIEW_OPERATOR), true); settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_UAS_LIST,VIEW_OPERATOR), true);
// ENABLE HUD TOOL WIDGET // ENABLE HUD TOOL WIDGET
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_HUD,VIEW_OPERATOR), true); settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_HUD,VIEW_OPERATOR), true);
// ENABLE WAYPOINTS
settings.setValue(buildMenuKey(SUB_SECTION_CHECKED,MainWindow::MENU_WAYPOINTS,VIEW_OPERATOR), true);
} }
// ENGINEER VIEW DEFAULT // ENGINEER VIEW DEFAULT
...@@ -399,15 +401,19 @@ void MainWindow::buildPxWidgets() ...@@ -399,15 +401,19 @@ void MainWindow::buildPxWidgets()
acceptList->append("-105,pitch,deg,+105,s"); acceptList->append("-105,pitch,deg,+105,s");
acceptList->append("-105,yaw,deg,+105,s"); acceptList->append("-105,yaw,deg,+105,s");
acceptList->append("-260,rollspeed,deg/s,+260,s"); acceptList->append("-60,rollspeed,deg/s,+60,s");
acceptList->append("-260,pitchspeed,deg/s,+260,s"); acceptList->append("-60,pitchspeed,deg/s,+60,s");
acceptList->append("-260,yawspeed,deg/s,+260,s"); acceptList->append("-60,yawspeed,deg/s,+60,s");
acceptList->append("0,airspeed,m/s,30");
acceptList->append("0,gpsspeed,m/s,30");
acceptList->append("0,truespeed,m/s,30");
//FIXME: memory of acceptList2 will never be freed again //FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList(); QStringList* acceptList2 = new QStringList();
acceptList2->append("0,abs pressure,hPa,65500"); acceptList2->append("0,abs pressure,hPa,65500");
acceptList2->append("-999,accel. X,raw,999,s"); acceptList2->append("-2048,accel. x,raw,2048,s");
acceptList2->append("-999,accel. Y,raw,999,s"); acceptList2->append("-2048,accel. y,raw,2048,s");
acceptList2->append("-2048,accel. z,raw,2048,s");
if (!linechartWidget) if (!linechartWidget)
{ {
......
...@@ -157,12 +157,18 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -157,12 +157,18 @@ MapWidget::MapWidget(QWidget *parent) :
zoomout->setStyleSheet(buttonStyle); zoomout->setStyleSheet(buttonStyle);
createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this); createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this);
createPath->setStyleSheet(buttonStyle); createPath->setStyleSheet(buttonStyle);
createPath->setToolTip(tr("Start / end waypoint add mode"));
createPath->setStatusTip(tr("Start / end waypoint add mode"));
// clearTracking = new QPushButton(QIcon(""), "", this); // clearTracking = new QPushButton(QIcon(""), "", this);
// clearTracking->setStyleSheet(buttonStyle); // clearTracking->setStyleSheet(buttonStyle);
followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this); followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this);
followgps->setStyleSheet(buttonStyle); followgps->setStyleSheet(buttonStyle);
followgps->setToolTip(tr("Follow the position of the current MAV with the map center"));
followgps->setStatusTip(tr("Follow the position of the current MAV with the map center"));
QPushButton* goToButton = new QPushButton(QIcon(""), "T", this); QPushButton* goToButton = new QPushButton(QIcon(""), "T", this);
goToButton->setStyleSheet(buttonStyle); goToButton->setStyleSheet(buttonStyle);
goToButton->setToolTip(tr("Enter a latitude/longitude position to move the map to"));
goToButton->setStatusTip(tr("Enter a latitude/longitude position to move the map to"));
zoomin->setMaximumWidth(30); zoomin->setMaximumWidth(30);
zoomout->setMaximumWidth(30); zoomout->setMaximumWidth(30);
......
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