37 #include <moveit_msgs/msg/move_it_error_codes.hpp>
58 explicit operator bool()
const
60 return val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
79 switch (error_code.val)
81 case moveit::core::MoveItErrorCode::SUCCESS:
82 return std::string(
"SUCCESS");
83 case moveit::core::MoveItErrorCode::FAILURE:
84 return std::string(
"FAILURE");
85 case moveit::core::MoveItErrorCode::PLANNING_FAILED:
86 return std::string(
"PLANNING_FAILED");
87 case moveit::core::MoveItErrorCode::INVALID_MOTION_PLAN:
88 return std::string(
"INVALID_MOTION_PLAN");
89 case moveit::core::MoveItErrorCode::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE:
90 return std::string(
"MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE");
91 case moveit::core::MoveItErrorCode::CONTROL_FAILED:
92 return std::string(
"CONTROL_FAILED");
93 case moveit::core::MoveItErrorCode::UNABLE_TO_AQUIRE_SENSOR_DATA:
94 return std::string(
"UNABLE_TO_AQUIRE_SENSOR_DATA");
95 case moveit::core::MoveItErrorCode::TIMED_OUT:
96 return std::string(
"TIMED_OUT");
97 case moveit::core::MoveItErrorCode::PREEMPTED:
98 return std::string(
"PREEMPTED");
99 case moveit::core::MoveItErrorCode::START_STATE_IN_COLLISION:
100 return std::string(
"START_STATE_IN_COLLISION");
101 case moveit::core::MoveItErrorCode::START_STATE_VIOLATES_PATH_CONSTRAINTS:
102 return std::string(
"START_STATE_VIOLATES_PATH_CONSTRAINTS");
103 case moveit::core::MoveItErrorCode::START_STATE_INVALID:
104 return std::string(
"START_STATE_INVALID");
105 case moveit::core::MoveItErrorCode::GOAL_IN_COLLISION:
106 return std::string(
"GOAL_IN_COLLISION");
107 case moveit::core::MoveItErrorCode::GOAL_VIOLATES_PATH_CONSTRAINTS:
108 return std::string(
"GOAL_VIOLATES_PATH_CONSTRAINTS");
109 case moveit::core::MoveItErrorCode::GOAL_CONSTRAINTS_VIOLATED:
110 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");
115 case moveit::core::MoveItErrorCode::INVALID_GROUP_NAME:
116 return std::string(
"INVALID_GROUP_NAME");
117 case moveit::core::MoveItErrorCode::INVALID_GOAL_CONSTRAINTS:
118 return std::string(
"INVALID_GOAL_CONSTRAINTS");
119 case moveit::core::MoveItErrorCode::INVALID_ROBOT_STATE:
120 return std::string(
"INVALID_ROBOT_STATE");
121 case moveit::core::MoveItErrorCode::INVALID_LINK_NAME:
122 return std::string(
"INVALID_LINK_NAME");
123 case moveit::core::MoveItErrorCode::INVALID_OBJECT_NAME:
124 return std::string(
"INVALID_OBJECT_NAME");
125 case moveit::core::MoveItErrorCode::FRAME_TRANSFORM_FAILURE:
126 return std::string(
"FRAME_TRANSFORM_FAILURE");
127 case moveit::core::MoveItErrorCode::COLLISION_CHECKING_UNAVAILABLE:
128 return std::string(
"COLLISION_CHECKING_UNAVAILABLE");
129 case moveit::core::MoveItErrorCode::ROBOT_STATE_STALE:
130 return std::string(
"ROBOT_STATE_STALE");
131 case moveit::core::MoveItErrorCode::SENSOR_INFO_STALE:
132 return std::string(
"SENSOR_INFO_STALE");
133 case moveit::core::MoveItErrorCode::COMMUNICATION_FAILURE:
134 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");
139 case moveit::core::MoveItErrorCode::NO_IK_SOLUTION:
140 return std::string(
"NO_IK_SOLUTION");
142 return std::string(
"Unrecognized MoveItErrorCode. This should never happen!");
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
bool operator!=(const int c) const
MoveItErrorCode(const moveit_msgs::msg::MoveItErrorCodes &code)
bool operator==(const int c) const
MoveItErrorCode(int code=0)
std::string error_code_to_string(MoveItErrorCode error_code)
Convenience function to translated error message into string.
Main namespace for MoveIt.