Skip to content

Commit

Permalink
added reference gnss coordinate as parameters.
Browse files Browse the repository at this point in the history
  • Loading branch information
hovak101 committed Nov 23, 2024
1 parent ff49f7d commit 598f0bd
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 11 deletions.
25 changes: 15 additions & 10 deletions src/gps/gps/geo_to_cart.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,20 @@
import rclpy
from rclpy.node import Node
from constants import GPS_TOPIC, CARTESIAN_TOPIC
from std_msgs.msg import String
from urc_intelsys_2024_msgs.msg import GPS, CART
import math

class CartesianPublisher(Node):
def __init__(self):
super().__init__('Cartesian_Publisher')
self.declare_parameters(
namespace="",
parameters=[
# "name", default_value
("ref_latitude", 90),
("ref_longitude", 90)
],
)
self.publisher_ = self.create_publisher(CART, CARTESIAN_TOPIC, 10)

self.subscription = self.create_subscription(
Expand All @@ -20,9 +27,11 @@ def __init__(self):
self.A = 6378137
# eccentricity constant
self.EE = 6.69437999013 * (10 ** (-3))
self.x_ref = 0
self.y_ref = 0
self.z_ref = 0

lat_rad = self.deg_to_rad(self.get_parameter("ref_latitude").value)
long_rad = self.deg_to_rad(self.get_parameter("ref_longitude").value)

self.x_ref, self.y_ref, self.z_ref = self.gnss_to_ecef(lat_rad, long_rad)

def deg_to_rad(self, deg):
return deg * math.pi / 180
Expand Down Expand Up @@ -79,16 +88,12 @@ def listener_callback(self, msg):
def main(args=None):
rclpy.init(args=args)

# TODO: Should this node be spun in main?
my_node = CartesianPublisher()

rclpy.spin(my_node)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
my_node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
rclpy.shutdown()
2 changes: 1 addition & 1 deletion src/gps/gps/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ def __init__(self):
parameters=[
# "name", default_value
("gps_publish_seconds", 0.5),
("gps_type", "fake"),
("gps_type", "actual"),
],
)

Expand Down

0 comments on commit 598f0bd

Please sign in to comment.