Skip to content

Commit

Permalink
MGI: use new COMMUNICATION_FAILURE error code
Browse files Browse the repository at this point in the history
  • Loading branch information
v4hn committed May 11, 2020
1 parent 3d6274b commit 2b38e26
Showing 1 changed file with 6 additions and 6 deletions.
Expand Up @@ -643,7 +643,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
if (!place_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "place action server not connected");
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::FAILURE);
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::COMMUNICATION_FAILURE);
}

place_action_client_->sendGoal(goal);
Expand Down Expand Up @@ -674,7 +674,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
if (!pick_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "pick action server not connected");
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::FAILURE);
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::COMMUNICATION_FAILURE);
}

pick_action_client_->sendGoal(goal);
Expand Down Expand Up @@ -722,7 +722,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
<< GRASP_PLANNING_SERVICE_NAME
<< "' is not available."
" This has to be implemented and started separately.");
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::FAILURE);
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::COMMUNICATION_FAILURE);
}

moveit_msgs::GraspPlanning::Request request;
Expand Down Expand Up @@ -753,7 +753,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
if (!move_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "move action server not connected");
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::FAILURE);
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::COMMUNICATION_FAILURE);
}

moveit_msgs::MoveGroupGoal goal;
Expand Down Expand Up @@ -794,7 +794,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
if (!move_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "move action server not connected");
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::FAILURE);
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::COMMUNICATION_FAILURE);
}

moveit_msgs::MoveGroupGoal goal;
Expand Down Expand Up @@ -839,7 +839,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
if (!execute_action_client_->isServerConnected())
{
ROS_WARN_STREAM_NAMED(LOGNAME, "execute action server not connected");
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::FAILURE);
return MoveItErrorCode(moveit_msgs::MoveItErrorCodes::COMMUNICATION_FAILURE);
}

moveit_msgs::ExecuteTrajectoryGoal goal;
Expand Down

0 comments on commit 2b38e26

Please sign in to comment.