mirror of https://github.com/ArduPilot/ardupilot
Tools: Set GPS instance ID in the GPS frame ID
Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
This commit is contained in:
parent
bd067f9615
commit
ebfecaddac
|
@ -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.
|
||||
|
|
|
@ -30,7 +30,7 @@ from rclpy.qos import QoSHistoryPolicy
|
|||
|
||||
from sensor_msgs.msg import NavSatFix
|
||||
|
||||
TOPIC = "ap/navsat/navsat0"
|
||||
TOPIC = "ap/navsat"
|
||||
|
||||
|
||||
class NavSatFixListener(rclpy.node.Node):
|
||||
|
|
Loading…
Reference in New Issue