Commit 2453de9e authored by Don Gagne's avatar Don Gagne

Default acceptance radius to 0

It is also no longer a user visible field
parent 4c863206
......@@ -35,12 +35,6 @@
"units": "seconds",
"default": 0,
"decimalPlaces": 0
},
"param2": {
"label": "Accept radius:",
"units": "meters",
"default": 3.0,
"decimalPlaces": 2
}
},
{
......
......@@ -821,6 +821,12 @@ void MissionItem::setDefaultsForCommand(void)
}
}
if (command == MAV_CMD_NAV_WAYPOINT) {
// We default all acceptance radius to 0. This allows flight controller to be in control of
// accept radius.
setParam2(0);
}
setAutoContinue(true);
setFrame(specifiesCoordinate() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_MISSION);
setRawEdit(false);
......
......@@ -38,7 +38,6 @@ const MissionItemTest::ItemInfo_t MissionItemTest::_rgItemInfo[] = {
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesWaypoint[] = {
{ "Altitude:", 70.1234567 },
{ "Hold:", 10.1234567 },
{ "Accept radius:", 20.1234567 },
};
const MissionItemTest::FactValue_t MissionItemTest::_rgFactValuesLoiterUnlim[] = {
......@@ -189,6 +188,5 @@ void MissionItemTest::_testDefaultValues(void)
item.setCommand(MAV_CMD_NAV_WAYPOINT);
item.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
QCOMPARE(item.param2(), 3.0);
QCOMPARE(item.param7(), MissionItem::defaultAltitude);
}
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