Skip to content

Commit 5493bed

Browse files
committed
(py) get configuration values of traj_exec_man
1 parent 442a32f commit 5493bed

File tree

2 files changed

+41
-0
lines changed

2 files changed

+41
-0
lines changed

moveit_py/moveit/planning.pyi

+6
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,9 @@ class PlanningSceneMonitor:
6868

6969
class TrajectoryExecutionManager:
7070
def __init__(self, *args, **kwargs) -> None: ...
71+
def allowed_execution_duration_scaling(self, *args, **kwargs) -> Any: ...
72+
def allowed_goal_duration_margin(self, *args, **kwargs) -> Any: ...
73+
def allowed_start_tolerance(self, *args, **kwargs) -> Any: ...
7174
def are_controllers_active(self, *args, **kwargs) -> Any: ...
7275
def clear(self, *args, **kwargs) -> Any: ...
7376
def enable_execution_duration_monitoring(self, *args, **kwargs) -> Any: ...
@@ -77,6 +80,8 @@ class TrajectoryExecutionManager:
7780
def ensure_active_controllers_for_joints(self, *args, **kwargs) -> Any: ...
7881
def execute(self, *args, **kwargs) -> Any: ...
7982
def execute_and_wait(self, *args, **kwargs) -> Any: ...
83+
def execution_duration_monitoring(self, *args, **kwargs) -> Any: ...
84+
def execution_velocity_scaling(self, *args, **kwargs) -> Any: ...
8085
def get_last_execution_status(self, *args, **kwargs) -> Any: ...
8186
def is_controller_active(self, *args, **kwargs) -> Any: ...
8287
def is_managing_controllers(self, *args, **kwargs) -> Any: ...
@@ -89,3 +94,4 @@ class TrajectoryExecutionManager:
8994
def set_wait_for_trajectory_completion(self, *args, **kwargs) -> Any: ...
9095
def stop_execution(self, *args, **kwargs) -> Any: ...
9196
def wait_for_execution(self, *args, **kwargs) -> Any: ...
97+
def wait_for_trajectory_completion(self, *args, **kwargs) -> Any: ...

moveit_py/src/moveit/moveit_ros/trajectory_execution_manager/trajectory_execution_manager.cpp

+35
Original file line numberDiff line numberDiff line change
@@ -214,19 +214,37 @@ void initTrajectoryExecutionManager(py::module& m)
214214
If a controller takes longer than expected, the trajectory is canceled.
215215
)")
216216

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+
217223
.def("set_allowed_execution_duration_scaling",
218224
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedExecutionDurationScaling,
219225
py::arg("scaling"),
220226
R"(
221227
When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution.
222228
)")
223229

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+
224236
.def("set_allowed_goal_duration_margin",
225237
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedGoalDurationMargin, py::arg("margin"),
226238
R"(
227239
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.
228240
)")
229241

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+
230248
.def("set_execution_velocity_scaling",
231249
&trajectory_execution_manager::TrajectoryExecutionManager::setExecutionVelocityScaling, py::arg("scaling"),
232250
R"(
@@ -235,16 +253,33 @@ void initTrajectoryExecutionManager(py::module& m)
235253
By default, this is 1.0
236254
)")
237255

256+
.def("execution_velocity_scaling",
257+
&trajectory_execution_manager::TrajectoryExecutionManager::ExecutionVelocityScaling,
258+
R"(
259+
Get the current scaling of the execution velocities.
260+
)")
261+
238262
.def("set_allowed_start_tolerance",
239263
&trajectory_execution_manager::TrajectoryExecutionManager::setAllowedStartTolerance, py::arg("tolerance"),
240264
R"(
241265
Set joint-value tolerance for validating trajectory's start point against current robot state.
242266
)")
243267

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+
244273
.def("set_wait_for_trajectory_completion",
245274
&trajectory_execution_manager::TrajectoryExecutionManager::setWaitForTrajectoryCompletion, py::arg("flag"),
246275
R"(
247276
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.
248283
)");
249284

250285
// ToDo(MatthijsBurgh)

0 commit comments

Comments
 (0)