moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
trajectory_execution_manager.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, Matthijs van der Burgh
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Matthijs van der Burgh */
36
38
39namespace moveit_py
40{
41namespace bind_trajectory_execution_manager
42{
44{
46 trajectory_execution_manager::TrajectoryExecutionManagerPtr>(m, "TrajectoryExecutionManager", R"(
47 Manages the trajectory execution.
48 )")
49
51 R"(
52 If this function returns true, then this instance of the manager is allowed to load/unload/switch controllers.
53 )")
54
56 R"(
57 Execute a named event (e.g., 'stop').
58 )")
59
60 .def("ensure_active_controllers_for_group",
62 R"(
63 Make sure the active controllers are such that trajectories that actuate joints in the specified group can be executed.
64
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.
66 )")
67
68 .def("ensure_active_controllers_for_joints",
70 py::arg("joints"),
71 R"(
72 Make sure the active controllers are such that trajectories that actuate joints in the specified set can be executed.
73
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.
75 )")
76
77 .def("ensure_active_controller",
79 R"(
80 Make sure a particular controller is active.
81
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.
83 )")
84
85 .def("ensure_active_controllers",
87 R"(
88 Make sure a particular set of controllers are active.
89
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.
91 )")
92
94 py::arg("controller"),
95 R"(
96 Check if a controller is active.
97 )")
98
100 py::arg("controllers"),
101 R"(
102 Check if a set of controllers is active.
103 )")
104
105 .def("push",
106 (bool(trajectory_execution_manager::TrajectoryExecutionManager::*)(const moveit_msgs::msg::RobotTrajectory&,
107 const std::string&)) &
109 py::arg("trajectory"), py::arg("controller") = "",
110 R"(
111 Add a trajectory for future execution. Optionally specify a controller to use for the trajectory.
112
113 If no controller is specified, a default is used.
114 )")
115
116 .def("push",
118 const trajectory_msgs::msg::JointTrajectory&, const std::string&)) &
120 py::arg("trajectory"), py::arg("controller") = "",
121 R"(
122 Add a trajectory for future execution. Optionally specify a controller to use for the trajectory.
123
124 If no controller is specified, a default is used.
125 )")
126
127 .def("push",
128 (bool(trajectory_execution_manager::TrajectoryExecutionManager::*)(const moveit_msgs::msg::RobotTrajectory&,
129 const std::vector<std::string>&)) &
131 py::arg("trajectory"), py::arg("controllers"),
132 R"(
133 Add a trajectory for future execution.
134
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.
139 )")
140
141 .def("push",
143 const trajectory_msgs::msg::JointTrajectory&, const std::vector<std::string>&)) &
145 py::arg("trajectory"), py::arg("controllers"),
146 R"(
147 Add a trajectory for future execution.
148
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.
153 )")
154
155 // ToDo(MatthijsBurgh)
156 // See https://github.com/moveit/moveit2/issues/2442
157 // get_trajectories
158 .def("execute",
161 py::arg("callback"), py::arg("auto_clear") = true,
162 R"(
163 Start the execution of pushed trajectories.
164
165 This does not wait for completion, but calls a callback when done.
166 )")
167 .def(
168 "execute",
172 py::arg("callback"), py::arg("part_callback"), py::arg("auto_clear") = true,
173 R"(
174 Start the execution of pushed trajectories.
175
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.
178 )")
180 py::arg("auto_clear") = true, py::call_guard<py::gil_scoped_release>(),
181 R"(
182 Execute a trajectory and wait for it to finish.
183 )")
185 py::call_guard<py::gil_scoped_release>(),
186 R"(
187 Wait for the current trajectory to finish execution.
188 )")
189 // ToDo(MatthijsBurgh)
190 // See https://github.com/moveit/moveit2/issues/2442
191 // get_current_expected_trajectory_index
192 .def("get_last_execution_status",
194 R"(
195 Get the status of the last execution.
196 )")
198 py::arg("auto_clear") = true, py::call_guard<py::gil_scoped_release>(),
199 R"(
200 Stop whatever executions are active, if any.
201 )")
202
204 R"(
205 Clear the trajectories to execute.
206 )")
207
208 .def("enable_execution_duration_monitoring",
210 py::arg("flag"),
211 R"(
212 Enable or disable the monitoring of trajectory execution duration.
213
214 If a controller takes longer than expected, the trajectory is canceled.
215 )")
216
217 .def("execution_duration_monitoring",
219 R"(
220 Get the current status of the monitoring of trajectory execution duration.
221 )")
222
223 .def("set_allowed_execution_duration_scaling",
225 py::arg("scaling"),
226 R"(
227 When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution.
228 )")
229
230 .def("allowed_execution_duration_scaling",
232 R"(
233 Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
234 )")
235
236 .def("set_allowed_goal_duration_margin",
238 R"(
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.
240 )")
241
242 .def("allowed_goal_duration_margin",
244 R"(
245 Get the current margin of the duration of a trajectory to get the allowed duration of execution.
246 )")
247
248 .def("set_execution_velocity_scaling",
250 R"(
251 Before sending a trajectory to a controller, scale the velocities by the factor specified.
252
253 By default, this is 1.0
254 )")
255
256 .def("execution_velocity_scaling",
258 R"(
259 Get the current scaling of the execution velocities.
260 )")
261
262 .def("set_allowed_start_tolerance",
264 R"(
265 Set joint-value tolerance for validating trajectory's start point against current robot state.
266 )")
267
269 R"(
270 Get the current joint-value for validating trajectory's start point against current robot state.
271 )")
272
273 .def("set_wait_for_trajectory_completion",
275 R"(
276 Enable or disable waiting for trajectory completion.
277 )")
278
279 .def("wait_for_trajectory_completion",
281 R"(
282 Get the current state of waiting for the trajectory being completed.
283 )");
284
285 // ToDo(MatthijsBurgh)
286 // https://github.com/moveit/moveit2/issues/2442
287 // get_controller_manager_node
288}
289} // namespace bind_trajectory_execution_manager
290} // namespace moveit_py
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.
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...
std::function< void(const moveit_controller_manager::ExecutionStatus &)> ExecutionCompleteCallback
bool ensureActiveController(const std::string &controller)
Make sure a particular controller is active.
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.
bool push(const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &controller="")
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)
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.
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.