Skip to content

Commit

Permalink
Fixed incorrect transformation in MainFramePublisher
Browse files Browse the repository at this point in the history
The hero frame was rotated 180 degrees from its true orientation.
The code publishing this hero frame was cleaned up, the bug fixed.
  • Loading branch information
vinzenzm committed Nov 24, 2024
1 parent dc831f6 commit 4ca5de6
Showing 1 changed file with 21 additions and 20 deletions.
41 changes: 21 additions & 20 deletions code/acting/src/acting/MainFramePublisher.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
#!/usr/bin/env python

from math import pi, cos, sin
import ros_compatibility as roscomp
import rospy
from geometry_msgs.msg import PoseStamped
Expand All @@ -9,6 +7,8 @@
from scipy.spatial.transform import Rotation as R
from std_msgs.msg import Float32

import numpy as np


class MainFramePublisher(CompatibleNode):

Expand Down Expand Up @@ -49,27 +49,28 @@ def loop(timer_event=None):
if self.current_pos is None:
# conversion only works if pos is known
return
rot = -self.current_heading
pos = [0, 0, 0]
pos[0] = (
cos(rot) * self.current_pos.pose.position.x
- sin(rot) * self.current_pos.pose.position.y
)
pos[1] = (
sin(rot) * self.current_pos.pose.position.x
+ cos(rot) * self.current_pos.pose.position.y

# The following converts the current_pos as well as the current_heading
# messages we receive into tf transforms.

position = np.array(
[
self.current_pos.pose.position.x,
self.current_pos.pose.position.y,
self.current_pos.pose.position.z,
]
)
pos[2] = -self.current_pos.pose.position.z
rot_quat = R.from_euler(
"xyz", [0, 0, -self.current_heading + pi], degrees=False
).as_quat()

rotation = R.from_euler("z", self.current_heading, degrees=False).as_quat()

# The position and rotation are "the hero frame in global coordinates"
# Therefore we publish the child hero with respect to the parent global
br.sendTransform(
pos,
rot_quat,
rospy.Time.now(),
"global",
"hero",
translation=position,
rotation=rotation,
time=rospy.Time.now(),
child="hero",
parent="global",
)

self.new_timer(self.control_loop_rate, loop)
Expand Down

0 comments on commit 4ca5de6

Please sign in to comment.