Commit 0ccecde8 authored by Lorenz Meier's avatar Lorenz Meier

Better defaults for Takeoff pitch and better visual indication

parent b61b0601
......@@ -191,6 +191,16 @@ void Waypoint::setAction(MAV_CMD action)
{
if (this->action != action) {
this->action = action;
// Flick defaults according to WP type
switch (this->action) {
case MAV_CMD_NAV_TAKEOFF:
// We default to 15 degrees minimum takeoff pitch
this->param1 = 15.0;
break;
}
emit changed(this);
}
}
......
......@@ -32,7 +32,16 @@
<property name="spacing">
<number>5</number>
</property>
<property name="margin">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
......@@ -296,7 +305,7 @@
<bool>false</bool>
</property>
<property name="prefix">
<string/>
<string>heading </string>
</property>
<property name="suffix">
<string>°</string>
......@@ -329,6 +338,9 @@
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>min. pitch </string>
</property>
<property name="suffix">
<string>°</string>
</property>
......
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