41namespace bind_trajectory_execution_manager
46 trajectory_execution_manager::TrajectoryExecutionManagerPtr>(m,
"TrajectoryExecutionManager", R
"(
47 Manages the trajectory execution.
52 If this function returns true, then this instance of the manager is allowed to load/unload/switch controllers.
57 Execute a named event (e.g., 'stop').
60 .def("ensure_active_controllers_for_group",
63 Make sure the active controllers are such that trajectories that actuate joints in the specified group can be executed.
65 If the 'moveit_manage_controllers' parameter is false and the controllers that happen to be active do not cover the joints in the group to be actuated, this function fails.
68 .def("ensure_active_controllers_for_joints",
72 Make sure the active controllers are such that trajectories that actuate joints in the specified set can be executed.
74 If the 'moveit_manage_controllers' parameter is false and the controllers that happen to be active do not cover the joints to be actuated, this function fails.
77 .def("ensure_active_controller",
80 Make sure a particular controller is active.
82 If the 'moveit_manage_controllers' parameter is false and the controllers that happen to be active do not include the one specified as argument, this function fails.
85 .def("ensure_active_controllers",
88 Make sure a particular set of controllers are active.
90 If the 'moveit_manage_controllers' parameter is false and the controllers that happen to be active do not include the ones specified as argument, this function fails.
94 py::arg(
"controller"),
96 Check if a controller is active.
100 py::arg(
"controllers"),
102 Check if a set of controllers is active.
107 const std::string&)) &
109 py::arg(
"trajectory"), py::arg(
"controller") =
"",
111 Add a trajectory for future execution. Optionally specify a controller to use for the trajectory.
113 If no controller is specified, a default is used.
118 const trajectory_msgs::msg::JointTrajectory&,
const std::string&)) &
120 py::arg(
"trajectory"), py::arg(
"controller") =
"",
122 Add a trajectory for future execution. Optionally specify a controller to use for the trajectory.
124 If no controller is specified, a default is used.
129 const std::vector<std::string>&)) &
131 py::arg(
"trajectory"), py::arg(
"controllers"),
133 Add a trajectory for future execution.
135 Optionally specify a set of controllers to consider using for the trajectory.
136 Multiple controllers can be used simultaneously to execute the different parts of the trajectory.
137 If multiple controllers can be used, preference is given to the already loaded ones.
138 If no controller is specified, a default is used.
143 const trajectory_msgs::msg::JointTrajectory&,
const std::vector<std::string>&)) &
145 py::arg(
"trajectory"), py::arg(
"controllers"),
147 Add a trajectory for future execution.
149 Optionally specify a set of controllers to consider using for the trajectory.
150 Multiple controllers can be used simultaneously to execute the different parts of the trajectory.
151 If multiple controllers can be used, preference is given to the already loaded ones.
152 If no controller is specified, a default is used.
161 py::arg(
"callback"), py::arg(
"auto_clear") =
true,
163 Start the execution of pushed trajectories.
165 This does not wait for completion, but calls a callback when done.
172 py::arg(
"callback"), py::arg(
"part_callback"), py::arg(
"auto_clear") =
true,
174 Start the execution of pushed trajectories.
176 This does not wait for completion, but calls a callback when done. A callback is also called for every
177 trajectory part that completes successfully.
180 py::arg(
"auto_clear") =
true, py::call_guard<py::gil_scoped_release>(),
182 Execute a trajectory and wait for it to finish.
185 py::call_guard<py::gil_scoped_release>(),
187 Wait for the current trajectory to finish execution.
192 .def(
"get_last_execution_status",
195 Get the status of the last execution.
198 py::arg(
"auto_clear") =
true, py::call_guard<py::gil_scoped_release>(),
200 Stop whatever executions are active, if any.
205 Clear the trajectories to execute.
208 .def("enable_execution_duration_monitoring",
212 Enable or disable the monitoring of trajectory execution duration.
214 If a controller takes longer than expected, the trajectory is canceled.
217 .def("execution_duration_monitoring",
220 Get the current status of the monitoring of trajectory execution duration.
223 .def("set_allowed_execution_duration_scaling",
227 When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution.
230 .def("allowed_execution_duration_scaling",
233 Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
236 .def("set_allowed_goal_duration_margin",
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.
242 .def("allowed_goal_duration_margin",
245 Get the current margin of the duration of a trajectory to get the allowed duration of execution.
248 .def("set_execution_velocity_scaling",
251 Before sending a trajectory to a controller, scale the velocities by the factor specified.
253 By default, this is 1.0
256 .def("execution_velocity_scaling",
259 Get the current scaling of the execution velocities.
262 .def("set_allowed_start_tolerance",
265 Set joint-value tolerance for validating trajectory's start point against current robot state.
270 Get the current joint-value for validating trajectory's start point against current robot state.
273 .def("set_wait_for_trajectory_completion",
276 Enable or disable waiting for trajectory completion.
279 .def("wait_for_trajectory_completion",
282 Get the current state of waiting for the trajectory being completed.
void execute(const ExecutionCompleteCallback &callback=ExecutionCompleteCallback(), bool auto_clear=true)
Start the execution of pushed trajectories; this does not wait for completion, but calls a callback w...
void stopExecution(bool auto_clear=true)
Stop whatever executions are active, if any.
void setWaitForTrajectoryCompletion(bool flag)
Enable or disable waiting for trajectory completion.
void clear()
Clear the trajectories to execute.
double allowedStartTolerance() const
Get the current joint-value for validating trajectory's start point against current robot state.
bool ensureActiveControllersForGroup(const std::string &group)
Make sure the active controllers are such that trajectories that actuate joints in the specified grou...
void setAllowedGoalDurationMargin(double margin)
std::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
bool ensureActiveController(const std::string &controller)
Make sure a particular controller is active.
void setAllowedExecutionDurationScaling(double scaling)
moveit_controller_manager::ExecutionStatus getLastExecutionStatus() const
Return the controller status for the last attempted execution.
double allowedExecutionDurationScaling() const
Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
void enableExecutionDurationMonitoring(bool flag)
bool push(const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &controller="")
void setExecutionVelocityScaling(double scaling)
bool isManagingControllers() const
If this function returns true, then this instance of the manager is allowed to load/unload/switch con...
bool isControllerActive(const std::string &controller)
Check if a controller is active.
bool executionDurationMonitoring() const
Get the current status of the monitoring of trajectory execution duration.
double allowedGoalDurationMargin() const
Get the current margin of the duration of a trajectory to get the allowed duration of execution.
bool waitForTrajectoryCompletion() const
Get the current state of waiting for the trajectory being completed.
moveit_controller_manager::ExecutionStatus executeAndWait(bool auto_clear=true)
moveit_controller_manager::ExecutionStatus waitForExecution()
void setAllowedStartTolerance(double tolerance)
Set joint-value tolerance for validating trajectory's start point against current robot state.
void processEvent(const std::string &event)
Execute a named event (e.g., 'stop')
double executionVelocityScaling() const
Get the current scaling of the execution velocities.
bool areControllersActive(const std::vector< std::string > &controllers)
Check if a set of controllers is active.
std::function< void(std::size_t)> PathSegmentCompleteCallback
bool ensureActiveControllersForJoints(const std::vector< std::string > &joints)
Make sure the active controllers are such that trajectories that actuate joints in the specified set ...
bool ensureActiveControllers(const std::vector< std::string > &controllers)
Make sure a particular set of controllers are active.
void initTrajectoryExecutionManager(py::module &m)