Skip to content

Commit d3575cb

Browse files
committed
new formatting rules
1 parent 3b9e06c commit d3575cb

17 files changed

Lines changed: 68 additions & 115 deletions

.clang-format

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ BreakBeforeBinaryOperators: false
1414
BreakBeforeTernaryOperators: false
1515
BreakConstructorInitializers: BeforeComma
1616
BinPackParameters: true
17-
ColumnLimit: 100
17+
ColumnLimit: 120
1818
ConstructorInitializerAllOnOneLineOrOnePerLine: true
1919
DerivePointerBinding: false
2020
PointerBindsToType: true

.pre-commit-config.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
#
1414
# See https://github.com/pre-commit/pre-commit
1515

16-
exclude: cmake/CPM.cmake|^3rdparty/|3rdparty
16+
exclude: cmake/CPM.cmake|^3rdparty/|3rdparty|^plotjuggler_base/include/PlotJuggler/contrib/|^contrib/|contrib
1717
repos:
1818

1919
# Standard hooks

.vscode/settings.json

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
{
2-
"ros.distro": "humble"
3-
}
2+
"ros.distro": "humble"
3+
}

src/DataLoadROS2/dataload_ros2.cpp

Lines changed: 6 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -70,17 +70,15 @@ bool DataLoadROS2::readDataFromFile(PJ::FileLoadInfo* info, PJ::PlotDataMapRef&
7070
}
7171
catch (std::runtime_error& ex)
7272
{
73-
QMessageBox::warning(nullptr, tr("Error"),
74-
QString("rosbag::open thrown an exception:\n") + QString(ex.what()));
73+
QMessageBox::warning(nullptr, tr("Error"), QString("rosbag::open thrown an exception:\n") + QString(ex.what()));
7574
return false;
7675
}
7776

7877
QDir::setCurrent(oldPath);
7978

8079
// Temporarily change the current directory as a workaround for rosbag2 relative directories not
8180
// working properly
82-
std::vector<rosbag2_storage::TopicMetadata> topic_metadata =
83-
temp_bag_reader->get_all_topics_and_types();
81+
std::vector<rosbag2_storage::TopicMetadata> topic_metadata = temp_bag_reader->get_all_topics_and_types();
8482

8583
std::unordered_map<std::string, std::string> topicTypesByName;
8684

@@ -93,8 +91,7 @@ bool DataLoadROS2::readDataFromFile(PJ::FileLoadInfo* info, PJ::PlotDataMapRef&
9391

9492
for (const rosbag2_storage::TopicMetadata& topic : topic_metadata)
9593
{
96-
all_topics_qt.push_back(
97-
{ QString::fromStdString(topic.name), QString::fromStdString(topic.type) });
94+
all_topics_qt.push_back({ QString::fromStdString(topic.name), QString::fromStdString(topic.type) });
9895
topicTypesByName.emplace(topic.name, topic.type);
9996

10097
const auto& typesupport_identifier = rosidl_typesupport_cpp::typesupport_identifier;
@@ -111,8 +108,7 @@ bool DataLoadROS2::readDataFromFile(PJ::FileLoadInfo* info, PJ::PlotDataMapRef&
111108

112109
if (!failed_topic_type.empty())
113110
{
114-
QString msg(
115-
"Can not recognize the following message types and those topics will be ignored:\n\n");
111+
QString msg("Can not recognize the following message types and those topics will be ignored:\n\n");
116112
for (const auto& type : failed_topic_type)
117113
{
118114
msg += " " + QString::fromStdString(type) + "\n";
@@ -177,10 +173,8 @@ bool DataLoadROS2::readDataFromFile(PJ::FileLoadInfo* info, PJ::PlotDataMapRef&
177173
progress_dialog.show();
178174
int msg_count = 0;
179175

180-
PJ::PlotDataAny& plot_consecutive =
181-
plot_map.addUserDefined("plotjuggler::rosbag2_cpp::consecutive_messages")->second;
182-
PJ::PlotDataAny& metadata_storage =
183-
plot_map.addUserDefined("plotjuggler::rosbag2_cpp::topics_metadata")->second;
176+
PJ::PlotDataAny& plot_consecutive = plot_map.addUserDefined("plotjuggler::rosbag2_cpp::consecutive_messages")->second;
177+
PJ::PlotDataAny& metadata_storage = plot_map.addUserDefined("plotjuggler::rosbag2_cpp::topics_metadata")->second;
184178

185179
// dirty trick. Store it in a one point timeseries
186180
metadata_storage.pushBack({ 0, std::any(topics_info) });

src/DataLoadROS2/dataload_ros2.h

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,7 @@ class DataLoadROS2 : public PJ::DataLoader
2121

2222
virtual const std::vector<const char*>& compatibleFileExtensions() const override;
2323

24-
virtual bool readDataFromFile(PJ::FileLoadInfo* fileload_info,
25-
PJ::PlotDataMapRef& destination) override;
24+
virtual bool readDataFromFile(PJ::FileLoadInfo* fileload_info, PJ::PlotDataMapRef& destination) override;
2625

2726
virtual const char* name() const override
2827
{

src/DataStreamROS2/datastream_ros2.cpp

Lines changed: 5 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -59,8 +59,7 @@ rclcpp::QoS adapt_request_to_offers(const std::string& topic_name,
5959
return request_qos;
6060
}
6161

62-
DataStreamROS2::DataStreamROS2()
63-
: DataStreamer(), _node(nullptr), _running(false), _first_warning(false)
62+
DataStreamROS2::DataStreamROS2() : DataStreamer(), _node(nullptr), _running(false), _first_warning(false)
6463
{
6564
loadDefaultSettings();
6665

@@ -231,26 +230,21 @@ void DataStreamROS2::subscribeToTopic(const std::string& topic_name, const std::
231230

232231
if (!_parser.hasParser(topic_name))
233232
{
234-
_parser.addParser(topic_name,
235-
CreateParserROS2(*parserFactories(), topic_name, topic_type, dataMap()));
233+
_parser.addParser(topic_name, CreateParserROS2(*parserFactories(), topic_name, topic_type, dataMap()));
236234
}
237235

238-
auto bound_callback = [=](std::shared_ptr<rclcpp::SerializedMessage> msg) {
239-
messageCallback(topic_name, msg);
240-
};
236+
auto bound_callback = [=](std::shared_ptr<rclcpp::SerializedMessage> msg) { messageCallback(topic_name, msg); };
241237

242238
auto publisher_info = _node->get_publishers_info_by_topic(topic_name);
243239
auto detected_qos = adapt_request_to_offers(topic_name, publisher_info);
244240

245241
// double subscription, latching or not
246-
auto subscription =
247-
_node->create_generic_subscription(topic_name, topic_type, detected_qos, bound_callback);
242+
auto subscription = _node->create_generic_subscription(topic_name, topic_type, detected_qos, bound_callback);
248243
_subscriptions[topic_name] = subscription;
249244
_node->get_node_topics_interface()->add_subscription(subscription, nullptr);
250245
}
251246

252-
void DataStreamROS2::messageCallback(const std::string& topic_name,
253-
std::shared_ptr<rclcpp::SerializedMessage> msg)
247+
void DataStreamROS2::messageCallback(const std::string& topic_name, std::shared_ptr<rclcpp::SerializedMessage> msg)
254248
{
255249
double timestamp = _node->get_clock()->now().seconds();
256250
try

src/DataStreamROS2/datastream_ros2.h

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,7 @@ class DataStreamROS2 : public PJ::DataStreamer
3939
const std::vector<QAction*>& availableActions() override;
4040

4141
private:
42-
void messageCallback(const std::string& topic_name,
43-
std::shared_ptr<rclcpp::SerializedMessage> msg);
42+
void messageCallback(const std::string& topic_name, std::shared_ptr<rclcpp::SerializedMessage> msg);
4443

4544
private:
4645
std::shared_ptr<rclcpp::Context> _context;

src/TopicPublisherROS2/generic_publisher.h

Lines changed: 8 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -23,14 +23,12 @@
2323
class GenericPublisher : public rclcpp::PublisherBase
2424
{
2525
public:
26-
GenericPublisher(rclcpp::node_interfaces::NodeBaseInterface* node_base,
27-
const std::string& topic_name, const rosidl_message_type_support_t& type_support)
26+
GenericPublisher(rclcpp::node_interfaces::NodeBaseInterface* node_base, const std::string& topic_name,
27+
const rosidl_message_type_support_t& type_support)
2828
#ifdef ROS_HUMBLE
29-
: rclcpp::PublisherBase(node_base, topic_name, type_support,
30-
rcl_publisher_get_default_options())
29+
: rclcpp::PublisherBase(node_base, topic_name, type_support, rcl_publisher_get_default_options())
3130
#else
32-
: rclcpp::PublisherBase(node_base, topic_name, type_support,
33-
rcl_publisher_get_default_options(), callbacks_, true)
31+
: rclcpp::PublisherBase(node_base, topic_name, type_support, rcl_publisher_get_default_options(), callbacks_, true)
3432
#endif
3533
{
3634
}
@@ -39,8 +37,7 @@ class GenericPublisher : public rclcpp::PublisherBase
3937

4038
void publish(std::shared_ptr<rmw_serialized_message_t> message)
4139
{
42-
auto return_code =
43-
rcl_publish_serialized_message(get_publisher_handle().get(), message.get(), NULL);
40+
auto return_code = rcl_publish_serialized_message(get_publisher_handle().get(), message.get(), NULL);
4441

4542
if (return_code != RCL_RET_OK)
4643
{
@@ -51,13 +48,10 @@ class GenericPublisher : public rclcpp::PublisherBase
5148
static std::shared_ptr<GenericPublisher> create(rclcpp::Node& node, const std::string& topic_name,
5249
const std::string& topic_type)
5350
{
54-
auto library =
55-
std::move(rosbag2_cpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp"));
56-
auto type_support =
57-
rosbag2_cpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", library);
51+
auto library = std::move(rosbag2_cpp::get_typesupport_library(topic_type, "rosidl_typesupport_cpp"));
52+
auto type_support = rosbag2_cpp::get_typesupport_handle(topic_type, "rosidl_typesupport_cpp", library);
5853

59-
return std::make_shared<GenericPublisher>(node.get_node_base_interface().get(), topic_name,
60-
*type_support);
54+
return std::make_shared<GenericPublisher>(node.get_node_base_interface().get(), topic_name, *type_support);
6155
}
6256

6357
#ifndef ROS_HUMBLE

src/TopicPublisherROS2/publisher_ros2.cpp

Lines changed: 5 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -62,8 +62,7 @@ void TopicPublisherROS2::updatePublishers()
6262
auto publisher_it = _publishers.find(info.topic_name);
6363
if (publisher_it == _publishers.end())
6464
{
65-
_publishers.insert(
66-
{ info.topic_name, GenericPublisher::create(*_node, info.topic_name, info.type) });
65+
_publishers.insert({ info.topic_name, GenericPublisher::create(*_node, info.topic_name, info.type) });
6766
}
6867
}
6968

@@ -165,10 +164,8 @@ void TopicPublisherROS2::filterDialog()
165164
cb->setFocusPolicy(Qt::NoFocus);
166165
dialog->ui()->formLayout->addRow(new QLabel(QString::fromStdString(topic_name)), cb);
167166
checkbox.insert(std::make_pair(topic_name, cb));
168-
connect(dialog->ui()->pushButtonSelect, &QPushButton::pressed,
169-
[cb]() { cb->setChecked(true); });
170-
connect(dialog->ui()->pushButtonDeselect, &QPushButton::pressed,
171-
[cb]() { cb->setChecked(false); });
167+
connect(dialog->ui()->pushButtonSelect, &QPushButton::pressed, [cb]() { cb->setChecked(true); });
168+
connect(dialog->ui()->pushButtonDeselect, &QPushButton::pressed, [cb]() { cb->setChecked(false); });
172169
}
173170

174171
dialog->exec();
@@ -248,11 +245,9 @@ void TopicPublisherROS2::broadcastTF(double current_time)
248245

249246
const auto& msg_instance = std::any_cast<MessageRefPtr>(any_value);
250247

251-
auto tf_type_support =
252-
rosidl_typesupport_cpp::get_message_type_support_handle<tf2_msgs::msg::TFMessage>();
248+
auto tf_type_support = rosidl_typesupport_cpp::get_message_type_support_handle<tf2_msgs::msg::TFMessage>();
253249
tf2_msgs::msg::TFMessage tf_msg;
254-
if (RMW_RET_OK !=
255-
rmw_deserialize(msg_instance->serialized_data.get(), tf_type_support, &tf_msg))
250+
if (RMW_RET_OK != rmw_deserialize(msg_instance->serialized_data.get(), tf_type_support, &tf_msg))
256251
{
257252
throw std::runtime_error("failed to deserialize TF message");
258253
}

src/dialog_select_ros_topics.cpp

Lines changed: 14 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,8 @@
1414
#include "dialog_select_ros_topics.h"
1515
#include "ui_dialog_select_ros_topics.h"
1616

17-
DialogSelectRosTopics::DialogSelectRosTopics(
18-
const std::vector<std::pair<QString, QString>>& topic_list, const PJ::RosParserConfig& config,
19-
QWidget* parent)
17+
DialogSelectRosTopics::DialogSelectRosTopics(const std::vector<std::pair<QString, QString>>& topic_list,
18+
const PJ::RosParserConfig& config, QWidget* parent)
2019
: QDialog(parent)
2120
, ui(new Ui::dialogSelectRosTopics)
2221
, _default_selected_topics(config.topics)
@@ -70,8 +69,7 @@ DialogSelectRosTopics::DialogSelectRosTopics(
7069
}
7170
});
7271

73-
connect(&_deselect_all, &QShortcut::activated, ui->listRosTopics,
74-
&QAbstractItemView::clearSelection);
72+
connect(&_deselect_all, &QShortcut::activated, ui->listRosTopics, &QAbstractItemView::clearSelection);
7573

7674
on_spinBoxArraySize_valueChanged(ui->spinBoxArraySize->value());
7775

@@ -190,18 +188,17 @@ void DialogSelectRosTopics::on_maximumSizeHelp_pressed()
190188
{
191189
QMessageBox msgBox;
192190
msgBox.setWindowTitle("Help");
193-
msgBox.setText(
194-
"Maximum Size of Arrays:\n\n"
195-
"If the size of an Arrays is larger than this maximum value, the entire array is skipped.\n\n"
196-
"This parameter is used to prevent the user from loading HUGE arrays, "
197-
"such as images, pointclouds, maps, etc.\n"
198-
"The term 'array' refers to the array in a message field,\n\n"
199-
" See http://wiki.ros.org/msg.\n\n"
200-
"This is NOT about the duration of a time series!\n\n"
201-
"MOTIVATION: pretend that a user tries to load a RGB image, which probably contains "
202-
"a few millions pixels.\n"
203-
"Plotjuggler would naively create a single time series for each pixel of the image! "
204-
"That makes no sense, of course, and it would probably freeze your system.\n");
191+
msgBox.setText("Maximum Size of Arrays:\n\n"
192+
"If the size of an Arrays is larger than this maximum value, the entire array is skipped.\n\n"
193+
"This parameter is used to prevent the user from loading HUGE arrays, "
194+
"such as images, pointclouds, maps, etc.\n"
195+
"The term 'array' refers to the array in a message field,\n\n"
196+
" See http://wiki.ros.org/msg.\n\n"
197+
"This is NOT about the duration of a time series!\n\n"
198+
"MOTIVATION: pretend that a user tries to load a RGB image, which probably contains "
199+
"a few millions pixels.\n"
200+
"Plotjuggler would naively create a single time series for each pixel of the image! "
201+
"That makes no sense, of course, and it would probably freeze your system.\n");
205202
msgBox.exec();
206203
}
207204

0 commit comments

Comments
 (0)