@@ -166,21 +166,26 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
166
166
exec_traj.trajectory_ ->setRobotTrajectoryMsg (state, sub_traj.trajectory );
167
167
exec_traj.controller_names_ = sub_traj.execution_info .controller_names ;
168
168
169
- /* TODO add action feedback and markers */
170
- exec_traj.effect_on_success_ = [this ,
171
- &scene_diff = const_cast <::moveit_msgs::PlanningScene&>(sub_traj.scene_diff ),
172
- description](const plan_execution::ExecutableMotionPlan* /* plan*/ ) {
173
- // Never modify joint state directly (only via robot trajectories)
174
- scene_diff.robot_state .joint_state = sensor_msgs::JointState ();
175
- scene_diff.robot_state .multi_dof_joint_state = sensor_msgs::MultiDOFJointState ();
176
- scene_diff.robot_state .is_diff = true ; // silent empty JointState msg error
177
-
178
- if (!moveit::core::isEmpty (scene_diff)) {
179
- ROS_DEBUG_STREAM_NAMED (" ExecuteTaskSolution" , " apply effect of " << description);
180
- return context_->planning_scene_monitor_ ->newPlanningSceneMessage (scene_diff);
181
- }
182
- return true ;
183
- };
169
+ exec_traj.effect_on_success_ =
170
+ [this , &scene_diff = const_cast <::moveit_msgs::PlanningScene&>(sub_traj.scene_diff ), description, i,
171
+ no = solution.sub_trajectory .size ()](const plan_execution::ExecutableMotionPlan* /* plan*/ ) {
172
+ // publish feedback
173
+ moveit_task_constructor_msgs::ExecuteTaskSolutionFeedback feedback;
174
+ feedback.sub_id = i;
175
+ feedback.sub_no = no;
176
+ as_->publishFeedback (feedback);
177
+
178
+ // Never modify joint state directly (only via robot trajectories)
179
+ scene_diff.robot_state .joint_state = sensor_msgs::JointState ();
180
+ scene_diff.robot_state .multi_dof_joint_state = sensor_msgs::MultiDOFJointState ();
181
+ scene_diff.robot_state .is_diff = true ; // silent empty JointState msg error
182
+
183
+ if (!moveit::core::isEmpty (scene_diff)) {
184
+ ROS_DEBUG_STREAM_NAMED (" ExecuteTaskSolution" , " apply effect of " << description);
185
+ return context_->planning_scene_monitor_ ->newPlanningSceneMessage (scene_diff);
186
+ }
187
+ return true ;
188
+ };
184
189
185
190
if (!moveit::core::isEmpty (sub_traj.scene_diff .robot_state ) &&
186
191
!moveit::core::robotStateMsgToRobotState (sub_traj.scene_diff .robot_state , state, true )) {
0 commit comments