Skip to content

Commit 442a32f

Browse files
committed
(ros_planning) get configuration values of traj_exec_man
1 parent f47b4c0 commit 442a32f

File tree

2 files changed

+48
-0
lines changed

2 files changed

+48
-0
lines changed

moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h

+18
Original file line numberDiff line numberDiff line change
@@ -193,24 +193,42 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager
193193
/// longer than expected, the trajectory is canceled
194194
void enableExecutionDurationMonitoring(bool flag);
195195

196+
/// Get the current status of the monitoring of trajectory execution duration.
197+
bool ExecutionDurationMonitoring() const;
198+
196199
/// When determining the expected duration of a trajectory, this multiplicative factor is applied
197200
/// to get the allowed duration of execution
198201
void setAllowedExecutionDurationScaling(double scaling);
199202

203+
/// Get the current scaling of the duration of a trajectory to get the allowed duration of execution.
204+
double AllowedExecutionDurationScaling() const;
205+
200206
/// When determining the expected duration of a trajectory, this multiplicative factor is applied
201207
/// to allow more than the expected execution time before triggering trajectory cancel
202208
void setAllowedGoalDurationMargin(double margin);
203209

210+
/// Get the current margin of the duration of a trajectory to get the allowed duration of execution.
211+
double AllowedGoalDurationMargin() const;
212+
204213
/// Before sending a trajectory to a controller, scale the velocities by the factor specified.
205214
/// By default, this is 1.0
206215
void setExecutionVelocityScaling(double scaling);
207216

217+
/// Get the current scaling of the execution velocities.
218+
double ExecutionVelocityScaling() const;
219+
208220
/// Set joint-value tolerance for validating trajectory's start point against current robot state
209221
void setAllowedStartTolerance(double tolerance);
210222

223+
/// Get the current joint-value for validating trajectory's start point against current robot state.
224+
double AllowedStartTolerance() const;
225+
211226
/// Enable or disable waiting for trajectory completion
212227
void setWaitForTrajectoryCompletion(bool flag);
213228

229+
/// Get the current state of waiting for the trajectory being completed.
230+
bool WaitForTrajectoryCompletion() const;
231+
214232
rclcpp::Node::SharedPtr getControllerManagerNode()
215233
{
216234
return controller_mgr_node_;

moveit_ros/planning/trajectory_execution_manager/src/trajectory_execution_manager.cpp

+30
Original file line numberDiff line numberDiff line change
@@ -255,31 +255,61 @@ void TrajectoryExecutionManager::enableExecutionDurationMonitoring(bool flag)
255255
execution_duration_monitoring_ = flag;
256256
}
257257

258+
bool TrajectoryExecutionManager::ExecutionDurationMonitoring() const
259+
{
260+
return execution_duration_monitoring_;
261+
}
262+
258263
void TrajectoryExecutionManager::setAllowedExecutionDurationScaling(double scaling)
259264
{
260265
allowed_execution_duration_scaling_ = scaling;
261266
}
262267

268+
double TrajectoryExecutionManager::AllowedExecutionDurationScaling() const
269+
{
270+
return allowed_execution_duration_scaling_;
271+
}
272+
263273
void TrajectoryExecutionManager::setAllowedGoalDurationMargin(double margin)
264274
{
265275
allowed_goal_duration_margin_ = margin;
266276
}
267277

278+
double TrajectoryExecutionManager::AllowedGoalDurationMargin() const
279+
{
280+
return allowed_goal_duration_margin_;
281+
}
282+
268283
void TrajectoryExecutionManager::setExecutionVelocityScaling(double scaling)
269284
{
270285
execution_velocity_scaling_ = scaling;
271286
}
272287

288+
double TrajectoryExecutionManager::ExecutionVelocityScaling() const
289+
{
290+
return execution_velocity_scaling_;
291+
}
292+
273293
void TrajectoryExecutionManager::setAllowedStartTolerance(double tolerance)
274294
{
275295
allowed_start_tolerance_ = tolerance;
276296
}
277297

298+
double TrajectoryExecutionManager::AllowedStartTolerance() const
299+
{
300+
return allowed_start_tolerance_;
301+
}
302+
278303
void TrajectoryExecutionManager::setWaitForTrajectoryCompletion(bool flag)
279304
{
280305
wait_for_trajectory_completion_ = flag;
281306
}
282307

308+
bool TrajectoryExecutionManager::WaitForTrajectoryCompletion() const
309+
{
310+
return wait_for_trajectory_completion_;
311+
}
312+
283313
bool TrajectoryExecutionManager::isManagingControllers() const
284314
{
285315
return manage_controllers_;

0 commit comments

Comments
 (0)