Skip to content

Commit 4c8e353

Browse files
Update moveit::core::error_msg_to_string (#2689)
1 parent 65970f0 commit 4c8e353

File tree

1 file changed

+12
-5
lines changed

1 file changed

+12
-5
lines changed

moveit_core/utils/include/moveit/utils/moveit_error_code.h

+12-5
Original file line numberDiff line numberDiff line change
@@ -47,11 +47,7 @@ namespace core
4747
class MoveItErrorCode : public moveit_msgs::msg::MoveItErrorCodes
4848
{
4949
public:
50-
MoveItErrorCode()
51-
{
52-
val = 0;
53-
}
54-
MoveItErrorCode(int code)
50+
MoveItErrorCode(int code = 0)
5551
{
5652
val = code;
5753
}
@@ -104,12 +100,18 @@ inline std::string error_code_to_string(MoveItErrorCode error_code)
104100
return std::string("START_STATE_IN_COLLISION");
105101
case moveit::core::MoveItErrorCode::START_STATE_VIOLATES_PATH_CONSTRAINTS:
106102
return std::string("START_STATE_VIOLATES_PATH_CONSTRAINTS");
103+
case moveit::core::MoveItErrorCode::START_STATE_INVALID:
104+
return std::string("START_STATE_INVALID");
107105
case moveit::core::MoveItErrorCode::GOAL_IN_COLLISION:
108106
return std::string("GOAL_IN_COLLISION");
109107
case moveit::core::MoveItErrorCode::GOAL_VIOLATES_PATH_CONSTRAINTS:
110108
return std::string("GOAL_VIOLATES_PATH_CONSTRAINTS");
111109
case moveit::core::MoveItErrorCode::GOAL_CONSTRAINTS_VIOLATED:
112110
return std::string("GOAL_CONSTRAINTS_VIOLATED");
111+
case moveit::core::MoveItErrorCode::GOAL_STATE_INVALID:
112+
return std::string("GOAL_STATE_INVALID");
113+
case moveit::core::MoveItErrorCode::UNRECOGNIZED_GOAL_TYPE:
114+
return std::string("UNRECOGNIZED_GOAL_TYPE");
113115
case moveit::core::MoveItErrorCode::INVALID_GROUP_NAME:
114116
return std::string("INVALID_GROUP_NAME");
115117
case moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS:
@@ -130,9 +132,14 @@ inline std::string error_code_to_string(MoveItErrorCode error_code)
130132
return std::string("SENSOR_INFO_STALE");
131133
case moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE:
132134
return std::string("COMMUNICATION_FAILURE");
135+
case moveit::core::MoveItErrorCode::CRASH:
136+
return std::string("CRASH");
137+
case moveit::core::MoveItErrorCode::ABORT:
138+
return std::string("ABORT");
133139
case moveit::core::MoveItErrorCode::NO_IK_SOLUTION:
134140
return std::string("NO_IK_SOLUTION");
135141
}
142+
return std::string("Unrecognized MoveItErrorCode. This should never happen!");
136143
}
137144

138145
} // namespace core

0 commit comments

Comments
 (0)