Skip to content

Commit b396503

Browse files
author
jonas
committed
skip do_jumps in rtl fast and rtl fast reverse
1 parent f45bc71 commit b396503

File tree

11 files changed

+197
-27
lines changed

11 files changed

+197
-27
lines changed

docs/en/flight_modes/return.md

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -110,11 +110,13 @@ The behaviour is fairly complex because it depends on the flight mode, and wheth
110110

111111
Mission _with_ landing pattern:
112112

113-
- **Mission mode:** Mission is continued in "fast-forward mode" (jumps, delay and any other non-position commands ignored, loiter and other position waypoints converted to simple waypoints) and then lands.
113+
- **Mission mode:**
114+
- Mission is continued in "fast-forward mode" and then lands.
115+
- DO_JUMP commands, delays and other non-position mission items are ignored, and loiter and other position waypoints are converted to simple waypoints.
114116
- **Auto mode other than mission mode:**
115117
- Ascend to a safe [minimum return altitude](#minimum-return-altitude) above any expected obstacles.
116118
- Fly directly to closest waypoint (for FW not a landing WP) and descend to waypoint altitude.
117-
- Continue mission in fast forward mode from that waypoint.
119+
- Continue mission in fast forward mode from that waypoint, using the same traversal rules as above.
118120
- **Manual modes:**
119121
- Ascend to a safe [minimum return altitude](#minimum-return-altitude) above any expected obstacles.
120122
- Fly directly to landing sequence position and descend to waypoint altitude
@@ -137,6 +139,11 @@ If no mission is defined PX4 will fly directly to home location and land (rally
137139

138140
If the mission changes during return mode, then the behaviour is re-evaluated based on the new mission following the same rules as above (e.g. if the new mission has no landing sequence and you're in a mission, the mission is reversed).
139141

142+
::: info
143+
For `RTL_TYPE=4`, PX4 currently chooses between continuing to a mission landing and reversing toward home by comparing raw mission item indices.
144+
This is only an approximation of the flown path length, because the number if mission items is not indicative of the distance remaining and non-position items are also counted.
145+
:::
146+
140147
### Closest Safe Destination Return Type (RTL_TYPE=3)
141148

142149
In this return type the vehicle:
@@ -208,7 +215,7 @@ The RTL parameters are listed in [Parameter Reference > Return Mode](../advanced
208215

209216
| Parameter | Description |
210217
| ----------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
211-
| <a id="RTL_TYPE"></a>[RTL_TYPE](../advanced_config/parameter_reference.md#RTL_TYPE) | Return mechanism (path and destination).<br>`0`: Return to a rally point or home (whichever is closest) via direct path.<br>`1`: Return to a rally point or the mission landing pattern start point (whichever is closest), via direct path. If neither mission landing or rally points are defined return home via a direct path. If the destination is a mission landing pattern, follow the pattern to land.<br>`2`: Use mission path fast-forward to landing if a landing pattern is defined, otherwise fast-reverse to home while skipping DO_JUMP and other non-position mission items. Ignore rally points. Fly direct to home if no mission plan is defined.<br>`3`: Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. |
218+
| <a id="RTL_TYPE"></a>[RTL_TYPE](../advanced_config/parameter_reference.md#RTL_TYPE) | Return mechanism (path and destination).<br>`0`: Return to a rally point or home (whichever is closest) via direct path.<br>`1`: Return to a rally point or the mission landing pattern start point (whichever is closest), via direct path. If neither mission landing or rally points are defined return home via a direct path. If the destination is a mission landing pattern, follow the pattern to land.<br>`2`: Use the mission path to landing while skipping DO_JUMP and other non-position mission items if a landing pattern is defined, otherwise fast-reverse to home with the same traversal rules. Ignore rally points. Fly direct to home if no mission plan is defined.<br>`3`: Return via direct path to closest destination: home, start of mission landing pattern or safe point. If the destination is a mission landing pattern, follow the pattern to land. |
212219
| <a id="RTL_RETURN_ALT"></a>[RTL_RETURN_ALT](../advanced_config/parameter_reference.md#RTL_RETURN_ALT) | Return altitude in meters (default: 60m) when [RTL_CONE_ANG](../advanced_config/parameter_reference.md#RTL_CONE_ANG) is 0. If already above this value the vehicle will return at its current altitude. |
213220
| <a id="RTL_DESCEND_ALT"></a>[RTL_DESCEND_ALT](../advanced_config/parameter_reference.md#RTL_DESCEND_ALT) | Minimum return altitude and altitude at which the vehicle will slow or stop its initial descent from a higher return altitude (default: 30m) |
214221
| <a id="RTL_LAND_DELAY"></a>[RTL_LAND_DELAY](../advanced_config/parameter_reference.md#RTL_LAND_DELAY) | Time to wait at `RTL_DESCEND_ALT` before landing (default: 0.5s) -by default this period is short so that the vehicle will simply slow and then land immediately. If set to -1 the system will loiter at `RTL_DESCEND_ALT` rather than landing. The delay is provided to allow you to configure time for landing gear to be deployed (triggered automatically). |

src/modules/navigator/mission.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ Mission::set_current_mission_index(uint16_t index)
130130

131131
bool Mission::setNextMissionItem()
132132
{
133-
return (goToNextItem(MissionTraversalType::FollowMissionControlFlow) == PX4_OK);
133+
return (goToNextItem() == PX4_OK);
134134
}
135135

136136
bool

src/modules/navigator/mission_base.cpp

Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1122,6 +1122,12 @@ bool MissionBase::loadTraversalItem(int32_t &mission_index, mission_item_s &miss
11221122
return loadMissionItemFromCache(mission_index, mission_item);
11231123
}
11241124

1125+
void MissionBase::getPreviousPositionItems(int32_t start_index, int32_t items_index[],
1126+
size_t &num_found_items, uint8_t max_num_items)
1127+
{
1128+
getPreviousPositionItems(start_index, items_index, num_found_items, max_num_items, traversalType());
1129+
}
1130+
11251131
void MissionBase::getPreviousPositionItems(int32_t start_index, int32_t items_index[],
11261132
size_t &num_found_items, uint8_t max_num_items, MissionTraversalType traversal_type)
11271133
{
@@ -1147,6 +1153,12 @@ void MissionBase::getPreviousPositionItems(int32_t start_index, int32_t items_in
11471153
}
11481154
}
11491155

1156+
void MissionBase::getNextPositionItems(int32_t start_index, int32_t items_index[],
1157+
size_t &num_found_items, uint8_t max_num_items)
1158+
{
1159+
getNextPositionItems(start_index, items_index, num_found_items, max_num_items, traversalType());
1160+
}
1161+
11501162
void MissionBase::getNextPositionItems(int32_t start_index, int32_t items_index[],
11511163
size_t &num_found_items, uint8_t max_num_items,
11521164
MissionTraversalType traversal_type)
@@ -1174,6 +1186,11 @@ void MissionBase::getNextPositionItems(int32_t start_index, int32_t items_index[
11741186
}
11751187
}
11761188

1189+
int MissionBase::goToNextItem()
1190+
{
1191+
return goToNextItem(traversalType());
1192+
}
1193+
11771194
int MissionBase::goToNextItem(MissionTraversalType traversal_type)
11781195
{
11791196
if (_mission.current_seq + 1 >= (_mission.count)) {
@@ -1183,6 +1200,11 @@ int MissionBase::goToNextItem(MissionTraversalType traversal_type)
11831200
return goToItem(_mission.current_seq + 1, traversal_type);
11841201
}
11851202

1203+
int MissionBase::goToPreviousItem()
1204+
{
1205+
return goToPreviousItem(traversalType());
1206+
}
1207+
11861208
int MissionBase::goToPreviousItem(MissionTraversalType traversal_type)
11871209
{
11881210
if (_mission.current_seq <= 0) {
@@ -1192,6 +1214,11 @@ int MissionBase::goToPreviousItem(MissionTraversalType traversal_type)
11921214
return goToItem(_mission.current_seq - 1, traversal_type, true);
11931215
}
11941216

1217+
int MissionBase::goToPreviousPositionItem()
1218+
{
1219+
return goToPreviousPositionItem(traversalType());
1220+
}
1221+
11951222
int MissionBase::goToPreviousPositionItem(MissionTraversalType traversal_type)
11961223
{
11971224
int32_t previous_position_item_index{-1};
@@ -1205,6 +1232,11 @@ int MissionBase::goToPreviousPositionItem(MissionTraversalType traversal_type)
12051232
}
12061233
}
12071234

1235+
int MissionBase::goToNextPositionItem()
1236+
{
1237+
return goToNextPositionItem(traversalType());
1238+
}
1239+
12081240
int MissionBase::goToNextPositionItem(MissionTraversalType traversal_type)
12091241
{
12101242
int32_t next_position_item_index{-1};

src/modules/navigator/mission_base.h

Lines changed: 76 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,20 @@ class MissionBase : public MissionBlock, public ModuleParams
105105
};
106106

107107
/**
108-
* @brief Get the previous mission position items.
108+
* @brief Get the previous mission position items using this mode's traversal policy.
109+
*
110+
* Convenience overload for callers that want the navigation mode default. Keep the
111+
* explicit traversal overload below for cases that intentionally need different semantics.
112+
*
113+
* @param[in] start_index Index from which to start searching backward
114+
* @param[out] items_index Array of the previous position item indices
115+
* @param[out] num_found_items Number of position items found
116+
* @param[in] max_num_items Maximum number of position items to collect
117+
*/
118+
void getPreviousPositionItems(int32_t start_index, int32_t items_index[], size_t &num_found_items,
119+
uint8_t max_num_items);
120+
/**
121+
* @brief Get the previous mission position items using an explicit traversal policy.
109122
*
110123
* @param[in] start_index Index from which to start searching backward
111124
* @param[out] items_index Array of the previous position item indices
@@ -115,9 +128,19 @@ class MissionBase : public MissionBlock, public ModuleParams
115128
*/
116129
void getPreviousPositionItems(int32_t start_index, int32_t items_index[], size_t &num_found_items,
117130
uint8_t max_num_items,
118-
MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
131+
MissionTraversalType traversal_type);
132+
/**
133+
* @brief Get the next mission item containing a position setpoint using this mode's traversal policy.
134+
*
135+
* @param[in] start_index Index from which to start searching forward
136+
* @param[out] items_index Array of the next position item indices
137+
* @param[out] num_found_items Number of position items found
138+
* @param[in] max_num_items Maximum number of position items to collect
139+
*/
140+
void getNextPositionItems(int32_t start_index, int32_t items_index[], size_t &num_found_items,
141+
uint8_t max_num_items);
119142
/**
120-
* @brief Get the next mission item containing a position setpoint.
143+
* @brief Get the next mission item containing a position setpoint using an explicit traversal policy.
121144
*
122145
* @param[in] start_index Index from which to start searching forward
123146
* @param[out] items_index Array of the next position item indices
@@ -127,7 +150,7 @@ class MissionBase : public MissionBlock, public ModuleParams
127150
*/
128151
void getNextPositionItems(int32_t start_index, int32_t items_index[], size_t &num_found_items,
129152
uint8_t max_num_items,
130-
MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
153+
MissionTraversalType traversal_type);
131154
/**
132155
* @brief Mission has a land start, a land, and is valid
133156
*
@@ -136,20 +159,35 @@ class MissionBase : public MissionBlock, public ModuleParams
136159
*/
137160
bool hasMissionLandStart() const { return _mission.land_start_index >= 0 && _mission.land_index >= 0 && isMissionValid();};
138161
/**
139-
* @brief Go to next Mission Item
162+
* @brief Go to next Mission Item using this mode's traversal policy.
163+
* Go to next non jump mission item
164+
*
165+
* @return PX4_OK if next mission item exists, PX4_ERR otherwise
166+
*/
167+
int goToNextItem();
168+
/**
169+
* @brief Go to next Mission Item using an explicit traversal policy.
140170
* Go to next non jump mission item
141171
*
142172
* @param[in] traversal_type Whether to follow DO_JUMP mission control flow or ignore DO_JUMP items
143173
* @return PX4_OK if next mission item exists, PX4_ERR otherwise
144174
*/
145-
int goToNextItem(MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
175+
int goToNextItem(MissionTraversalType traversal_type);
176+
/**
177+
* @brief Go to previous Mission Item using this mode's traversal policy.
178+
* Go to previous non jump mission item
179+
*
180+
* @return PX4_OK if previous mission item exists, PX4_ERR otherwise
181+
*/
182+
int goToPreviousItem();
146183
/**
147-
* @brief Go to previous Mission Item
184+
* @brief Go to previous Mission Item using an explicit traversal policy.
148185
* Go to previous non jump mission item
186+
*
149187
* @param[in] traversal_type Whether to follow DO_JUMP mission control flow or ignore DO_JUMP items
150188
* @return PX4_OK if previous mission item exists, PX4_ERR otherwise
151189
*/
152-
int goToPreviousItem(MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
190+
int goToPreviousItem(MissionTraversalType traversal_type);
153191
/**
154192
* @brief Go to Mission Item
155193
*
@@ -161,19 +199,31 @@ class MissionBase : public MissionBlock, public ModuleParams
161199
int goToItem(int32_t index, MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow,
162200
bool mission_direction_backward = false);
163201
/**
164-
* @brief Go To Previous Mission Position Item
202+
* @brief Go To Previous Mission Position Item using this mode's traversal policy.
203+
*
204+
* @return PX4_OK if previous mission item exists, PX4_ERR otherwise
205+
*/
206+
int goToPreviousPositionItem();
207+
/**
208+
* @brief Go To Previous Mission Position Item using an explicit traversal policy.
165209
*
166210
* @param[in] traversal_type Whether to follow DO_JUMP mission control flow or ignore DO_JUMP items
167211
* @return PX4_OK if previous mission item exists, PX4_ERR otherwise
168212
*/
169-
int goToPreviousPositionItem(MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
213+
int goToPreviousPositionItem(MissionTraversalType traversal_type);
214+
/**
215+
* @brief Go To Next Mission Position Item using this mode's traversal policy.
216+
*
217+
* @return PX4_OK if next mission item exists, PX4_ERR otherwise
218+
*/
219+
int goToNextPositionItem();
170220
/**
171-
* @brief Go To Next Mission Position Item
221+
* @brief Go To Next Mission Position Item using an explicit traversal policy.
172222
*
173223
* @param[in] traversal_type Whether to follow DO_JUMP mission control flow or ignore DO_JUMP items
174224
* @return PX4_OK if next mission item exists, PX4_ERR otherwise
175225
*/
176-
int goToNextPositionItem(MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
226+
int goToNextPositionItem(MissionTraversalType traversal_type);
177227
/**
178228
* @brief Go to Mission Land Start Item
179229
*
@@ -326,6 +376,18 @@ class MissionBase : public MissionBlock, public ModuleParams
326376
*/
327377
bool position_setpoint_equal(const position_setpoint_s *p1, const position_setpoint_s *p2) const;
328378

379+
/**
380+
* @brief Traversal mode used by this navigation mode when walking position items.
381+
*
382+
* Mission mode follows active DO_JUMP control flow by default. Derived modes such as
383+
* mission-based RTL can override this to walk the geometric mission path instead.
384+
* Traversal helpers use this policy unless the caller explicitly overrides it.
385+
*/
386+
virtual MissionTraversalType traversalType() const
387+
{
388+
return MissionTraversalType::FollowMissionControlFlow;
389+
}
390+
329391
/**
330392
* @brief Set the Mission Index
331393
*
@@ -353,7 +415,7 @@ class MissionBase : public MissionBlock, public ModuleParams
353415
* @return true if a position item was found
354416
*/
355417
bool findNextPositionIndex(int32_t start_index, int32_t &next_index,
356-
MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
418+
MissionTraversalType traversal_type);
357419

358420
/**
359421
* @brief Find the previous position mission item.
@@ -366,7 +428,7 @@ class MissionBase : public MissionBlock, public ModuleParams
366428
* @return true if a position item was found
367429
*/
368430
bool findPreviousPositionIndex(int32_t start_index, int32_t &previous_index,
369-
MissionTraversalType traversal_type = MissionTraversalType::FollowMissionControlFlow);
431+
MissionTraversalType traversal_type);
370432

371433
bool _is_current_planned_mission_item_valid{false}; /**< Flag indicating if the currently loaded mission item is valid*/
372434
bool _mission_has_been_activated{false}; /**< Flag indicating if the mission has been activated*/

src/modules/navigator/rtl_direct_mission_land.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,7 @@ void RtlDirectMissionLand::on_activation()
115115

116116
bool RtlDirectMissionLand::setNextMissionItem()
117117
{
118-
return (goToNextPositionItem(MissionTraversalType::FollowMissionControlFlow) == PX4_OK);
118+
return (goToNextPositionItem() == PX4_OK);
119119
}
120120

121121
void RtlDirectMissionLand::setActiveMissionItems()

src/modules/navigator/rtl_mission_fast.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ void RtlMissionFast::on_activation()
101101

102102
bool RtlMissionFast::setNextMissionItem()
103103
{
104-
return (goToNextPositionItem(MissionTraversalType::FollowMissionControlFlow) == PX4_OK);
104+
return (goToNextPositionItem() == PX4_OK);
105105
}
106106

107107
void RtlMissionFast::setActiveMissionItems()

src/modules/navigator/rtl_mission_fast.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ class RtlMissionFast : public RtlBase
6363
private:
6464
bool setNextMissionItem() override;
6565
void setActiveMissionItems() override;
66+
MissionTraversalType traversalType() const override { return MissionTraversalType::IgnoreDoJump; }
6667

6768
int32_t _mission_index_prior_rtl{INT32_C(-1)};
6869

0 commit comments

Comments
 (0)