@@ -143,16 +143,16 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
143143 state = scene->getCurrentState ();
144144 }
145145
146- plan.plan_components .reserve (solution.sub_trajectory .size ());
146+ plan.plan_components_ .reserve (solution.sub_trajectory .size ());
147147 for (size_t i = 0 ; i < solution.sub_trajectory .size (); ++i) {
148148 const moveit_task_constructor_msgs::msg::SubTrajectory& sub_traj = solution.sub_trajectory [i];
149149
150- plan.plan_components .emplace_back ();
151- plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components .back ();
150+ plan.plan_components_ .emplace_back ();
151+ plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components_ .back ();
152152
153153 // define individual variable for use in closure below
154154 const std::string description = std::to_string (i + 1 ) + " /" + std::to_string (solution.sub_trajectory .size ());
155- exec_traj.description = description;
155+ exec_traj.description_ = description;
156156
157157 const moveit::core::JointModelGroup* group = nullptr ;
158158 {
@@ -169,8 +169,8 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
169169 RCLCPP_DEBUG (LOGGER, " Using JointModelGroup '%s' for execution" , group->getName ().c_str ());
170170 }
171171 }
172- exec_traj.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
173- exec_traj.trajectory ->setRobotTrajectoryMsg (state, sub_traj.trajectory );
172+ exec_traj.trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
173+ exec_traj.trajectory_ ->setRobotTrajectoryMsg (state, sub_traj.trajectory );
174174
175175 // Check that sub trajectories that contain a valid trajectory have controllers configured.
176176 if (!sub_traj.trajectory .joint_trajectory .points .empty () && sub_traj.execution_info .controller_names .empty ()) {
@@ -179,12 +179,12 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
179179 " trajectory execution. This might lead to unexpected controller selection." ,
180180 sub_traj.info .stage_id , solution.task_id .c_str ());
181181 }
182- exec_traj.controller_name = sub_traj.execution_info .controller_names ;
182+ exec_traj.controller_names_ = sub_traj.execution_info .controller_names ;
183183
184184 /* TODO add action feedback and markers */
185- exec_traj.effect_on_success = [this ,
186- &scene_diff = const_cast <::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff ),
187- description](const plan_execution::ExecutableMotionPlan* /* plan*/ ) {
185+ exec_traj.effect_on_success_ = [this ,
186+ &scene_diff = const_cast <::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff ),
187+ description](const plan_execution::ExecutableMotionPlan* /* plan*/ ) {
188188 // Never modify joint state directly (only via robot trajectories)
189189 scene_diff.robot_state .joint_state = sensor_msgs::msg::JointState ();
190190 scene_diff.robot_state .multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState ();
0 commit comments