Skip to content

Commit d2d311e

Browse files
committed
changed published ros msg fields
1 parent c3790b1 commit d2d311e

File tree

1 file changed

+15
-12
lines changed

1 file changed

+15
-12
lines changed

rb_ws/src/buggy/buggy/buggy_state_converter.py

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -74,13 +74,14 @@ def convert_SC_state(self, msg):
7474
yaw = self.quaternion_to_yaw(qx, qy, qz, qw)
7575
converted_msg.pose.pose.orientation.x = yaw
7676
# ignored:
77-
# converted_msg.pose.pose.orientation.y = qy
78-
# converted_msg.pose.pose.orientation.z = qz
79-
# converted_msg.pose.pose.orientation.w = qw
77+
converted_msg.pose.pose.orientation.y = 0.0
78+
converted_msg.pose.pose.orientation.z = 0.0
79+
converted_msg.pose.pose.orientation.w = 0.0
8080

8181
# ---- 3. Copy Covariances (Unchanged) ----
82-
converted_msg.pose.covariance = msg.pose.covariance
83-
converted_msg.twist.covariance = msg.twist.covariance
82+
# TODO: check whether covariances should be copied over or not sent at all
83+
# converted_msg.pose.covariance = msg.pose.covariance
84+
# converted_msg.twist.covariance = msg.twist.covariance
8485

8586
# ---- 4. Copy Linear Velocities ----
8687
converted_msg.twist.twist.linear.x = msg.twist.twist.linear.x # m/s in x-direction
@@ -107,16 +108,17 @@ def convert_NAND_state(self, msg):
107108
# ---- 2. Orientation in Radians with 0 at East ----
108109
converted_msg.pose.pose.orientation.x = msg.pose.pose.orientation.x
109110
# ignored:
110-
# converted_msg.pose.pose.orientation.y = msg.pose.pose.orientation.y
111-
# converted_msg.pose.pose.orientation.z = msg.pose.pose.orientation.z
112-
# converted_msg.pose.pose.orientation.w = msg.pose.pose.orientation.w
111+
converted_msg.pose.pose.orientation.y = 0.0
112+
converted_msg.pose.pose.orientation.z = 0.0
113+
converted_msg.pose.pose.orientation.w = 0.0
113114

114115
# ---- 3. Copy Covariances (Unchanged) ----
115-
converted_msg.pose.covariance = msg.pose.covariance
116-
converted_msg.twist.covariance = msg.twist.covariance
116+
# TODO: check whether covariances should be copied over or not sent at all
117+
# converted_msg.pose.covariance = msg.pose.covariance
118+
# converted_msg.twist.covariance = msg.twist.covariance
117119

118120
# ---- 4. Copy Linear Velocities ----
119-
# CHECK: ROS serial translator node must change scalar speed to velocity x/y components before pushing to raw_state
121+
# TODO: check that ROS serial translator node changes scalar speed to velocity x/y components before pushing to raw_state
120122
converted_msg.twist.twist.linear.x = msg.twist.twist.linear.x # m/s in x-direction
121123
converted_msg.twist.twist.linear.y = msg.twist.twist.linear.y # m/s in y-direction
122124
converted_msg.twist.twist.linear.z = msg.twist.twist.linear.z # Keep original Z velocity (??)
@@ -131,7 +133,8 @@ def convert_NAND_state(self, msg):
131133
def quaternion_to_yaw(self, qx, qy, qz, qw):
132134
"""Convert a quaternion to yaw (heading) in radians."""
133135
siny_cosp = 2.0 * (qw * qz + qx * qy)
134-
cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz)
136+
cosy_cosp = 1.0 - 2.0 * (qy * qy + qz * qz) # assumes quaternion is normalized, should be true in ROS,
137+
# else use (qw * qw + qx * qx - qy * qy - qz * qz)
135138
return np.arctan2(siny_cosp, cosy_cosp)
136139

137140

0 commit comments

Comments
 (0)