Skip to content

Commit b222461

Browse files
committed
Restore underscores for public members in MotionPlanResponse
This reverts commit 5c308d1.
1 parent f59c3a8 commit b222461

File tree

1 file changed

+10
-10
lines changed

1 file changed

+10
-10
lines changed

capabilities/src/execute_task_solution_capability.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -145,16 +145,16 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
145145
state = scene->getCurrentState();
146146
}
147147

148-
plan.plan_components.reserve(solution.sub_trajectory.size());
148+
plan.plan_components_.reserve(solution.sub_trajectory.size());
149149
for (size_t i = 0; i < solution.sub_trajectory.size(); ++i) {
150150
const moveit_task_constructor_msgs::msg::SubTrajectory& sub_traj = solution.sub_trajectory[i];
151151

152-
plan.plan_components.emplace_back();
153-
plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components.back();
152+
plan.plan_components_.emplace_back();
153+
plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components_.back();
154154

155155
// define individual variable for use in closure below
156156
const std::string description = std::to_string(i + 1) + "/" + std::to_string(solution.sub_trajectory.size());
157-
exec_traj.description = description;
157+
exec_traj.description_ = description;
158158

159159
const moveit::core::JointModelGroup* group = nullptr;
160160
{
@@ -171,8 +171,8 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
171171
RCLCPP_DEBUG(LOGGER, "Using JointModelGroup '%s' for execution", group->getName().c_str());
172172
}
173173
}
174-
exec_traj.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
175-
exec_traj.trajectory->setRobotTrajectoryMsg(state, sub_traj.trajectory);
174+
exec_traj.trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
175+
exec_traj.trajectory_->setRobotTrajectoryMsg(state, sub_traj.trajectory);
176176

177177
// Check that sub trajectories that contain a valid trajectory have controllers configured.
178178
if (!sub_traj.trajectory.joint_trajectory.points.empty() && sub_traj.execution_info.controller_names.empty()) {
@@ -181,12 +181,12 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
181181
"trajectory execution. This might lead to unexpected controller selection.",
182182
sub_traj.info.stage_id, solution.task_id.c_str());
183183
}
184-
exec_traj.controller_name = sub_traj.execution_info.controller_names;
184+
exec_traj.controller_names_ = sub_traj.execution_info.controller_names;
185185

186186
/* TODO add action feedback and markers */
187-
exec_traj.effect_on_success = [this,
188-
&scene_diff = const_cast<::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff),
189-
description](const plan_execution::ExecutableMotionPlan* /*plan*/) {
187+
exec_traj.effect_on_success_ = [this,
188+
&scene_diff = const_cast<::moveit_msgs::msg::PlanningScene&>(sub_traj.scene_diff),
189+
description](const plan_execution::ExecutableMotionPlan* /*plan*/) {
190190
scene_diff.robot_state.joint_state = sensor_msgs::msg::JointState();
191191
scene_diff.robot_state.multi_dof_joint_state = sensor_msgs::msg::MultiDOFJointState();
192192

0 commit comments

Comments
 (0)