Skip to content

Commit

Permalink
fix(moveit_server): fix add_plane service (#189)
Browse files Browse the repository at this point in the history
This commit ensures that the moveit server `add_plane` service does not
crash when no normal is given.
  • Loading branch information
rickstaa authored Nov 27, 2023
1 parent a03b978 commit 424fd4e
Show file tree
Hide file tree
Showing 2 changed files with 56 additions and 14 deletions.
46 changes: 46 additions & 0 deletions panda_gazebo/src/panda_gazebo/common/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -429,6 +429,52 @@ def normalize_quaternion(quaternion):
return quaternion


def vector_norm(vector):
"""Calculates the norm of a vector.
Args:
vector (union[list, tuple, np.array]): A vector.
Returns:
float: The norm of the vector.
Raises:
TypeError: If vector is not of type list or tuple.
"""
if not isinstance(vector, (list, tuple, np.ndarray)):
raise TypeError("vector must be of type list, tuple or numpy array")

vector = np.array(vector)
return np.linalg.norm(vector)


def normalize_vector(vector, force=True):
"""Normalizes a given vector.
Args:
vector (union[list, tuple]): A vector.
force (bool): Whether to force the vector to have a unit length if the norm is
zero. Defaults to ``True``.
Returns:
list: The normalized vector.
Raises:
TypeError: If vector is not of type list or tuple.
"""
if not isinstance(vector, (list, tuple, np.ndarray)):
raise TypeError("vector must be of type list or tuple or numpy array")

vector = np.array(vector)
norm = vector_norm(vector)
if norm == 0:
if force:
return [0.0, 0.0, 1.0]
rospy.logwarn("Vector could not be normalized since the norm is zero.")
return list(vector)
return list(vector / norm)


def ros_exit_gracefully(shutdown_msg=None, exit_code=0):
"""Shuts down the ROS node wait until it is shutdown and exits the script.
Expand Down
24 changes: 10 additions & 14 deletions panda_gazebo/src/panda_gazebo/core/moveit_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
quaternion_norm,
ros_exit_gracefully,
translate_moveit_error_code,
normalize_vector,
)
from panda_gazebo.exceptions import InputMessageInvalidError
from panda_gazebo.srv import (
Expand Down Expand Up @@ -1884,30 +1885,25 @@ def _scene_add_plane_callback(self, add_plane_req):
Returns:
bool: Whether the plane was successfully added.
"""
pose_header = Header(
frame_id=add_plane_req.frame_id if add_plane_req.frame_id else "world"
)
pose_header = Header(frame_id=add_plane_req.frame_id or "world")
plane_pose = Pose(
position=add_plane_req.pose.position,
orientation=normalize_quaternion(add_plane_req.pose.orientation),
orientation=add_plane_req.pose.orientation,
)
pose_stamped = PoseStamped(header=pose_header, pose=plane_pose)

# Send request.
resp = AddPlaneResponse()
try:
self.scene.add_plane(
add_plane_req.name if add_plane_req.name else "plane",
PoseStamped(header=pose_header, pose=plane_pose)
if add_plane_req.pose
else PoseStamped(
header=pose_header, pose=Pose(orientation=Quaternion(0, 0, 0, 1))
),
normal=add_plane_req.normal if add_plane_req.normal else (0, 0, 1),
offset=add_plane_req.offset if add_plane_req.offset else 0,
add_plane_req.name or "plane",
pose_stamped,
normal=normalize_vector(add_plane_req.normal, force=True),
offset=add_plane_req.offset,
)
except Exception:
except Exception as e:
resp.success = False
resp.message = "Plane could not be added"
resp.message = "Plane could not be added because: %s" % e
return resp

# Return response.
Expand Down

0 comments on commit 424fd4e

Please sign in to comment.