File tree Expand file tree Collapse file tree 2 files changed +10
-6
lines changed
px4_ros2_cpp/include/px4_ros2/mission/actions Expand file tree Collapse file tree 2 files changed +10
-6
lines changed Original file line number Diff line number Diff line change @@ -47,6 +47,10 @@ properties:
47
47
description : |
48
48
Optional ID of the mission item, can be set to an arbitrary string
49
49
type : string
50
+ type :
51
+ type : string
52
+ not :
53
+ pattern : " ^internal:"
50
54
allOf :
51
55
- if :
52
56
properties :
@@ -152,9 +156,9 @@ properties:
152
156
description : |
153
157
Enter Hold (aka Loiter) for a certain duration
154
158
properties :
155
- delay :
159
+ duration :
156
160
description : |
157
- Delay in seconds. Default: 1 second
161
+ Duration in seconds. Default: 1 second
158
162
type : number
159
163
minimum : 0
160
164
Original file line number Diff line number Diff line change @@ -94,13 +94,13 @@ class Hold : public ActionInterface
94
94
const std::shared_ptr<ActionHandler> & handler, const ActionArguments & arguments,
95
95
const std::function<void ()> & on_completed) override
96
96
{
97
- float delay_s = 1 .0f ;
98
- if (arguments.contains (" delay " )) {
99
- delay_s = arguments.at <float >(" delay " );
97
+ float duration_s = 1 .0f ;
98
+ if (arguments.contains (" duration " )) {
99
+ duration_s = arguments.at <float >(" duration " );
100
100
}
101
101
handler->runMode (ModeBase::kModeIDLoiter , [] {});
102
102
_timer = _node.create_wall_timer (
103
- std::chrono::duration<float >(delay_s ), [this , on_completed] {
103
+ std::chrono::duration<float >(duration_s ), [this , on_completed] {
104
104
_timer.reset ();
105
105
on_completed ();
106
106
});
You can’t perform that action at this time.
0 commit comments