1
1
import numpy as np
2
+ import scipy
2
3
import geometry_msgs .msg
3
4
import rospy
4
5
import std_msgs .msg
5
6
6
- from moma_utils .spatial import Rotation , Transform
7
+ from moma_utils .transform import Rotation , Transform
7
8
8
9
9
- def from_point_msg (msg ) :
10
+ def from_point_msg (msg : geometry_msgs . msg . Point ) -> np . array :
10
11
return np .r_ [msg .x , msg .y , msg .z ]
11
12
12
13
13
- def from_quat_msg (msg ) :
14
+ def from_quat_msg (msg : geometry_msgs . msg . Quaternion ) -> Rotation :
14
15
return Rotation .from_quat ([msg .x , msg .y , msg .z , msg .w ])
15
16
16
17
17
- def from_pose_msg (msg ) :
18
+ def from_pose_msg (msg : geometry_msgs . msg . Pose ) -> Transform :
18
19
position = from_point_msg (msg .position )
19
20
orientation = from_quat_msg (msg .orientation )
20
21
return Transform (orientation , position )
21
22
22
23
23
- def from_transform_msg (msg ) :
24
+ def from_transform_msg (msg : geometry_msgs . msg . Transform ) -> Transform :
24
25
translation = from_vector3_msg (msg .translation )
25
26
rotation = from_quat_msg (msg .rotation )
26
27
return Transform (rotation , translation )
27
28
28
29
29
- def from_vector3_msg (msg ) :
30
+ def from_vector3_msg (msg : geometry_msgs . msg . Vector3 ) -> np . array :
30
31
return np .r_ [msg .x , msg .y , msg .z ]
31
32
32
33
33
- def to_color_msg (color ) :
34
+ def to_color_msg (color : list ) -> std_msgs . msg . ColorRGBA :
34
35
msg = std_msgs .msg .ColorRGBA ()
35
36
msg .r = color [0 ]
36
37
msg .g = color [1 ]
@@ -39,29 +40,29 @@ def to_color_msg(color):
39
40
return msg
40
41
41
42
42
- def to_point_msg (point ) :
43
+ def to_point_msg (point : np . array ) -> geometry_msgs . msg . Point :
43
44
msg = geometry_msgs .msg .Point ()
44
45
msg .x = point [0 ]
45
46
msg .y = point [1 ]
46
47
msg .z = point [2 ]
47
48
return msg
48
49
49
50
50
- def to_pose_msg (transform ) :
51
+ def to_pose_msg (transform : Transform ) -> geometry_msgs . msg . Pose :
51
52
msg = geometry_msgs .msg .Pose ()
52
53
msg .position = to_point_msg (transform .translation )
53
54
msg .orientation = to_quat_msg (transform .rotation )
54
55
return msg
55
56
56
57
57
- def to_pose_stamped_msg (transform , frame_id ) :
58
+ def to_pose_stamped_msg (transform : Transform , frame_id : str ) -> geometry_msgs . msg . PoseStamped :
58
59
msg = geometry_msgs .msg .PoseStamped ()
59
60
msg .header .frame_id = frame_id
60
61
msg .pose = to_pose_msg (transform )
61
62
return msg
62
63
63
64
64
- def to_quat_msg (orientation ) :
65
+ def to_quat_msg (orientation : scipy . spatial . transform . Rotation ) -> geometry_msgs . msg . Quaternion :
65
66
quat = orientation .as_quat ()
66
67
msg = geometry_msgs .msg .Quaternion ()
67
68
msg .x = quat [0 ]
@@ -71,22 +72,22 @@ def to_quat_msg(orientation):
71
72
return msg
72
73
73
74
74
- def to_transform_msg (transform ) :
75
+ def to_transform_msg (transform : Transform ) -> geometry_msgs . msg . Transform :
75
76
msg = geometry_msgs .msg .Transform ()
76
77
msg .translation = to_vector3_msg (transform .translation )
77
78
msg .rotation = to_quat_msg (transform .rotation )
78
79
return msg
79
80
80
81
81
- def to_vector3_msg (vector3 ) :
82
+ def to_vector3_msg (vector3 : list ) -> geometry_msgs . msg . Vector3 :
82
83
msg = geometry_msgs .msg .Vector3 ()
83
84
msg .x = vector3 [0 ]
84
85
msg .y = vector3 [1 ]
85
86
msg .z = vector3 [2 ]
86
87
return msg
87
88
88
89
89
- def waypoint_to_pose_msg (waypoint ) :
90
+ def waypoint_to_pose_msg (waypoint : list ) -> geometry_msgs . msg . PoseStamped :
90
91
"""Converts 2D waypoint to a PoseStamped message.
91
92
92
93
Arguments:
0 commit comments