Skip to content

Commit c3ce403

Browse files
committed
ros2: update terrain_navigation_ros
- update relay from /mavros/set_point/global to /ap/cmd_gps_pose. Signed-off-by: Rhys Mainwaring <[email protected]>
1 parent 9ac5fd8 commit c3ce403

File tree

1 file changed

+16
-0
lines changed

1 file changed

+16
-0
lines changed

terrain_navigation_ros/scripts/global_postion_relay.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,11 +33,27 @@ def __init__(self):
3333
def global_position_cb(self, msg):
3434

3535
pos_msg = GlobalPosition()
36+
# header
3637
pos_msg.header = msg.header
3738
pos_msg.header.frame_id = "map"
39+
# coordinate frame and type mask
40+
pos_msg.coordinate_frame = msg.coordinate_frame
41+
pos_msg.type_mask = msg.type_mask
42+
# geodetic position (datum AMSL)
3843
pos_msg.latitude = msg.latitude
3944
pos_msg.longitude = msg.longitude
4045
pos_msg.altitude = msg.altitude
46+
# velocity
47+
pos_msg.velocity.linear.x = msg.velocity.x
48+
pos_msg.velocity.linear.y = msg.velocity.y
49+
pos_msg.velocity.linear.z = msg.velocity.z
50+
# acceleration or force
51+
pos_msg.acceleration_or_force.linear.x = msg.acceleration_or_force.x
52+
pos_msg.acceleration_or_force.linear.y = msg.acceleration_or_force.y
53+
pos_msg.acceleration_or_force.linear.z = msg.acceleration_or_force.z
54+
# yaw rate
55+
pos_msg.velocity.angular.z = msg.yaw_rate
56+
# TODO: yaw (no corresponding member in GlobalPosition)
4157

4258
self.pub.publish(pos_msg)
4359

0 commit comments

Comments
 (0)