Skip to content
This repository was archived by the owner on Nov 13, 2017. It is now read-only.

Commit 5a950c8

Browse files
committed
reformatting
1 parent 34d030e commit 5a950c8

File tree

1 file changed

+5
-7
lines changed

1 file changed

+5
-7
lines changed

move_group/src/default_capabilities/execute_service_capability.cpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -70,14 +70,12 @@ bool move_group::MoveGroupExecuteService::executeTrajectoryService(moveit_msgs::
7070
moveit_controller_manager::ExecutionStatus es = context_->trajectory_execution_manager_->waitForExecution();
7171
if (es == moveit_controller_manager::ExecutionStatus::SUCCEEDED)
7272
res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
73+
else if (es == moveit_controller_manager::ExecutionStatus::PREEMPTED)
74+
res.error_code.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
75+
else if (es == moveit_controller_manager::ExecutionStatus::TIMED_OUT)
76+
res.error_code.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
7377
else
74-
if (es == moveit_controller_manager::ExecutionStatus::PREEMPTED)
75-
res.error_code.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
76-
else
77-
if (es == moveit_controller_manager::ExecutionStatus::TIMED_OUT)
78-
res.error_code.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
79-
else
80-
res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
78+
res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
8179
// wait for all planning scene updates to be processed
8280
context_->planning_scene_monitor_->syncUpdates(ros::Time::now());
8381
ROS_INFO_STREAM("Execution completed: " << es.asString());

0 commit comments

Comments
 (0)