Skip to content

Commit

Permalink
Feature/string error codes (#83)
Browse files Browse the repository at this point in the history
* feat: add method for getting the string value of error codes

* feat: update logging to print string error codes

* feat: update logging to print string error codes for gripper

* rename get_enum_string -> enum_to_str and add type hints

* formatting: make pre-commit happy

* pre-commit: fix import order
  • Loading branch information
blooop authored Feb 19, 2025
1 parent 640bb85 commit b8dde85
Show file tree
Hide file tree
Showing 3 changed files with 33 additions and 6 deletions.
4 changes: 3 additions & 1 deletion pymoveit2/gripper_command.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
)
from sensor_msgs.msg import JointState

from pymoveit2.utils import enum_to_str


class GripperCommand:
"""
Expand Down Expand Up @@ -289,7 +291,7 @@ def __response_callback_gripper_command(self, response):
def __result_callback_gripper_command(self, res):
if res.result().status != GoalStatus.STATUS_SUCCEEDED:
self._node.get_logger().error(
f"Action '{self.__gripper_command_action_client._action_name}' was unsuccessful: {res.result().status}"
f"Action '{self.__gripper_command_action_client._action_name}' was unsuccessful: {enum_to_str(GoalStatus, res.result().status)}"
)

self.__is_executing = False
Expand Down
12 changes: 7 additions & 5 deletions pymoveit2/moveit2.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@
from std_msgs.msg import Header, String
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint

from pymoveit2.utils import enum_to_str


class MoveIt2State(Enum):
"""
Expand Down Expand Up @@ -703,7 +705,7 @@ def get_trajectory(
return None
else:
self._node.get_logger().warn(
f"Planning failed! Error code: {res.error_code.val}."
f"Planning failed! Error code: {enum_to_str(MoveItErrorCodes, res.error_code.val)}"
)
return None

Expand All @@ -713,7 +715,7 @@ def get_trajectory(
return res.trajectory.joint_trajectory
else:
self._node.get_logger().warn(
f"Planning failed! Error code: {res.error_code.val}."
f"Planning failed! Error code: {enum_to_str(MoveItErrorCodes, res.error_code.val)}"
)
return None

Expand Down Expand Up @@ -1318,7 +1320,7 @@ def get_compute_ik_result(
return res.solution.joint_state
else:
self._node.get_logger().warn(
f"IK computation failed! Error code: {res.error_code.val}."
f"IK computation failed! Error code: {enum_to_str(MoveItErrorCodes, res.error_code.val)}"
)
return None

Expand Down Expand Up @@ -2110,7 +2112,7 @@ def __result_callback_move_action(self, res):
self.__execution_mutex.acquire()
if res.result().status != GoalStatus.STATUS_SUCCEEDED:
self._node.get_logger().warn(
f"Action '{self.__move_action_client._action_name}' was unsuccessful: {res.result().status}."
f"Action '{self.__move_action_client._action_name}' was unsuccessful: {enum_to_str(GoalStatus,res.result().status)}."
)
self.motion_suceeded = False
else:
Expand Down Expand Up @@ -2176,7 +2178,7 @@ def __result_callback_execute_trajectory(self, res):
self.__execution_mutex.acquire()
if res.result().status != GoalStatus.STATUS_SUCCEEDED:
self._node.get_logger().warn(
f"Action '{self._execute_trajectory_action_client._action_name}' was unsuccessful: {res.result().status}."
f"Action '{self._execute_trajectory_action_client._action_name}' was unsuccessful: {enum_to_str(GoalStatus,res.result().status)}."
)
self.motion_suceeded = False
else:
Expand Down
23 changes: 23 additions & 0 deletions pymoveit2/utils.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
from typing import Type


def enum_to_str(enum_class: Type, value: int) -> str:
"""Converts a ROS2 enum value to its string name.
Args:
enum_class: The ROS2 message class containing the enum constants.
value: The integer value of the enum.
Returns:
str: The name of the enum constant, or the value with "UNKNOWN NAME" if not found.
"""
mapping = {}
# Iterate over all attributes in the enum class
for attr_name in dir(enum_class):
# Consider only uppercase attributes (common convention for enums)
if attr_name.isupper():
attr_value = getattr(enum_class, attr_name)
# Check if the attribute is an integer (enum values are typically int)
if isinstance(attr_value, int):
mapping[attr_value] = attr_name
return mapping.get(value, f"{value} :UNKNOWN NAME")

0 comments on commit b8dde85

Please sign in to comment.