Skip to content

Commit

Permalink
Tools: Set GPS instance ID in the GPS frame ID
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
  • Loading branch information
Ryanf55 authored and tridge committed Nov 1, 2024
1 parent bd067f9 commit ebfecad
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion Tools/ros2/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ To see all current options, use the `-s` argument:
ros2 launch ardupilot_sitl sitl.launch.py -s
```

#### `ardupilot_dds_test`
#### `ardupilot_dds_tests`

A `colcon` package for testing communication between `micro_ros_agent` and the
ArduPilot `AP_DDS` client library.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@

from sensor_msgs.msg import NavSatFix

TOPIC = "ap/navsat/navsat0"
TOPIC = "ap/navsat"


class NavSatFixListener(rclpy.node.Node):
Expand Down

0 comments on commit ebfecad

Please sign in to comment.