Skip to content

Commit 0c4b4fc

Browse files
sjahrrhaschke
authored andcommitted
Print warning if no controllers are configured for trajectory execution (#514)
1 parent 7393752 commit 0c4b4fc

File tree

1 file changed

+9
-0
lines changed

1 file changed

+9
-0
lines changed

capabilities/src/execute_task_solution_capability.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -174,6 +174,15 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
174174
exec_traj.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
175175
exec_traj.trajectory->setRobotTrajectoryMsg(state, sub_traj.trajectory);
176176

177+
// Check that sub trajectories that contain a valid trajectory have controllers configured.
178+
if (!sub_traj.trajectory.joint_trajectory.points.empty() && sub_traj.execution_info.controller_names.empty()) {
179+
RCLCPP_WARN(LOGGER,
180+
"The trajectory of stage '%i' from task '%s' does not have any controllers specified for "
181+
"trajectory execution. This might lead to unexpected controller selection.",
182+
sub_traj.info.stage_id, solution.task_id.c_str());
183+
}
184+
exec_traj.controller_name = sub_traj.execution_info.controller_names;
185+
177186
/* TODO add action feedback and markers */
178187
exec_traj.effect_on_success = [this,
179188
&scene_diff = const_cast<::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff),

0 commit comments

Comments
 (0)