Skip to content

Commit 5c308d1

Browse files
remove underscore from public members in MotionPlanResponse (moveit#426)
Required to align with changes introduced by moveit/moveit2#1939 Co-authored-by: JafarAbdi <[email protected]>
1 parent 2938986 commit 5c308d1

File tree

3 files changed

+15
-15
lines changed

3 files changed

+15
-15
lines changed

capabilities/src/execute_task_solution_capability.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ void ExecuteTaskSolutionCapability::initialize() {
9999
}
100100

101101
void ExecuteTaskSolutionCapability::goalCallback(
102-
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>> goal_handle) {
102+
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& goal_handle) {
103103
auto result = std::make_shared<moveit_task_constructor_msgs::action::ExecuteTaskSolution::Result>();
104104

105105
const auto& goal = goal_handle->get_goal();
@@ -126,7 +126,7 @@ void ExecuteTaskSolutionCapability::goalCallback(
126126
}
127127

128128
rclcpp_action::CancelResponse ExecuteTaskSolutionCapability::preemptCallback(
129-
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>> /*goal_handle*/) {
129+
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& /*goal_handle*/) {
130130
if (context_->plan_execution_)
131131
context_->plan_execution_->stop();
132132
return rclcpp_action::CancelResponse::ACCEPT;
@@ -142,16 +142,16 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
142142
state = scene->getCurrentState();
143143
}
144144

145-
plan.plan_components_.reserve(solution.sub_trajectory.size());
145+
plan.plan_components.reserve(solution.sub_trajectory.size());
146146
for (size_t i = 0; i < solution.sub_trajectory.size(); ++i) {
147147
const moveit_task_constructor_msgs::msg::SubTrajectory& sub_traj = solution.sub_trajectory[i];
148148

149-
plan.plan_components_.emplace_back();
150-
plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components_.back();
149+
plan.plan_components.emplace_back();
150+
plan_execution::ExecutableTrajectory& exec_traj = plan.plan_components.back();
151151

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

156156
const moveit::core::JointModelGroup* group = nullptr;
157157
{
@@ -168,12 +168,12 @@ bool ExecuteTaskSolutionCapability::constructMotionPlan(const moveit_task_constr
168168
RCLCPP_DEBUG(LOGGER, "Using JointModelGroup '%s' for execution", group->getName().c_str());
169169
}
170170
}
171-
exec_traj.trajectory_ = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
172-
exec_traj.trajectory_->setRobotTrajectoryMsg(state, sub_traj.trajectory);
171+
exec_traj.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(model, group);
172+
exec_traj.trajectory->setRobotTrajectoryMsg(state, sub_traj.trajectory);
173173

174174
/* TODO add action feedback and markers */
175-
exec_traj.effect_on_success_ = [this, sub_traj,
176-
description](const plan_execution::ExecutableMotionPlan* /*plan*/) {
175+
exec_traj.effect_on_success = [this, sub_traj,
176+
description](const plan_execution::ExecutableMotionPlan* /*plan*/) {
177177
if (!moveit::core::isEmpty(sub_traj.scene_diff)) {
178178
RCLCPP_DEBUG_STREAM(LOGGER, "apply effect of " << description);
179179
return context_->planning_scene_monitor_->newPlanningSceneMessage(sub_traj.scene_diff);

capabilities/src/execute_task_solution_capability.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -63,14 +63,14 @@ class ExecuteTaskSolutionCapability : public MoveGroupCapability
6363
bool constructMotionPlan(const moveit_task_constructor_msgs::msg::Solution& solution,
6464
plan_execution::ExecutableMotionPlan& plan);
6565

66-
void goalCallback(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>> goal_handle);
66+
void goalCallback(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& goal_handle);
6767

6868
rclcpp_action::CancelResponse
69-
preemptCallback(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>> goal_handle);
69+
preemptCallback(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ExecuteTaskSolutionAction>>& goal_handle);
7070

7171
/** Always accept the goal */
7272
rclcpp_action::GoalResponse handleNewGoal(const rclcpp_action::GoalUUID& /*uuid*/,
73-
const ExecuteTaskSolutionAction::Goal::ConstSharedPtr /*goal*/) const {
73+
const ExecuteTaskSolutionAction::Goal::ConstSharedPtr& /*goal*/) const {
7474
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
7575
}
7676

core/src/solvers/pipeline_planner.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -180,7 +180,7 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from,
180180

181181
::planning_interface::MotionPlanResponse res;
182182
bool success = planner_->generatePlan(from, req, res);
183-
result = res.trajectory_;
183+
result = res.trajectory;
184184
return success;
185185
}
186186

@@ -205,7 +205,7 @@ bool PipelinePlanner::plan(const planning_scene::PlanningSceneConstPtr& from, co
205205

206206
::planning_interface::MotionPlanResponse res;
207207
bool success = planner_->generatePlan(from, req, res);
208-
result = res.trajectory_;
208+
result = res.trajectory;
209209
return success;
210210
}
211211
} // namespace solvers

0 commit comments

Comments
 (0)