swri-robotics / mapviz

Modular ROS visualization tool for 2D data.
BSD 3-Clause "New" or "Revised" License
396 stars 152 forks source link

How to convert to LocalXy from GPS Coordinates #775

Open xycotyco opened 1 year ago

xycotyco commented 1 year ago

I've been trying to publish a frame, but have not been able to convert it to LocalXy coordinates, this is the python file that I am using currently. Any suggestions would be highly appreciated.

`

      #!/usr/bin/env python
      import rospy
      import tf2_ros
      import geometry_msgs.msg
      from sensor_msgs.msg import NavSatFix
      import swri_transform_util 

      class NavSatFixTFBroadcaster:

          def __init__(self):
              rospy.init_node(navsatfix_tf_broadcaster)
              self.tf_broadcaster = tf2_ros.TransformBroadcaster()
              rospy.Subscriber("/actual", NavSatFix, self.navsatfix_callback)

          def navsatfix_callback(self, navsat_fix):
              t = geometry_msgs.msg.TransformStamped()
              t.header.stamp = rospy.Time.now()
              t.header.frame_id = "map"
              t.child_frame_id = "dynamic_frame"

              # Get latitude and longitude from NavSatFix message
              latitude = navsat_fix.latitude
              longitude = navsat_fix.longitude

              # Calculate the transformation based on latitude and longitude
              y = float(longitude)
              x = float(latitude)
              z = 0.0
              print(x,y)
              t.transform.translation.x = x
              t.transform.translation.y = y
              t.transform.translation.z = z

              t.transform.rotation.x = 0.0
              t.transform.rotation.y = 0.0
              t.transform.rotation.z = 0.0
              t.transform.rotation.w = 1.0

              self.tf_broadcaster.sendTransform(t)

          def run(self):
              rospy.spin()

      if __name__== __main__:
          tf_broadcaster = NavSatFixTFBroadcaster()
          tf_broadcaster.run()

`

What files and functions will I require to convert the coordinates to LocalXy and vice versa if required? The swri_transform import hasn't been running as well as I though it would.

rjb0026 commented 1 year ago

@xycotyco Are you running an initialize origin node? If not, maybe check out running this node: https://github.com/swri-robotics/marti_common/blob/master/swri_transform_util/nodes/initialize_origin.py

It can be configured to take a NavSatFix message and publish the /local_xy_origin topic with the coordinates of a "map" frame origin (or whatever you set that frame to be called).

You could then subscribe to the /local_xy_origin topic from any other node and use those origin coordinates with the wgs84_transformer module to convert from you gnss coordinates to coordinates in the "map" frame and create a new transform from "map" to whatever your desired child frame is: https://github.com/swri-robotics/marti_common/blob/master/swri_transform_util/src/swri_transform_util/wgs84_transformer.py

Hope that helps!