Skip to content

Commit cbc6dc3

Browse files
committed
jazzy+
1 parent d0692ad commit cbc6dc3

5 files changed

Lines changed: 48 additions & 13 deletions

File tree

.github/workflows/ros2.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,10 +7,10 @@ jobs:
77
strategy:
88
matrix:
99
env:
10-
- {ROS_DISTRO: humble, ROS_REPO: main}
11-
- {ROS_DISTRO: iron, ROS_REPO: main}
10+
- {ROS_DISTRO: jazzy, ROS_REPO: main}
11+
- {ROS_DISTRO: kilted, ROS_REPO: main}
1212
- {ROS_DISTRO: rolling, ROS_REPO: main}
13-
runs-on: ubuntu-latest
13+
runs-on: ubuntu-24.04
1414
steps:
1515
- uses: actions/checkout@v1
1616
- uses: 'ros-industrial/industrial_ci@master'

package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@
3838
<depend>libqt5-svg-dev</depend>
3939
<depend>libqt5-websockets-dev</depend>
4040
<depend>boost</depend>
41+
<depend>fmt</depend>
4142

4243
<!-- The export tag contains other, unspecified, tags -->
4344
<export>

src/DataLoadROS2/dataload_ros2.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -193,7 +193,7 @@ bool DataLoadROS2::readDataFromFile(PJ::FileLoadInfo* info,
193193
{
194194
continue;
195195
}
196-
const double msg_timestamp = 1e-9 * double(msg->time_stamp); // nanoseconds to seconds
196+
const double msg_timestamp = 1e-9 * double(msg->send_timestamp); // nanoseconds to seconds
197197

198198
//------ progress dialog --------------
199199
if (msg_count++ % 100 == 0)

src/DataStreamROS2/datastream_ros2.cpp

Lines changed: 42 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,47 @@
77
#include <QApplication>
88
#include <QProgressDialog>
99
#include "rclcpp/generic_subscription.hpp"
10-
#include "rosbag2_transport/qos.hpp"
10+
11+
// function taken from rosbag2_transport
12+
13+
rclcpp::QoS adapt_request_to_offers(
14+
const std::string & topic_name, const std::vector<rclcpp::TopicEndpointInfo> & endpoints)
15+
{
16+
rclcpp::QoS request_qos(rmw_qos_profile_default.depth);
17+
18+
if (endpoints.empty()) {
19+
return request_qos;
20+
}
21+
size_t num_endpoints = endpoints.size();
22+
size_t reliability_reliable_endpoints_count = 0;
23+
size_t durability_transient_local_endpoints_count = 0;
24+
for (const auto & endpoint : endpoints) {
25+
const auto & profile = endpoint.qos_profile().get_rmw_qos_profile();
26+
if (profile.reliability == RMW_QOS_POLICY_RELIABILITY_RELIABLE) {
27+
reliability_reliable_endpoints_count++;
28+
}
29+
if (profile.durability == RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) {
30+
durability_transient_local_endpoints_count++;
31+
}
32+
}
33+
34+
// Policy: reliability
35+
if (reliability_reliable_endpoints_count == num_endpoints) {
36+
request_qos.reliable();
37+
} else {
38+
request_qos.best_effort();
39+
}
40+
41+
// Policy: durability
42+
// If all publishers offer transient_local, we can request it and receive latched messages
43+
if (durability_transient_local_endpoints_count == num_endpoints) {
44+
request_qos.transient_local();
45+
} else {
46+
request_qos.durability_volatile();
47+
}
48+
49+
return request_qos;
50+
}
1151

1252
DataStreamROS2::DataStreamROS2() :
1353
DataStreamer(),
@@ -192,7 +232,7 @@ void DataStreamROS2::subscribeToTopic(const std::string& topic_name, const std::
192232
auto bound_callback = [=](std::shared_ptr<rclcpp::SerializedMessage> msg) { messageCallback(topic_name, msg); };
193233

194234
auto publisher_info = _node->get_publishers_info_by_topic(topic_name);
195-
auto detected_qos = rosbag2_transport::Rosbag2QoS::adapt_request_to_offers(topic_name, publisher_info);
235+
auto detected_qos = adapt_request_to_offers(topic_name, publisher_info);
196236

197237
// double subscription, latching or not
198238
auto subscription = _node->create_generic_subscription(topic_name,

src/ros_parsers/ros2_parser.cpp

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -8,14 +8,8 @@
88

99
#include <rosidl_typesupport_cpp/identifier.hpp>
1010
#include <rosidl_typesupport_introspection_cpp/identifier.hpp>
11+
#include <fmt/core.h>
1112

12-
#if __has_include(<PlotJuggler/fmt/core.h>)
13-
# include <PlotJuggler/fmt/core.h>
14-
#endif
15-
16-
#if __has_include(<PlotJuggler/contrib/fmt/core.h>)
17-
# include <PlotJuggler/contrib/fmt/core.h>
18-
#endif
1913

2014
bool TypeHasHeader(const rosidl_message_type_support_t* type_support)
2115
{

0 commit comments

Comments
 (0)