@@ -144,16 +144,16 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(
144144 state = scene->getCurrentState ();
145145 }
146146
147- plan.plan_components .reserve (solution.sub_trajectory .size ());
147+ plan.plan_components_ .reserve (solution.sub_trajectory .size ());
148148 for (size_t i = 0 ; i < solution.sub_trajectory .size (); ++i) {
149149 const moveit_task_constructor_msgs::msg::SubTrajectory& sub_traj = solution.sub_trajectory [i];
150150
151- plan.plan_components .emplace_back ();
152- plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components .back ();
151+ plan.plan_components_ .emplace_back ();
152+ plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components_ .back ();
153153
154154 // define individual variable for use in closure below
155155 const std::string description = std::to_string (i + 1 ) + " /" + std::to_string (solution.sub_trajectory .size ());
156- exec_traj.description = description;
156+ exec_traj.description_ = description;
157157
158158 const moveit::core::JointModelGroup* group = nullptr ;
159159 {
@@ -170,8 +170,8 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(
170170 RCLCPP_DEBUG (LOGGER, " Using JointModelGroup '%s' for execution" , group->getName ().c_str ());
171171 }
172172 }
173- exec_traj.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
174- exec_traj.trajectory ->setRobotTrajectoryMsg (state, sub_traj.trajectory );
173+ exec_traj.trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
174+ exec_traj.trajectory_ ->setRobotTrajectoryMsg (state, sub_traj.trajectory );
175175
176176 // Check that sub trajectories that contain a valid trajectory have controllers configured.
177177 if (!sub_traj.trajectory .joint_trajectory .points .empty () && sub_traj.execution_info .controller_names .empty ()) {
@@ -180,10 +180,10 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(
180180 " trajectory execution. This might lead to unexpected controller selection." ,
181181 sub_traj.info .stage_id , solution.task_id .c_str ());
182182 }
183- exec_traj.controller_name = sub_traj.execution_info .controller_names ;
183+ exec_traj.controller_names_ = sub_traj.execution_info .controller_names ;
184184
185185 /* TODO add action feedback and markers */
186- exec_traj.effect_on_success =
186+ exec_traj.effect_on_success_ =
187187 [this , &scene_diff = const_cast <::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff ), description,
188188 goal_handle, i, no = solution.sub_trajectory .size ()](const plan_execution::ExecutableMotionPlan* /* plan*/ ) {
189189 // publish feedback
0 commit comments