Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
49 changes: 0 additions & 49 deletions dimos/msgs/geometry_msgs/Pose.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,18 +20,6 @@
Pose as LCMPose,
Transform as LCMTransform,
)

try:
from geometry_msgs.msg import ( # type: ignore[attr-defined]
Point as ROSPoint,
Pose as ROSPose,
Quaternion as ROSQuaternion,
)
except ImportError:
ROSPose = None # type: ignore[assignment, misc]
ROSPoint = None # type: ignore[assignment, misc]
ROSQuaternion = None # type: ignore[assignment, misc]

from plum import dispatch

from dimos.msgs.geometry_msgs.Quaternion import Quaternion, QuaternionConvertable
Expand Down Expand Up @@ -235,43 +223,6 @@ def __sub__(self, other: Pose) -> Pose:
delta_orientation = self.orientation * other.orientation.inverse()
return Pose(delta_position, delta_orientation)

@classmethod
def from_ros_msg(cls, ros_msg: ROSPose) -> Pose:
"""Create a Pose from a ROS geometry_msgs/Pose message.

Args:
ros_msg: ROS Pose message

Returns:
Pose instance
"""
position = Vector3(ros_msg.position.x, ros_msg.position.y, ros_msg.position.z)
orientation = Quaternion(
ros_msg.orientation.x,
ros_msg.orientation.y,
ros_msg.orientation.z,
ros_msg.orientation.w,
)
return cls(position, orientation)

def to_ros_msg(self) -> ROSPose:
"""Convert to a ROS geometry_msgs/Pose message.

Returns:
ROS Pose message
"""
ros_msg = ROSPose() # type: ignore[no-untyped-call]
ros_msg.position = ROSPoint( # type: ignore[no-untyped-call]
x=float(self.position.x), y=float(self.position.y), z=float(self.position.z)
)
ros_msg.orientation = ROSQuaternion( # type: ignore[no-untyped-call]
x=float(self.orientation.x),
y=float(self.orientation.y),
z=float(self.orientation.z),
w=float(self.orientation.w),
)
return ros_msg


@dispatch
def to_pose(value: Pose) -> Pose:
Expand Down
48 changes: 0 additions & 48 deletions dimos/msgs/geometry_msgs/PoseStamped.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,6 @@
from rerun._baseclasses import Archetype

from dimos_lcm.geometry_msgs import PoseStamped as LCMPoseStamped

try:
from geometry_msgs.msg import ( # type: ignore[attr-defined]
PoseStamped as ROSPoseStamped,
)
except ImportError:
ROSPoseStamped = None # type: ignore[assignment, misc]
from plum import dispatch

from dimos.msgs.geometry_msgs.Pose import Pose
Expand Down Expand Up @@ -145,44 +138,3 @@ def find_transform(self, other: PoseStamped) -> Transform:
translation=local_translation,
rotation=relative_rotation,
)

@classmethod
def from_ros_msg(cls, ros_msg: ROSPoseStamped) -> PoseStamped: # type: ignore[override]
"""Create a PoseStamped from a ROS geometry_msgs/PoseStamped message.

Args:
ros_msg: ROS PoseStamped message

Returns:
PoseStamped instance
"""
# Convert timestamp from ROS header
ts = ros_msg.header.stamp.sec + (ros_msg.header.stamp.nanosec / 1_000_000_000)

# Convert pose
pose = Pose.from_ros_msg(ros_msg.pose)

return cls(
ts=ts,
frame_id=ros_msg.header.frame_id,
position=pose.position,
orientation=pose.orientation,
)

def to_ros_msg(self) -> ROSPoseStamped: # type: ignore[override]
"""Convert to a ROS geometry_msgs/PoseStamped message.

Returns:
ROS PoseStamped message
"""
ros_msg = ROSPoseStamped() # type: ignore[no-untyped-call]

# Set header
ros_msg.header.frame_id = self.frame_id
ros_msg.header.stamp.sec = int(self.ts)
ros_msg.header.stamp.nanosec = int((self.ts - int(self.ts)) * 1_000_000_000)

# Set pose
ros_msg.pose = Pose.to_ros_msg(self)

return ros_msg
37 changes: 0 additions & 37 deletions dimos/msgs/geometry_msgs/PoseWithCovariance.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,6 @@
import numpy as np
from plum import dispatch

try:
from geometry_msgs.msg import ( # type: ignore[attr-defined]
PoseWithCovariance as ROSPoseWithCovariance,
)
except ImportError:
ROSPoseWithCovariance = None # type: ignore[assignment, misc]

from dimos.msgs.geometry_msgs.Pose import Pose, PoseConvertable

if TYPE_CHECKING:
Expand Down Expand Up @@ -201,33 +194,3 @@ def lcm_decode(cls, data: bytes) -> PoseWithCovariance:
],
)
return cls(pose, lcm_msg.covariance)

@classmethod
def from_ros_msg(cls, ros_msg: ROSPoseWithCovariance) -> PoseWithCovariance:
"""Create a PoseWithCovariance from a ROS geometry_msgs/PoseWithCovariance message.

Args:
ros_msg: ROS PoseWithCovariance message

Returns:
PoseWithCovariance instance
"""

pose = Pose.from_ros_msg(ros_msg.pose)
return cls(pose, list(ros_msg.covariance))

def to_ros_msg(self) -> ROSPoseWithCovariance:
"""Convert to a ROS geometry_msgs/PoseWithCovariance message.

Returns:
ROS PoseWithCovariance message
"""

ros_msg = ROSPoseWithCovariance() # type: ignore[no-untyped-call]
ros_msg.pose = self.pose.to_ros_msg()
# ROS expects list, not numpy array
if isinstance(self.covariance, np.ndarray): # type: ignore[has-type]
ros_msg.covariance = self.covariance.tolist() # type: ignore[has-type]
else:
ros_msg.covariance = list(self.covariance) # type: ignore[has-type]
return ros_msg
55 changes: 0 additions & 55 deletions dimos/msgs/geometry_msgs/PoseWithCovarianceStamped.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,6 @@
import numpy as np
from plum import dispatch

try:
from geometry_msgs.msg import ( # type: ignore[attr-defined]
PoseWithCovarianceStamped as ROSPoseWithCovarianceStamped,
)
except ImportError:
ROSPoseWithCovarianceStamped = None # type: ignore[assignment, misc]

from dimos.msgs.geometry_msgs.Pose import Pose, PoseConvertable
from dimos.msgs.geometry_msgs.PoseWithCovariance import PoseWithCovariance
from dimos.types.timestamped import Timestamped
Expand Down Expand Up @@ -115,51 +108,3 @@ def __str__(self) -> str:
f"euler=[{self.roll:.3f}, {self.pitch:.3f}, {self.yaw:.3f}], "
f"cov_trace={np.trace(self.covariance_matrix):.3f})"
)

@classmethod
def from_ros_msg(cls, ros_msg: ROSPoseWithCovarianceStamped) -> PoseWithCovarianceStamped: # type: ignore[override]
"""Create a PoseWithCovarianceStamped from a ROS geometry_msgs/PoseWithCovarianceStamped message.

Args:
ros_msg: ROS PoseWithCovarianceStamped message

Returns:
PoseWithCovarianceStamped instance
"""

# Convert timestamp from ROS header
ts = ros_msg.header.stamp.sec + (ros_msg.header.stamp.nanosec / 1_000_000_000)

# Convert pose with covariance
pose_with_cov = PoseWithCovariance.from_ros_msg(ros_msg.pose)

return cls(
ts=ts,
frame_id=ros_msg.header.frame_id,
pose=pose_with_cov.pose,
covariance=pose_with_cov.covariance, # type: ignore[has-type]
)

def to_ros_msg(self) -> ROSPoseWithCovarianceStamped: # type: ignore[override]
"""Convert to a ROS geometry_msgs/PoseWithCovarianceStamped message.

Returns:
ROS PoseWithCovarianceStamped message
"""

ros_msg = ROSPoseWithCovarianceStamped() # type: ignore[no-untyped-call]

# Set header
ros_msg.header.frame_id = self.frame_id
ros_msg.header.stamp.sec = int(self.ts)
ros_msg.header.stamp.nanosec = int((self.ts - int(self.ts)) * 1_000_000_000)

# Set pose with covariance
ros_msg.pose.pose = self.pose.to_ros_msg()
# ROS expects list, not numpy array
if isinstance(self.covariance, np.ndarray): # type: ignore[has-type]
ros_msg.pose.covariance = self.covariance.tolist() # type: ignore[has-type]
else:
ros_msg.pose.covariance = list(self.covariance) # type: ignore[has-type]

return ros_msg
77 changes: 0 additions & 77 deletions dimos/msgs/geometry_msgs/Transform.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,19 +25,6 @@
TransformStamped as LCMTransformStamped,
)

try:
from geometry_msgs.msg import ( # type: ignore[attr-defined]
Quaternion as ROSQuaternion,
Transform as ROSTransform,
TransformStamped as ROSTransformStamped,
Vector3 as ROSVector3,
)
except ImportError:
ROSTransformStamped = None # type: ignore[assignment, misc]
ROSTransform = None # type: ignore[assignment, misc]
ROSVector3 = None # type: ignore[assignment, misc]
ROSQuaternion = None # type: ignore[assignment, misc]

from dimos.msgs.geometry_msgs.Quaternion import Quaternion
from dimos.msgs.geometry_msgs.Vector3 import Vector3
from dimos.msgs.std_msgs import Header
Expand Down Expand Up @@ -168,70 +155,6 @@ def inverse(self) -> Transform:
ts=self.ts,
)

@classmethod
def from_ros_transform_stamped(cls, ros_msg: ROSTransformStamped) -> Transform:
"""Create a Transform from a ROS geometry_msgs/TransformStamped message.

Args:
ros_msg: ROS TransformStamped message

Returns:
Transform instance
"""

# Convert timestamp
ts = ros_msg.header.stamp.sec + (ros_msg.header.stamp.nanosec / 1_000_000_000)

# Convert translation
translation = Vector3(
ros_msg.transform.translation.x,
ros_msg.transform.translation.y,
ros_msg.transform.translation.z,
)

# Convert rotation
rotation = Quaternion(
ros_msg.transform.rotation.x,
ros_msg.transform.rotation.y,
ros_msg.transform.rotation.z,
ros_msg.transform.rotation.w,
)

return cls(
translation=translation,
rotation=rotation,
frame_id=ros_msg.header.frame_id,
child_frame_id=ros_msg.child_frame_id,
ts=ts,
)

def to_ros_transform_stamped(self) -> ROSTransformStamped:
"""Convert to a ROS geometry_msgs/TransformStamped message.

Returns:
ROS TransformStamped message
"""

ros_msg = ROSTransformStamped() # type: ignore[no-untyped-call]

# Set header
ros_msg.header.frame_id = self.frame_id
ros_msg.header.stamp.sec = int(self.ts)
ros_msg.header.stamp.nanosec = int((self.ts - int(self.ts)) * 1_000_000_000)

# Set child frame
ros_msg.child_frame_id = self.child_frame_id

# Set transform
ros_msg.transform.translation = ROSVector3( # type: ignore[no-untyped-call]
x=self.translation.x, y=self.translation.y, z=self.translation.z
)
ros_msg.transform.rotation = ROSQuaternion( # type: ignore[no-untyped-call]
x=self.rotation.x, y=self.rotation.y, z=self.rotation.z, w=self.rotation.w
)

return ros_msg

def __neg__(self) -> Transform:
"""Unary minus operator returns the inverse transform."""
return self.inverse()
Expand Down
36 changes: 0 additions & 36 deletions dimos/msgs/geometry_msgs/Twist.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,6 @@
from dimos_lcm.geometry_msgs import Twist as LCMTwist
from plum import dispatch

try:
from geometry_msgs.msg import ( # type: ignore[attr-defined]
Twist as ROSTwist,
Vector3 as ROSVector3,
)
except ImportError:
ROSTwist = None # type: ignore[assignment, misc]
ROSVector3 = None # type: ignore[assignment, misc]

# Import Quaternion at runtime for beartype compatibility
# (beartype needs to resolve forward references at runtime)
from dimos.msgs.geometry_msgs.Quaternion import Quaternion
Expand Down Expand Up @@ -108,32 +99,5 @@ def __bool__(self) -> bool:
"""
return not self.is_zero()

@classmethod
def from_ros_msg(cls, ros_msg: ROSTwist) -> Twist:
"""Create a Twist from a ROS geometry_msgs/Twist message.

Args:
ros_msg: ROS Twist message

Returns:
Twist instance
"""

linear = Vector3(ros_msg.linear.x, ros_msg.linear.y, ros_msg.linear.z)
angular = Vector3(ros_msg.angular.x, ros_msg.angular.y, ros_msg.angular.z)
return cls(linear, angular)

def to_ros_msg(self) -> ROSTwist:
"""Convert to a ROS geometry_msgs/Twist message.

Returns:
ROS Twist message
"""

ros_msg = ROSTwist() # type: ignore[no-untyped-call]
ros_msg.linear = ROSVector3(x=self.linear.x, y=self.linear.y, z=self.linear.z) # type: ignore[no-untyped-call]
ros_msg.angular = ROSVector3(x=self.angular.x, y=self.angular.y, z=self.angular.z) # type: ignore[no-untyped-call]
return ros_msg


__all__ = ["Quaternion", "Twist"]
Loading
Loading