@@ -214,19 +214,37 @@ void initTrajectoryExecutionManager(py::module& m)
214
214
If a controller takes longer than expected, the trajectory is canceled.
215
215
)" )
216
216
217
+ .def (" execution_duration_monitoring" ,
218
+ &trajectory_execution_manager::TrajectoryExecutionManager::ExecutionDurationMonitoring,
219
+ R"(
220
+ Get the current status of the monitoring of trajectory execution duration.
221
+ )" )
222
+
217
223
.def (" set_allowed_execution_duration_scaling" ,
218
224
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedExecutionDurationScaling,
219
225
py::arg (" scaling" ),
220
226
R"(
221
227
When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution.
222
228
)" )
223
229
230
+ .def (" allowed_execution_duration_scaling" ,
231
+ &trajectory_execution_manager::TrajectoryExecutionManager::AllowedExecutionDurationScaling,
232
+ R"(
233
+ Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
234
+ )" )
235
+
224
236
.def (" set_allowed_goal_duration_margin" ,
225
237
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedGoalDurationMargin, py::arg (" margin" ),
226
238
R"(
227
239
When determining the expected duration of a trajectory, this additional margin s applied after scalign to allow more than the expected execution time before triggering trajectory cancel.
228
240
)" )
229
241
242
+ .def (" allowed_goal_duration_margin" ,
243
+ &trajectory_execution_manager::TrajectoryExecutionManager::AllowedGoalDurationMargin,
244
+ R"(
245
+ Get the current margin of the duration of a trajectory to get the allowed duration of execution.
246
+ )" )
247
+
230
248
.def (" set_execution_velocity_scaling" ,
231
249
&trajectory_execution_manager::TrajectoryExecutionManager::setExecutionVelocityScaling, py::arg (" scaling" ),
232
250
R"(
@@ -235,16 +253,33 @@ void initTrajectoryExecutionManager(py::module& m)
235
253
By default, this is 1.0
236
254
)" )
237
255
256
+ .def (" execution_velocity_scaling" ,
257
+ &trajectory_execution_manager::TrajectoryExecutionManager::ExecutionVelocityScaling,
258
+ R"(
259
+ Get the current scaling of the execution velocities.
260
+ )" )
261
+
238
262
.def (" set_allowed_start_tolerance" ,
239
263
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedStartTolerance, py::arg (" tolerance" ),
240
264
R"(
241
265
Set joint-value tolerance for validating trajectory's start point against current robot state.
242
266
)" )
243
267
268
+ .def (" allowed_start_tolerance" , &trajectory_execution_manager::TrajectoryExecutionManager::AllowedStartTolerance,
269
+ R"(
270
+ Get the current joint-value for validating trajectory's start point against current robot state.
271
+ )" )
272
+
244
273
.def (" set_wait_for_trajectory_completion" ,
245
274
&trajectory_execution_manager::TrajectoryExecutionManager::setWaitForTrajectoryCompletion, py::arg (" flag" ),
246
275
R"(
247
276
Enable or disable waiting for trajectory completion.
277
+ )" )
278
+
279
+ .def (" wait_for_trajectory_completion" ,
280
+ &trajectory_execution_manager::TrajectoryExecutionManager::WaitForTrajectoryCompletion,
281
+ R"(
282
+ Get the current state of waiting for the trajectory being completed.
248
283
)" );
249
284
250
285
// ToDo(MatthijsBurgh)
0 commit comments