Commit 33d5b9f1 authored by Thomas Gubler's avatar Thomas Gubler

Merge pull request #974 from mavlink/offboard_mode

Offboard mode
parents 356369eb e03bd3f4
#ifndef PX4_CUSTOM_MODE_H
#define PX4_CUSTOM_MODE_H
/*
* px4_custom_mode.h
*
* Created on: 09.08.2013
* Author: ton
*/
#ifndef PX4_CUSTOM_MODE_H_
#define PX4_CUSTOM_MODE_H_
#include <stdint.h>
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
PX4_CUSTOM_MAIN_MODE_ALTCTL,
PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
PX4_CUSTOM_MAIN_MODE_ALTCTL,
PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_MAIN_MODE_ACRO,
PX4_CUSTOM_MAIN_MODE_OFFBOARD,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
PX4_CUSTOM_SUB_MODE_AUTO_RTL,
PX4_CUSTOM_SUB_MODE_AUTO_LAND,
PX4_CUSTOM_SUB_MODE_AUTO_READY = 1,
PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF,
PX4_CUSTOM_SUB_MODE_AUTO_LOITER,
PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
PX4_CUSTOM_SUB_MODE_AUTO_RTL,
PX4_CUSTOM_SUB_MODE_AUTO_LAND,
PX4_CUSTOM_SUB_MODE_AUTO_RTGS
};
union px4_custom_mode {
struct {
uint16_t reserved;
uint8_t main_mode;
uint8_t sub_mode;
};
uint32_t data;
float data_float;
struct {
uint16_t reserved;
uint8_t main_mode;
uint8_t sub_mode;
};
uint32_t data;
float data_float;
};
#endif // PX4_CUSTOM_MODE_H
#endif /* PX4_CUSTOM_MODE_H_ */
......@@ -2905,7 +2905,7 @@ bool UAS::emergencyKILL()
void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration)
{
Q_UNUSED(configuration);
QGCFlightGearLink* link = dynamic_cast<QGCFlightGearLink*>(simulation);
if (!link || !simulation) {
// Delete wrong sim
......@@ -3115,7 +3115,7 @@ void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, floa
float flow_comp_m_y, quint8 quality, float ground_distance)
{
// FIXME: This needs to be updated for new mavlink_msg_hil_optical_flow_pack api
Q_UNUSED(time_us);
Q_UNUSED(flow_x);
Q_UNUSED(flow_y);
......@@ -3123,14 +3123,14 @@ void UAS::sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, floa
Q_UNUSED(flow_comp_m_y);
Q_UNUSED(quality);
Q_UNUSED(ground_distance);
if (this->base_mode & MAV_MODE_FLAG_HIL_ENABLED)
{
#if 0
mavlink_message_t msg;
mavlink_msg_hil_optical_flow_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg,
time_us, 0, 0 /* hack */, flow_x, flow_y, 0.0f /* hack */, 0.0f /* hack */, 0.0f /* hack */, 0 /* hack */, quality, ground_distance);
sendMessage(msg);
lastSendTimeOpticalFlow = QGC::groundTimeMilliseconds();
#endif
......@@ -3354,6 +3354,8 @@ QString UAS::getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode, int au
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LAND) {
mode += "|LAND";
}
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) {
mode += "|OFFBOARD";
}
}
}
......
......@@ -52,7 +52,7 @@ static struct full_mode_s modes_list_common[] = {
0 },
};
static struct full_mode_s modes_list_px4[4];
static struct full_mode_s modes_list_px4[5];
UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent),
uasID(-1),
......@@ -88,6 +88,9 @@ void UASControlWidget::updateModesList()
modes_list_px4[3].baseMode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
modes_list_px4[3].customMode = px4_cm.data;
modes_list_px4[4].baseMode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
px4_cm.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD;
modes_list_px4[4].customMode = px4_cm.data;
// Detect autopilot type
int autopilot = 0;
......
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