Skip to content

Commit

Permalink
ros2: update terrain_navigation_ros
Browse files Browse the repository at this point in the history
- update relay from /mavros/set_point/global to /ap/cmd_gps_pose.

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Dec 8, 2023
1 parent 9ac5fd8 commit c3ce403
Showing 1 changed file with 16 additions and 0 deletions.
16 changes: 16 additions & 0 deletions terrain_navigation_ros/scripts/global_postion_relay.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,27 @@ def __init__(self):
def global_position_cb(self, msg):

pos_msg = GlobalPosition()
# header
pos_msg.header = msg.header
pos_msg.header.frame_id = "map"
# coordinate frame and type mask
pos_msg.coordinate_frame = msg.coordinate_frame
pos_msg.type_mask = msg.type_mask
# geodetic position (datum AMSL)
pos_msg.latitude = msg.latitude
pos_msg.longitude = msg.longitude
pos_msg.altitude = msg.altitude
# velocity
pos_msg.velocity.linear.x = msg.velocity.x
pos_msg.velocity.linear.y = msg.velocity.y
pos_msg.velocity.linear.z = msg.velocity.z
# acceleration or force
pos_msg.acceleration_or_force.linear.x = msg.acceleration_or_force.x
pos_msg.acceleration_or_force.linear.y = msg.acceleration_or_force.y
pos_msg.acceleration_or_force.linear.z = msg.acceleration_or_force.z
# yaw rate
pos_msg.velocity.angular.z = msg.yaw_rate
# TODO: yaw (no corresponding member in GlobalPosition)

self.pub.publish(pos_msg)

Expand Down

0 comments on commit c3ce403

Please sign in to comment.