Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_DDS: Set GPS instance ID in the GPS frame ID #28441

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
3 changes: 2 additions & 1 deletion libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,8 @@ bool AP_DDS_Client::update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t i


update_topic(msg.header.stamp);
strcpy(msg.header.frame_id, WGS_84_FRAME_ID);
static_assert(GPS_MAX_RECEIVERS <= 9, "GPS_MAX_RECEIVERS is greater than 9");
hal.util->snprintf(msg.header.frame_id, 2, "%u", instance);
msg.status.service = 0; // SERVICE_GPS
msg.status.status = -1; // STATUS_NO_FIX

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_DDS/AP_DDS_Topic_Table.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = {
.dw_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAWRITER_ID},
.dr_id = uxrObjectId{.id=to_underlying(TopicIndex::NAV_SAT_FIX_PUB), .type=UXR_DATAREADER_ID},
.topic_rw = Topic_rw::DataWriter,
.topic_name = "rt/ap/navsat/navsat0",
.topic_name = "rt/ap/navsat",
.type_name = "sensor_msgs::msg::dds_::NavSatFix_",
.qos = {
.durability = UXR_DURABILITY_VOLATILE,
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_DDS/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ Published topics:
* /ap/geopose/filtered [geographic_msgs/msg/GeoPoseStamped] 1 publisher
* /ap/gps_global_origin/filtered [geographic_msgs/msg/GeoPointStamped] 1 publisher
* /ap/imu/experimental/data [sensor_msgs/msg/Imu] 1 publisher
* /ap/navsat/navsat0 [sensor_msgs/msg/NavSatFix] 1 publisher
* /ap/navsat [sensor_msgs/msg/NavSatFix] 1 publisher
* /ap/pose/filtered [geometry_msgs/msg/PoseStamped] 1 publisher
* /ap/tf_static [tf2_msgs/msg/TFMessage] 1 publisher
* /ap/time [builtin_interfaces/msg/Time] 1 publisher
Expand Down Expand Up @@ -354,7 +354,7 @@ The table below provides example mappings for topics and services
| ROS 2 | DDS |
| --- | --- |
| ap/clock | rt/ap/clock |
| ap/navsat/navsat0 | rt/ap/navsat/navsat0 |
| ap/navsat | rt/ap/navsat |
| ap/arm_motors | rq/ap/arm_motorsRequest, rr/ap/arm_motorsReply |

Refer to existing mappings in [`AP_DDS_Topic_Table`](https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/AP_DDS_Topic_Table.h)
Expand Down
Loading