Commit 9cb538d6 authored by pixhawk's avatar pixhawk

Merge branch 'v10release' of git://github.com/pixhawk/qgroundcontrol into v10release

parents 61098eba 994aa292
......@@ -201,14 +201,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// If the matching UAS object does not yet exist, it has to be created
// before emitting the packetReceived signal
// BIG NASTY HACK
//TODO
//BUG
//BAD
//FIXME
if (message.sysid == 35)
message.sysid = 42;
UASInterface* uas = UASManager::instance()->getUASForId(message.sysid);
// Check and (if necessary) create UAS object
......
......@@ -555,7 +555,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_param_value_t value;
mavlink_msg_param_value_decode(&message, &value);
QByteArray bytes((char*)value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QByteArray bytes(value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QString parameterName = QString(bytes);
int component = message.compid;
mavlink_param_union_t val;
......@@ -890,7 +890,19 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
case MAVLINK_MSG_ID_OPTICAL_FLOW:
break;
case MAVLINK_MSG_ID_DEBUG_VECT:
{
mavlink_debug_vect_t debug;
mavlink_msg_debug_vect_decode(&message, &debug);
debug.name[MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN-1] = '\0';
QString name(debug.name);
quint64 time = getUnixTime(debug.time_usec);
emit valueChanged(uasId, name+".x", "raw", debug.x, time);
emit valueChanged(uasId, name+".y", "raw", debug.y, time);
emit valueChanged(uasId, name+".z", "raw", debug.z, time);
}
break;
case MAVLINK_MSG_ID_DEBUG:
break;
default:
......@@ -1952,36 +1964,30 @@ void UAS::receiveButton(int buttonIndex)
void UAS::halt()
{
// FIXME MAVLINKV10PORTINGNEEDED
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_HALT);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_HOLD, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
sendMessage(msg);
}
void UAS::go()
{
// FIXME MAVLINKV10PORTINGNEEDED
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_CONTINUE);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, 0, 0, 0, 0, 0);
sendMessage(msg);
}
/** Order the robot to return home / to land on the runway **/
void UAS::home()
{
// FIXME MAVLINKV10PORTINGNEEDED
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_RETURN);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
mavlink_message_t msg;
double latitude = UASManager::instance()->getHomeLatitude();
double longitude = UASManager::instance()->getHomeLongitude();
double altitude = UASManager::instance()->getHomeAltitude();
int frame = UASManager::instance()->getHomeFrame();
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_OVERRIDE_GOTO, 1, MAV_GOTO_DO_CONTINUE, MAV_GOTO_HOLD_AT_CURRENT_POSITION, frame, 0, latitude, longitude, altitude);
sendMessage(msg);
}
/**
......@@ -1990,13 +1996,8 @@ void UAS::home()
*/
void UAS::emergencySTOP()
{
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// // FIXME MAVLINKV10PORTINGNEEDED
// //mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU, (int)MAV_ACTION_EMCY_LAND);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
// FIXME MAVLINKV10PORTINGNEEDED
halt();
}
/**
......@@ -2007,6 +2008,7 @@ void UAS::emergencySTOP()
*/
bool UAS::emergencyKILL()
{
halt();
// FIXME MAVLINKV10PORTINGNEEDED
// bool result = false;
// QMessageBox msgBox;
......@@ -2096,41 +2098,33 @@ void UAS::stopHil()
void UAS::shutdown()
{
// FIXME MAVLINKV10PORTINGNEEDED
// bool result = false;
// QMessageBox msgBox;
// msgBox.setIcon(QMessageBox::Critical);
// msgBox.setText("Shutting down the UAS");
// msgBox.setInformativeText("Do you want to shut down the onboard computer?");
// msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
// msgBox.setDefaultButton(QMessageBox::Cancel);
// int ret = msgBox.exec();
bool result = false;
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Shutting down the UAS");
msgBox.setInformativeText("Do you want to shut down the onboard computer?");
// // Close the message box shortly after the click to prevent accidental clicks
// QTimer::singleShot(5000, &msgBox, SLOT(reject()));
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel);
msgBox.setDefaultButton(QMessageBox::Cancel);
int ret = msgBox.exec();
// if (ret == QMessageBox::Yes)
// {
// // If the active UAS is set, execute command
// mavlink_message_t msg;
// // TODO Replace MG System ID with static function call and allow to change ID in GUI
// mavlink_msg_action_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, this->getUASID(), MAV_COMP_ID_IMU,(int)MAV_ACTION_SHUTDOWN);
// // Send message twice to increase chance of reception
// sendMessage(msg);
// sendMessage(msg);
// Close the message box shortly after the click to prevent accidental clicks
QTimer::singleShot(5000, &msgBox, SLOT(reject()));
// result = true;
// }
if (ret == QMessageBox::Yes)
{
// If the active UAS is set, execute command
mavlink_message_t msg;
mavlink_msg_command_short_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0, 2, 0, 0, 0);
sendMessage(msg);
result = true;
}
}
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
mavlink_message_t msg;
mavlink_msg_set_local_position_setpoint_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_FRAME_LOCAL_NED, x, y, z, yaw);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
......
......@@ -214,7 +214,8 @@ UASManager::UASManager() :
activeUAS(NULL),
homeLat(47.3769),
homeLon(8.549444),
homeAlt(470.0)
homeAlt(470.0),
homeFrame(MAV_FRAME_GLOBAL)
{
loadSettings();
setLocalNEDSafetyBorders(1, -1, 0, -1, 1, -1);
......
......@@ -84,6 +84,12 @@ public:
return homeAlt;
}
/** @brief Get the home position coordinate frame */
int getHomeFrame() const
{
return homeFrame;
}
/** @brief Convert WGS84 coordinates to earth centric frame */
Eigen::Vector3d wgs84ToEcef(const double & latitude, const double & longitude, const double & altitude);
/** @brief Convert earth centric frame to EAST-NORTH-UP frame (x-y-z directions */
......@@ -238,6 +244,7 @@ protected:
double homeLat;
double homeLon;
double homeAlt;
int homeFrame;
Eigen::Quaterniond ecef_ref_orientation_;
Eigen::Vector3d ecef_ref_point_;
Eigen::Vector3d nedSafetyLimitPosition1;
......
......@@ -20,6 +20,8 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
messageFilter.insert(MAVLINK_MSG_ID_MISSION_ITEM, false);
messageFilter.insert(MAVLINK_MSG_ID_MISSION_COUNT, false);
messageFilter.insert(MAVLINK_MSG_ID_MISSION_ACK, false);
messageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, false);
messageFilter.insert(MAVLINK_MSG_ID_NAMED_VALUE_INT, false);
textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG, false);
textMessageFilter.insert(MAVLINK_MSG_ID_DEBUG_VECT, false);
......
......@@ -616,8 +616,6 @@ void QGCParamWidget::requestParameterList()
// Request twice as mean of forward error correction
mav->requestParameters();
QGC::SLEEP::msleep(15);
mav->requestParameters();
}
void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column)
......
......@@ -77,21 +77,26 @@ QGCRemoteControlView::~QGCRemoteControlView()
void QGCRemoteControlView::setUASId(int id)
{
// Clear channel count
raw.clear();
normalized.clear();
if (uasId != -1) {
UASInterface* uas = UASManager::instance()->getUASForId(id);
if (uas) {
if (uasId != -1)
{
UASInterface* uas = UASManager::instance()->getUASForId(uasId);
if (uas)
{
// The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannel(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
}
}
// Clear channel count
raw.clear();
raw.resize(0);
normalized.clear();
normalized.resize(0);
foreach (QLabel* label, rawLabels)
{
label->deleteLater();
......@@ -103,11 +108,14 @@ void QGCRemoteControlView::setUASId(int id)
}
rawLabels.clear();
rawLabels.resize(0);
progressBars.clear();
progressBars.resize(0);
// Connect the new UAS
UASInterface* newUAS = UASManager::instance()->getUASForId(id);
if (newUAS) {
if (newUAS)
{
// New UAS exists, connect
nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName()));
calibrationWindow->setUASId(id);
......@@ -140,11 +148,10 @@ void QGCRemoteControlView::setChannelRaw(int channelId, float raw)
void QGCRemoteControlView::setChannelScaled(int channelId, float normalized)
{
if (this->raw.size() <= channelId) // using raw vector as size indicator
if (this->normalized.size() <= channelId) // using raw vector as size indicator
{
// This is a new channel, append it
this->normalized.append(normalized);
this->raw.append(0);
appendChannelWidget(channelId);
updated = true;
}
......
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