diff --git a/rviz2/test/tools/send_lots_of_points_node.cpp b/rviz2/test/tools/send_lots_of_points_node.cpp index 082305300..e52fc92fd 100644 --- a/rviz2/test/tools/send_lots_of_points_node.cpp +++ b/rviz2/test/tools/send_lots_of_points_node.cpp @@ -84,7 +84,8 @@ int main(int argc, char ** argv) } msg.header.stamp = node->now(); - printf("publishing at %d hz, %s, %d x %d points.\n", + printf( + "publishing at %d hz, %s, %d x %d points.\n", rate, (moving ? "moving" : "static"), width, length); pub->publish(msg); diff --git a/rviz_common/include/rviz_common/factory/pluginlib_factory.hpp b/rviz_common/include/rviz_common/factory/pluginlib_factory.hpp index 7c6841ebd..5f93a8883 100644 --- a/rviz_common/include/rviz_common/factory/pluginlib_factory.hpp +++ b/rviz_common/include/rviz_common/factory/pluginlib_factory.hpp @@ -159,8 +159,9 @@ class PluginlibFactory : public ClassIdRecordingFactory try { return class_loader_->createUnmanagedInstance(class_id.toStdString()); } catch (pluginlib::PluginlibException & ex) { - RVIZ_COMMON_LOG_ERROR_STREAM("PluginlibFactory: The plugin for class '" << - qPrintable(class_id) << "' failed to load. Error: " << ex.what()); + RVIZ_COMMON_LOG_ERROR_STREAM( + "PluginlibFactory: The plugin for class '" << + qPrintable(class_id) << "' failed to load. Error: " << ex.what()); if (error_return) { *error_return = QString::fromStdString(ex.what()); } diff --git a/rviz_common/include/rviz_common/frame_manager_iface.hpp b/rviz_common/include/rviz_common/frame_manager_iface.hpp index ee8a2ee8e..b40cdbb8a 100644 --- a/rviz_common/include/rviz_common/frame_manager_iface.hpp +++ b/rviz_common/include/rviz_common/frame_manager_iface.hpp @@ -274,8 +274,10 @@ class RVIZ_COMMON_PUBLIC FrameManagerIface : public QObject Display * display) override { filter->registerCallback(boost::bind(&FrameManager::messageCallback, this, _1, display)); - filter->registerFailureCallback(boost::bind(&FrameManager::failureCallback, this, _1, _2, - display)); + filter->registerFailureCallback( + boost::bind( + &FrameManager::failureCallback, this, _1, _2, + display)); } #endif diff --git a/rviz_common/include/rviz_common/message_filter_display.hpp b/rviz_common/include/rviz_common/message_filter_display.hpp index 9a97516ad..29db66382 100644 --- a/rviz_common/include/rviz_common/message_filter_display.hpp +++ b/rviz_common/include/rviz_common/message_filter_display.hpp @@ -126,8 +126,9 @@ class MessageFilterDisplay : public _RosTopicDisplay fixed_frame_.toStdString(), 10, rviz_ros_node_.lock()->get_raw_node()); tf_filter_->connectInput(*subscription_); tf_filter_->registerCallback( - std::bind(&MessageFilterDisplay::incomingMessage, this, - std::placeholders::_1)); + std::bind( + &MessageFilterDisplay::incomingMessage, this, + std::placeholders::_1)); setStatus(properties::StatusProperty::Ok, "Topic", "OK"); } catch (rclcpp::exceptions::InvalidTopicNameError & e) { setStatus( diff --git a/rviz_common/include/rviz_common/ros_topic_display.hpp b/rviz_common/include/rviz_common/ros_topic_display.hpp index 86b05f860..01fe05e44 100644 --- a/rviz_common/include/rviz_common/ros_topic_display.hpp +++ b/rviz_common/include/rviz_common/ros_topic_display.hpp @@ -66,8 +66,9 @@ class RVIZ_COMMON_PUBLIC _RosTopicDisplay : public Display : rviz_ros_node_(), qos_profile(5) { - topic_property_ = new properties::RosTopicProperty("Topic", "", - "", "", this, SLOT(updateTopic())); + topic_property_ = new properties::RosTopicProperty( + "Topic", "", + "", "", this, SLOT(updateTopic())); qos_profile_property_ = new properties::QosProfileProperty(topic_property_, qos_profile); } @@ -167,7 +168,8 @@ class RosTopicDisplay : public _RosTopicDisplay } if (topic_property_->isEmpty()) { - setStatus(properties::StatusProperty::Error, + setStatus( + properties::StatusProperty::Error, "Topic", QString("Error subscribing: Empty topic name")); return; @@ -182,7 +184,8 @@ class RosTopicDisplay : public _RosTopicDisplay [this](const typename MessageType::ConstSharedPtr message) {incomingMessage(message);}); setStatus(properties::StatusProperty::Ok, "Topic", "OK"); } catch (rclcpp::exceptions::InvalidTopicNameError & e) { - setStatus(properties::StatusProperty::Error, "Topic", + setStatus( + properties::StatusProperty::Error, "Topic", QString("Error subscribing: ") + e.what()); } } diff --git a/rviz_common/src/rviz_common/add_display_dialog.cpp b/rviz_common/src/rviz_common/add_display_dialog.cpp index 96f64286c..494c87d4e 100644 --- a/rviz_common/src/rviz_common/add_display_dialog.cpp +++ b/rviz_common/src/rviz_common/add_display_dialog.cpp @@ -166,9 +166,10 @@ void getPluginGroups( QString datatype = QString::fromStdString(map_pair.second[0]); if (datatype_plugins.contains(datatype)) { - if (groups->empty() || - !isSubtopic(groups->back().base_topic.toStdString(), - topic.toStdString())) + if ( + groups->empty() || + !isSubtopic( + groups->back().base_topic.toStdString(), topic.toStdString())) { PluginGroup pi; pi.base_topic = topic; @@ -478,7 +479,8 @@ TopicDisplayWidget::TopicDisplayWidget( // *INDENT-ON* // Connect signal from checkbox - connect(enable_hidden_box_, SIGNAL(stateChanged(int)), + connect( + enable_hidden_box_, SIGNAL(stateChanged(int)), this, SLOT(stateChanged(int))); setLayout(layout); diff --git a/rviz_common/src/rviz_common/config.cpp b/rviz_common/src/rviz_common/config.cpp index 1a3f0845a..7b8bbed74 100644 --- a/rviz_common/src/rviz_common/config.cpp +++ b/rviz_common/src/rviz_common/config.cpp @@ -229,8 +229,8 @@ bool Config::mapGetInt(const QString & key, int * value_out) const bool Config::mapGetFloat(const QString & key, float * value_out) const { QVariant v; - if (mapGetValue(key, - &v) && + if ( + mapGetValue(key, &v) && (static_cast(v.type()) == static_cast(QMetaType::Float) || v.type() == QVariant::Double || v.type() == QVariant::String)) diff --git a/rviz_common/src/rviz_common/display.cpp b/rviz_common/src/rviz_common/display.cpp index 63d41a351..daf09b123 100644 --- a/rviz_common/src/rviz_common/display.cpp +++ b/rviz_common/src/rviz_common/display.cpp @@ -202,7 +202,8 @@ void Display::setStatus( const QString & name, const QString & text) { - QMetaObject::invokeMethod(this, "setStatusInternal", Qt::QueuedConnection, + QMetaObject::invokeMethod( + this, "setStatusInternal", Qt::QueuedConnection, Q_ARG(int, level), Q_ARG(QString, name), Q_ARG(QString, text)); @@ -254,8 +255,8 @@ void Display::setStatusInternal(int level, const QString & name, const QString & void Display::deleteStatus(const QString & name) { - QMetaObject::invokeMethod(this, "deleteStatusInternal", Qt::QueuedConnection, - Q_ARG(QString, name)); + QMetaObject::invokeMethod( + this, "deleteStatusInternal", Qt::QueuedConnection, Q_ARG(QString, name)); } void Display::deleteStatusInternal(const QString & name) @@ -398,7 +399,8 @@ Ogre::SceneNode * Display::getSceneNode() const void Display::setAssociatedWidget(QWidget * widget) { if (associated_widget_panel_) { - disconnect(associated_widget_panel_, SIGNAL(visibilityChanged(bool)), this, + disconnect( + associated_widget_panel_, SIGNAL(visibilityChanged(bool)), this, SLOT(associatedPanelVisibilityChange(bool))); disconnect(associated_widget_panel_, SIGNAL(closed()), this, SLOT(disable())); } @@ -408,7 +410,8 @@ void Display::setAssociatedWidget(QWidget * widget) WindowManagerInterface * wm = context_->getWindowManager(); if (wm) { associated_widget_panel_ = wm->addPane(getName(), associated_widget_); - connect(associated_widget_panel_, SIGNAL(visibilityChanged(bool)), this, + connect( + associated_widget_panel_, SIGNAL(visibilityChanged(bool)), this, SLOT(associatedPanelVisibilityChange(bool))); connect(associated_widget_panel_, SIGNAL(closed()), this, SLOT(disable())); associated_widget_panel_->setIcon(getIcon()); diff --git a/rviz_common/src/rviz_common/failed_tool.cpp b/rviz_common/src/rviz_common/failed_tool.cpp index 7a7aa11dc..3e8601682 100644 --- a/rviz_common/src/rviz_common/failed_tool.cpp +++ b/rviz_common/src/rviz_common/failed_tool.cpp @@ -70,7 +70,8 @@ void FailedTool::deactivate() void FailedTool::onInitialize() { - setDescription("The class required for this tool, '" + getClassId() + + setDescription( + "The class required for this tool, '" + getClassId() + "', could not be loaded.
Error:
" + error_message_); } diff --git a/rviz_common/src/rviz_common/failed_view_controller.cpp b/rviz_common/src/rviz_common/failed_view_controller.cpp index 06bcfbad3..cf67751c4 100644 --- a/rviz_common/src/rviz_common/failed_view_controller.cpp +++ b/rviz_common/src/rviz_common/failed_view_controller.cpp @@ -73,7 +73,8 @@ void FailedViewController::onActivate() if (context_->getWindowManager() ) { parent = context_->getWindowManager()->getParentWindow(); } - QMessageBox::critical(parent, "ViewController '" + getName() + "'unavailable.", + QMessageBox::critical( + parent, "ViewController '" + getName() + "'unavailable.", getDescription() ); } diff --git a/rviz_common/src/rviz_common/interaction/selection_manager.cpp b/rviz_common/src/rviz_common/interaction/selection_manager.cpp index db84f6be4..bf6b6efbb 100644 --- a/rviz_common/src/rviz_common/interaction/selection_manager.cpp +++ b/rviz_common/src/rviz_common/interaction/selection_manager.cpp @@ -140,9 +140,9 @@ void SelectionManager::initialize() static const uint32_t texture_data[1] = {0xffff0080}; Ogre::DataStreamPtr pixel_stream; - pixel_stream.reset(new Ogre::MemoryDataStream( - reinterpret_cast(const_cast(&texture_data[0])), - 4 + pixel_stream.reset( + new Ogre::MemoryDataStream( + reinterpret_cast(const_cast(&texture_data[0])), 4 )); Ogre::TexturePtr tex = Ogre::TextureManager::getSingleton().loadRawData( @@ -207,9 +207,10 @@ void SelectionManager::setTextureSize(unsigned size) } // create new texture - render_texture = Ogre::TextureManager::getSingleton().createManual(tex_name, - Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D, size, size, 0, - Ogre::PF_R8G8B8A8, Ogre::TU_STATIC | Ogre::TU_RENDERTARGET); + render_texture = Ogre::TextureManager::getSingleton().createManual( + tex_name, + Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, Ogre::TEX_TYPE_2D, size, size, 0, + Ogre::PF_R8G8B8A8, Ogre::TU_STATIC | Ogre::TU_RENDERTARGET); render_texture->getBuffer()->getRenderTarget()->setAutoUpdated(false); } diff --git a/rviz_common/src/rviz_common/interaction/view_picker.cpp b/rviz_common/src/rviz_common/interaction/view_picker.cpp index 3aef340fa..44a4cc7de 100644 --- a/rviz_common/src/rviz_common/interaction/view_picker.cpp +++ b/rviz_common/src/rviz_common/interaction/view_picker.cpp @@ -227,11 +227,12 @@ void ViewPicker::setDepthTextureSize(unsigned width, unsigned height) } depth_render_texture_ = - Ogre::TextureManager::getSingleton().createManual(tex_name, - Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, - Ogre::TEX_TYPE_2D, depth_texture_width_, depth_texture_height_, 0, - Ogre::PF_R8G8B8, - Ogre::TU_RENDERTARGET); + Ogre::TextureManager::getSingleton().createManual( + tex_name, + Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, + Ogre::TEX_TYPE_2D, depth_texture_width_, depth_texture_height_, 0, + Ogre::PF_R8G8B8, + Ogre::TU_RENDERTARGET); depth_render_texture_->getBuffer()->getRenderTarget()->setAutoUpdated(false); } diff --git a/rviz_common/src/rviz_common/load_resource.cpp b/rviz_common/src/rviz_common/load_resource.cpp index b17eb3596..88210c488 100644 --- a/rviz_common/src/rviz_common/load_resource.cpp +++ b/rviz_common/src/rviz_common/load_resource.cpp @@ -94,8 +94,9 @@ QCursor makeIconCursor(QString url, bool fill_cache) { QPixmap icon = loadPixmap(url, fill_cache); if (icon.width() == 0 || icon.height() == 0) { - RVIZ_COMMON_LOG_ERROR_STREAM("Could not load pixmap " << url.toStdString() << " -- " - "using default cursor instead."); + RVIZ_COMMON_LOG_ERROR_STREAM( + "Could not load pixmap " << url.toStdString() << " -- " + "using default cursor instead."); return getDefaultCursor(); } QString cache_key = url + ".cursor"; diff --git a/rviz_common/src/rviz_common/new_object_dialog.cpp b/rviz_common/src/rviz_common/new_object_dialog.cpp index 2b7448993..09ee718bc 100644 --- a/rviz_common/src/rviz_common/new_object_dialog.cpp +++ b/rviz_common/src/rviz_common/new_object_dialog.cpp @@ -94,8 +94,8 @@ NewObjectDialog::NewObjectDialog( } // Buttons - button_box_ = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel, - Qt::Horizontal); + button_box_ = new QDialogButtonBox( + QDialogButtonBox::Ok | QDialogButtonBox::Cancel, Qt::Horizontal); auto main_layout = new QVBoxLayout; main_layout->addWidget(type_box); diff --git a/rviz_common/src/rviz_common/panel_factory.cpp b/rviz_common/src/rviz_common/panel_factory.cpp index 98b3179fa..98c5c64fb 100644 --- a/rviz_common/src/rviz_common/panel_factory.cpp +++ b/rviz_common/src/rviz_common/panel_factory.cpp @@ -59,22 +59,28 @@ PanelFactory::PanelFactory( VisualizationManager * manager) : PluginlibFactory("rviz_common", "rviz_common::Panel") { - addBuiltInClass("rviz_common", "Displays", + addBuiltInClass( + "rviz_common", "Displays", "Show and edit the list of Displays", [rviz_ros_node, manager]() -> Panel * { return new DisplaysPanel(rviz_ros_node, manager, nullptr); }); - addBuiltInClass("rviz_common", "Help", + addBuiltInClass( + "rviz_common", "Help", "Show the key and mouse bindings", &newHelpPanel); - addBuiltInClass("rviz_common", "Selection", + addBuiltInClass( + "rviz_common", "Selection", "Show properties of selected objects", &newSelectionPanel); // addBuiltInClass("rviz", "Time", // "Show the current time", &newTimePanel); - addBuiltInClass("rviz_common", "Tool Properties", + addBuiltInClass( + "rviz_common", "Tool Properties", "Show and edit properties of tools", &newToolPropertiesPanel); - addBuiltInClass("rviz_common", "Transformation", + addBuiltInClass( + "rviz_common", "Transformation", "Choose the transformation plugin", &newTransformationPanel); - addBuiltInClass("rviz_common", "Views", + addBuiltInClass( + "rviz_common", "Views", "Show and edit viewpoints", &newViewsPanel); } diff --git a/rviz_common/src/rviz_common/properties/color_editor.cpp b/rviz_common/src/rviz_common/properties/color_editor.cpp index bbd57f30d..33d98ad2a 100644 --- a/rviz_common/src/rviz_common/properties/color_editor.cpp +++ b/rviz_common/src/rviz_common/properties/color_editor.cpp @@ -48,7 +48,8 @@ ColorEditor::ColorEditor(ColorProperty * property, QWidget * parent) : LineEditWithButton(parent), property_(property) { - connect(this, SIGNAL(textChanged(const QString&)), + connect( + this, SIGNAL(textChanged(const QString&)), this, SLOT(parseText())); } @@ -66,7 +67,8 @@ void ColorEditor::paintColorBox(QPainter * painter, const QRect & rect, const QC int size = rect.height() - padding * 2 - 1; painter->save(); painter->setBrush(color); - painter->drawRoundedRect(rect.x() + padding + 3, + painter->drawRoundedRect( + rect.x() + padding + 3, rect.y() + padding, size, size, 0, 0, Qt::AbsoluteSize); painter->restore(); } @@ -108,13 +110,15 @@ void ColorEditor::onButtonClick() QColorDialog * dialog = new QColorDialog(color_, parentWidget() ); - connect(dialog, SIGNAL(currentColorChanged(const QColor&)), + connect( + dialog, SIGNAL(currentColorChanged(const QColor&)), property_, SLOT(setColor(const QColor&))); // Without this connection the PropertyTreeWidget does not update // the color info "live" when it changes in the dialog and the 3D // view. - connect(dialog, SIGNAL(currentColorChanged(const QColor&)), + connect( + dialog, SIGNAL(currentColorChanged(const QColor&)), parentWidget(), SLOT(update())); // On the TWM window manager under linux, and on OSX, this diff --git a/rviz_common/src/rviz_common/properties/covariance_property.cpp b/rviz_common/src/rviz_common/properties/covariance_property.cpp index a69ab6684..cc79642d7 100644 --- a/rviz_common/src/rviz_common/properties/covariance_property.cpp +++ b/rviz_common/src/rviz_common/properties/covariance_property.cpp @@ -54,68 +54,80 @@ CovarianceProperty::CovarianceProperty( const char * changed_slot) : BoolProperty(name, default_value, description, parent, changed_slot) { - position_property_ = new BoolProperty("Position", true, - "Whether or not to show the position part of covariances", - this, changed_slot, parent); + position_property_ = new BoolProperty( + "Position", true, + "Whether or not to show the position part of covariances", + this, changed_slot, parent); position_property_->setDisableChildrenIfFalse(true); - position_color_property_ = new ColorProperty("Color", QColor(204, 51, 204), - "Color to draw the position covariance ellipse.", - position_property_, changed_slot, parent); + position_color_property_ = new ColorProperty( + "Color", QColor(204, 51, 204), + "Color to draw the position covariance ellipse.", + position_property_, changed_slot, parent); - position_alpha_property_ = new FloatProperty("Alpha", 0.3f, - "0 is fully transparent, 1.0 is fully opaque.", - position_property_, changed_slot, parent); + position_alpha_property_ = new FloatProperty( + "Alpha", 0.3f, + "0 is fully transparent, 1.0 is fully opaque.", + position_property_, changed_slot, parent); position_alpha_property_->setMin(0); position_alpha_property_->setMax(1); - position_scale_property_ = new FloatProperty("Scale", 1.0f, - "Scale factor to be applied to covariance ellipse. " - "Corresponds to the number of standard deviations to display", - position_property_, changed_slot, parent); + position_scale_property_ = new FloatProperty( + "Scale", 1.0f, + "Scale factor to be applied to covariance ellipse. " + "Corresponds to the number of standard deviations to display", + position_property_, changed_slot, parent); position_scale_property_->setMin(0); - orientation_property_ = new BoolProperty("Orientation", true, - "Whether or not to show the orientation part of covariances", - this, changed_slot, parent); + orientation_property_ = new BoolProperty( + "Orientation", true, + "Whether or not to show the orientation part of covariances", + this, changed_slot, parent); orientation_property_->setDisableChildrenIfFalse(true); - orientation_frame_property_ = new EnumProperty("Frame", "Local", - "Frame used to display the orientation covariance.", - orientation_property_, changed_slot, parent); + orientation_frame_property_ = new EnumProperty( + "Frame", "Local", + "Frame used to display the orientation covariance.", + orientation_property_, changed_slot, parent); orientation_frame_property_->addOption("Local", rviz_rendering::Local); orientation_frame_property_->addOption("Fixed", rviz_rendering::Fixed); - orientation_colorstyle_property_ = new EnumProperty("Color Style", "Unique", - "Style to color the orientation covariance: " - "XYZ with same unique color or following RGB order", - orientation_property_, changed_slot, parent); + orientation_colorstyle_property_ = new EnumProperty( + "Color Style", "Unique", + "Style to color the orientation covariance: " + "XYZ with same unique color or following RGB order", + orientation_property_, changed_slot, parent); orientation_colorstyle_property_->addOption("Unique", rviz_rendering::Unique); orientation_colorstyle_property_->addOption("RGB", rviz_rendering::RGB); - connect(orientation_colorstyle_property_, SIGNAL(changed()), + connect( + orientation_colorstyle_property_, SIGNAL(changed()), this, SLOT(updateColorStyleChoice())); - orientation_color_property_ = new ColorProperty("Color", QColor(255, 255, 127), - "Color to draw the covariance ellipse.", - orientation_property_, changed_slot, parent); + orientation_color_property_ = new ColorProperty( + "Color", QColor(255, 255, 127), + "Color to draw the covariance ellipse.", + orientation_property_, changed_slot, parent); - orientation_alpha_property_ = new FloatProperty("Alpha", 0.5f, - "0 is fully transparent, 1.0 is fully opaque.", - orientation_property_, changed_slot, parent); + orientation_alpha_property_ = new FloatProperty( + "Alpha", 0.5f, + "0 is fully transparent, 1.0 is fully opaque.", + orientation_property_, changed_slot, parent); orientation_alpha_property_->setMin(0); orientation_alpha_property_->setMax(1); - orientation_offset_property_ = new FloatProperty("Offset", 1.0f, - "For 3D poses: the distance where to position the ellipses representing " - "orientation covariance. " - "For 2D poses: the height of the triangle representing the variance on yaw", - orientation_property_, changed_slot, parent); + orientation_offset_property_ = new FloatProperty( + "Offset", 1.0f, + "For 3D poses: the distance where to position the ellipses representing " + "orientation covariance. " + "For 2D poses: the height of the triangle representing the variance on yaw", + orientation_property_, changed_slot, parent); orientation_offset_property_->setMin(0); - orientation_scale_property_ = new FloatProperty("Scale", 1.0f, - "Scale factor to be applied to orientation covariance shapes. " - "Corresponds to the number of standard deviations to display", - orientation_property_, changed_slot, parent); + orientation_scale_property_ = new FloatProperty( + "Scale", 1.0f, + "Scale factor to be applied to orientation covariance shapes. " + "Corresponds to the number of standard deviations to display", + orientation_property_, changed_slot, parent); orientation_scale_property_->setMin(0); setDisableChildrenIfFalse(true); diff --git a/rviz_common/src/rviz_common/properties/display_group_visibility_property.cpp b/rviz_common/src/rviz_common/properties/display_group_visibility_property.cpp index 2d8026240..317ce969b 100644 --- a/rviz_common/src/rviz_common/properties/display_group_visibility_property.cpp +++ b/rviz_common/src/rviz_common/properties/display_group_visibility_property.cpp @@ -108,11 +108,13 @@ void DisplayGroupVisibilityProperty::onDisplayAdded(Display * display) auto display_group = qobject_cast(display); DisplayVisibilityProperty * vis_prop; if (display_group) { - vis_prop = new DisplayGroupVisibilityProperty(vis_bit_, display_group, parent_display_, "", - true, "Uncheck to hide everything in this Display Group", this); + vis_prop = new DisplayGroupVisibilityProperty( + vis_bit_, display_group, parent_display_, "", + true, "Uncheck to hide everything in this Display Group", this); } else { - vis_prop = new DisplayVisibilityProperty(vis_bit_, display, "", true, - "Show or hide this Display", this); + vis_prop = new DisplayVisibilityProperty( + vis_bit_, display, "", true, + "Show or hide this Display", this); } disp_vis_props_[display] = vis_prop; sortDisplayList(); diff --git a/rviz_common/src/rviz_common/properties/editable_enum_property.cpp b/rviz_common/src/rviz_common/properties/editable_enum_property.cpp index 91713e548..85d1589f3 100644 --- a/rviz_common/src/rviz_common/properties/editable_enum_property.cpp +++ b/rviz_common/src/rviz_common/properties/editable_enum_property.cpp @@ -77,7 +77,8 @@ QWidget * EditableEnumProperty::createEditor(QWidget * parent, const QStyleOptio EditableComboBox * cb = new EditableComboBox(parent); cb->addItems(strings_); cb->setEditText(getValue().toString() ); - QObject::connect(cb, SIGNAL(currentIndexChanged(const QString&)), this, + QObject::connect( + cb, SIGNAL(currentIndexChanged(const QString&)), this, SLOT(setString(const QString&))); // TODO(unknown): need to better handle string value which is not in list. diff --git a/rviz_common/src/rviz_common/properties/enum_property.cpp b/rviz_common/src/rviz_common/properties/enum_property.cpp index cb712511b..0c8dd60aa 100644 --- a/rviz_common/src/rviz_common/properties/enum_property.cpp +++ b/rviz_common/src/rviz_common/properties/enum_property.cpp @@ -86,7 +86,8 @@ QWidget * EnumProperty::createEditor(QWidget * parent, const QStyleOptionViewIte ComboBox * cb = new ComboBox(parent); cb->addItems(strings_); cb->setCurrentIndex(strings_.indexOf(getValue().toString() )); - QObject::connect(cb, SIGNAL(currentIndexChanged(const QString&)), this, + QObject::connect( + cb, SIGNAL(currentIndexChanged(const QString&)), this, SLOT(setString(const QString&))); // TODO(anyone): need to better handle string value which is not in list. diff --git a/rviz_common/src/rviz_common/properties/file_picker.cpp b/rviz_common/src/rviz_common/properties/file_picker.cpp index 97cc461da..f85385683 100644 --- a/rviz_common/src/rviz_common/properties/file_picker.cpp +++ b/rviz_common/src/rviz_common/properties/file_picker.cpp @@ -50,7 +50,8 @@ void FilePicker::onButtonClick() { auto dialog = new QFileDialog(parentWidget()); - connect(dialog, SIGNAL(fileSelected(const QString&)), + connect( + dialog, SIGNAL(fileSelected(const QString&)), file_name_property_, SLOT(setString(const QString&))); dialog->exec(); diff --git a/rviz_common/src/rviz_common/properties/line_edit_with_button.cpp b/rviz_common/src/rviz_common/properties/line_edit_with_button.cpp index fd573039e..baf54ae23 100644 --- a/rviz_common/src/rviz_common/properties/line_edit_with_button.cpp +++ b/rviz_common/src/rviz_common/properties/line_edit_with_button.cpp @@ -72,7 +72,8 @@ void LineEditWithButton::resizeEvent(QResizeEvent * event) // padding, and located all the way to the right. int button_width = height() - 2 * padding; int button_height = button_width; - button_->setGeometry(width() - button_width - padding, padding, + button_->setGeometry( + width() - button_width - padding, padding, button_width, button_height); } diff --git a/rviz_common/src/rviz_common/properties/property.cpp b/rviz_common/src/rviz_common/properties/property.cpp index 50030d673..a70d16f23 100644 --- a/rviz_common/src/rviz_common/properties/property.cpp +++ b/rviz_common/src/rviz_common/properties/property.cpp @@ -202,7 +202,8 @@ Property * Property::subProp(const QString & sub_name) for (Property * prop = this; prop != NULL; prop = prop->getParent() ) { ancestry = "\"" + prop->getName() + "\"->" + ancestry; } - printf("ERROR: Undefined property %s \"%s\" accessed.\n", qPrintable(ancestry), + printf( + "ERROR: Undefined property %s \"%s\" accessed.\n", qPrintable(ancestry), qPrintable(sub_name)); return failprop_; } @@ -459,7 +460,8 @@ void Property::loadValue(const Config & config) case QVariant::String: setValue(config.getValue().toString() ); break; case QVariant::Bool: setValue(config.getValue().toBool() ); break; default: - printf("Property::loadValue() TODO: error handling - unexpected QVariant type %d.\n", + printf( + "Property::loadValue() TODO: error handling - unexpected QVariant type %d.\n", static_cast(value_.type() )); break; } diff --git a/rviz_common/src/rviz_common/properties/property_tree_widget.cpp b/rviz_common/src/rviz_common/properties/property_tree_widget.cpp index fd45f8436..21aaa75e4 100644 --- a/rviz_common/src/rviz_common/properties/property_tree_widget.cpp +++ b/rviz_common/src/rviz_common/properties/property_tree_widget.cpp @@ -70,7 +70,8 @@ void PropertyTreeWidget::currentChanged( const QModelIndex & previous_current_index) { QTreeView::currentChanged(new_current_index, previous_current_index); - Q_EMIT currentPropertyChanged(static_cast( + Q_EMIT currentPropertyChanged( + static_cast( new_current_index.internalPointer() )); } @@ -85,21 +86,27 @@ void PropertyTreeWidget::selectionChanged( void PropertyTreeWidget::setModel(PropertyTreeModel * model) { if (model_) { - disconnect(model_, SIGNAL(propertyHiddenChanged(const Property*)), + disconnect( + model_, SIGNAL(propertyHiddenChanged(const Property*)), this, SLOT(propertyHiddenChanged(const Property*))); - disconnect(model_, SIGNAL(expand(const QModelIndex&)), + disconnect( + model_, SIGNAL(expand(const QModelIndex&)), this, SLOT(expand(const QModelIndex&))); - disconnect(model_, SIGNAL(collapse(const QModelIndex&)), + disconnect( + model_, SIGNAL(collapse(const QModelIndex&)), this, SLOT(collapse(const QModelIndex&))); } model_ = model; QTreeView::setModel(model_); if (model_) { - connect(model_, SIGNAL(propertyHiddenChanged(const Property*)), + connect( + model_, SIGNAL(propertyHiddenChanged(const Property*)), this, SLOT(propertyHiddenChanged(const Property*)), Qt::QueuedConnection); - connect(model_, SIGNAL(expand(const QModelIndex&)), + connect( + model_, SIGNAL(expand(const QModelIndex&)), this, SLOT(expand(const QModelIndex&))); - connect(model_, SIGNAL(collapse(const QModelIndex&)), + connect( + model_, SIGNAL(collapse(const QModelIndex&)), this, SLOT(collapse(const QModelIndex&))); // this will trigger all hiddenChanged events to get re-fired @@ -110,7 +117,8 @@ void PropertyTreeWidget::setModel(PropertyTreeModel * model) void PropertyTreeWidget::propertyHiddenChanged(const Property * property) { if (model_) { - setRowHidden(property->rowNumberInParent(), model_->parentIndex(property), + setRowHidden( + property->rowNumberInParent(), model_->parentIndex(property), property->getHidden() ); } } diff --git a/rviz_common/src/rviz_common/properties/property_tree_with_help.cpp b/rviz_common/src/rviz_common/properties/property_tree_with_help.cpp index 1574d6b22..1bc8d4718 100644 --- a/rviz_common/src/rviz_common/properties/property_tree_with_help.cpp +++ b/rviz_common/src/rviz_common/properties/property_tree_with_help.cpp @@ -61,7 +61,8 @@ PropertyTreeWithHelp::PropertyTreeWithHelp(QWidget * parent) _sizes.push_back(1); setSizes(_sizes); - connect(property_tree_, SIGNAL(currentPropertyChanged(const Property*)), + connect( + property_tree_, SIGNAL(currentPropertyChanged(const Property*)), this, SLOT(showHelpForProperty(const Property*))); } diff --git a/rviz_common/src/rviz_common/properties/ros_topic_property.cpp b/rviz_common/src/rviz_common/properties/ros_topic_property.cpp index 27d9dfef8..2699f6188 100644 --- a/rviz_common/src/rviz_common/properties/ros_topic_property.cpp +++ b/rviz_common/src/rviz_common/properties/ros_topic_property.cpp @@ -53,7 +53,8 @@ RosTopicProperty::RosTopicProperty( rviz_ros_node_(), message_type_(message_type) { - connect(this, SIGNAL(requestOptions(EditableEnumProperty*)), + connect( + this, SIGNAL(requestOptions(EditableEnumProperty*)), this, SLOT(fillTopicList())); } diff --git a/rviz_common/src/rviz_common/properties/tf_frame_property.cpp b/rviz_common/src/rviz_common/properties/tf_frame_property.cpp index a2116eb66..7ffe15d8b 100644 --- a/rviz_common/src/rviz_common/properties/tf_frame_property.cpp +++ b/rviz_common/src/rviz_common/properties/tf_frame_property.cpp @@ -59,7 +59,8 @@ TfFrameProperty::TfFrameProperty( include_fixed_frame_string_(include_fixed_frame_string) { // Parent class EditableEnumProperty has requestOptions() signal. - connect(this, SIGNAL(requestOptions(EditableEnumProperty*)), + connect( + this, SIGNAL(requestOptions(EditableEnumProperty*)), this, SLOT(fillFrameList())); setFrameManager(frame_manager); } @@ -78,12 +79,14 @@ bool TfFrameProperty::setValue(const QVariant & new_value) void TfFrameProperty::setFrameManager(FrameManagerIface * frame_manager) { if (frame_manager_ && include_fixed_frame_string_) { - disconnect(frame_manager_, SIGNAL(fixedFrameChanged()), + disconnect( + frame_manager_, SIGNAL(fixedFrameChanged()), this, SLOT(handleFixedFrameChange())); } frame_manager_ = frame_manager; if (frame_manager_ && include_fixed_frame_string_) { - connect(frame_manager_, SIGNAL(fixedFrameChanged()), + connect( + frame_manager_, SIGNAL(fixedFrameChanged()), this, SLOT(handleFixedFrameChange())); } } diff --git a/rviz_common/src/rviz_common/screenshot_dialog.cpp b/rviz_common/src/rviz_common/screenshot_dialog.cpp index f200e3370..8fef5ea50 100644 --- a/rviz_common/src/rviz_common/screenshot_dialog.cpp +++ b/rviz_common/src/rviz_common/screenshot_dialog.cpp @@ -69,9 +69,10 @@ ScreenshotDialog::ScreenshotDialog( QCheckBox * full_window_checkbox = new QCheckBox("Save entire rviz window"); - button_box_ = new QDialogButtonBox(QDialogButtonBox::Save | - QDialogButtonBox::Retry | - QDialogButtonBox::Cancel); + button_box_ = new QDialogButtonBox( + QDialogButtonBox::Save | + QDialogButtonBox::Retry | + QDialogButtonBox::Cancel); QVBoxLayout * main_layout = new QVBoxLayout; main_layout->addWidget(image_widget_, 100); @@ -81,7 +82,8 @@ ScreenshotDialog::ScreenshotDialog( setLayout(main_layout); - connect(button_box_, SIGNAL(clicked(QAbstractButton*)), this, + connect( + button_box_, SIGNAL(clicked(QAbstractButton*)), this, SLOT(onButtonClicked(QAbstractButton*))); connect(full_window_checkbox, SIGNAL(toggled(bool)), this, SLOT(setSaveFullWindow(bool))); connect(delay_timer_, SIGNAL(timeout()), this, SLOT(onTimeout())); @@ -91,8 +93,7 @@ void ScreenshotDialog::showEvent(QShowEvent * event) { if (first_time_) { QPoint center = main_window_->rect().center(); - move(center.x() - width() / 2, - center.y() - height() / 2); + move(center.x() - width() / 2, center.y() - height() / 2); first_time_ = false; } diff --git a/rviz_common/src/rviz_common/splash_screen.cpp b/rviz_common/src/rviz_common/splash_screen.cpp index e825b41f8..1d3bb423a 100644 --- a/rviz_common/src/rviz_common/splash_screen.cpp +++ b/rviz_common/src/rviz_common/splash_screen.cpp @@ -53,8 +53,10 @@ SplashScreen::SplashScreen(const QPixmap & pixmap) painter.drawPixmap(QPoint(0, 0), pixmap); QPixmap overlay = loadPixmap("package://rviz_common/images/splash_overlay.png"); - painter.drawTiledPixmap(QRect(0, pixmap.height() - overlay.height(), pixmap.width(), - pixmap.height() ), overlay); + painter.drawTiledPixmap( + QRect( + 0, pixmap.height() - overlay.height(), pixmap.width(), + pixmap.height() ), overlay); // draw version info QString version_info = "r" + QString(get_version().c_str()); diff --git a/rviz_common/src/rviz_common/time_panel.cpp b/rviz_common/src/rviz_common/time_panel.cpp index 5cfd4629a..5e827da33 100644 --- a/rviz_common/src/rviz_common/time_panel.cpp +++ b/rviz_common/src/rviz_common/time_panel.cpp @@ -152,9 +152,11 @@ void TimePanel::onDisplayAdded(Display * display) { DisplayGroup * display_group = qobject_cast(display); if (display_group) { - connect(display_group, SIGNAL(displayAdded(rviz::Display*)), this, + connect( + display_group, SIGNAL(displayAdded(rviz::Display*)), this, SLOT(onDisplayAdded(rviz::Display*))); - connect(display_group, SIGNAL(displayRemoved(rviz::Display*)), this, + connect( + display_group, SIGNAL(displayRemoved(rviz::Display*)), this, SLOT(onDisplayRemoved(rviz::Display*))); for (int i = 0; i < display_group->numDisplays(); i++) { diff --git a/rviz_common/src/rviz_common/view_controller.cpp b/rviz_common/src/rviz_common/view_controller.cpp index c9460574d..229f101ba 100644 --- a/rviz_common/src/rviz_common/view_controller.cpp +++ b/rviz_common/src/rviz_common/view_controller.cpp @@ -67,23 +67,28 @@ ViewController::ViewController() near_clip_property_->setMin(0.001f); near_clip_property_->setMax(10000); - stereo_enable_ = new BoolProperty("Enable Stereo Rendering", true, - "Render the main view in stereo if supported." - " On Linux this requires a recent version of Ogre and" - " an NVIDIA Quadro card with 3DVision glasses.", - this, SLOT(updateStereoProperties())); - stereo_eye_swap_ = new BoolProperty("Swap Stereo Eyes", false, - "Swap eyes if the monitor shows the left eye on the right.", - stereo_enable_, SLOT(updateStereoProperties()), this); - stereo_eye_separation_ = new FloatProperty("Stereo Eye Separation", 0.06f, - "Distance between eyes for stereo rendering.", - stereo_enable_, SLOT(updateStereoProperties()), this); - stereo_focal_distance_ = new FloatProperty("Stereo Focal Distance", 1.0f, - "Distance from eyes to screen. For stereo rendering.", - stereo_enable_, SLOT(updateStereoProperties()), this); - invert_z_ = new BoolProperty("Invert Z Axis", false, - "Invert camera's Z axis for Z-down environments/models.", - this, SLOT(updateStereoProperties())); + stereo_enable_ = new BoolProperty( + "Enable Stereo Rendering", true, + "Render the main view in stereo if supported." + " On Linux this requires a recent version of Ogre and" + " an NVIDIA Quadro card with 3DVision glasses.", + this, SLOT(updateStereoProperties())); + stereo_eye_swap_ = new BoolProperty( + "Swap Stereo Eyes", false, + "Swap eyes if the monitor shows the left eye on the right.", + stereo_enable_, SLOT(updateStereoProperties()), this); + stereo_eye_separation_ = new FloatProperty( + "Stereo Eye Separation", 0.06f, + "Distance between eyes for stereo rendering.", + stereo_enable_, SLOT(updateStereoProperties()), this); + stereo_focal_distance_ = new FloatProperty( + "Stereo Focal Distance", 1.0f, + "Distance from eyes to screen. For stereo rendering.", + stereo_enable_, SLOT(updateStereoProperties()), this); + invert_z_ = new BoolProperty( + "Invert Z Axis", false, + "Invert camera's Z axis for Z-down environments/models.", + this, SLOT(updateStereoProperties())); } void ViewController::initialize(DisplayContext * context) @@ -218,9 +223,11 @@ void ViewController::handleKeyEvent(QKeyEvent * event, RenderPanel * panel) if (event->key() == Qt::Key_F && context_->getViewPicker()) { QPoint mouse_rel_panel = panel->mapFromGlobal(QCursor::pos()); Ogre::Vector3 point_rel_world; // output of get3DPoint(). - if (context_->getViewPicker()->get3DPoint(panel, - mouse_rel_panel.x(), mouse_rel_panel.y(), - point_rel_world)) + if ( + context_->getViewPicker()->get3DPoint( + panel, + mouse_rel_panel.x(), mouse_rel_panel.y(), + point_rel_world)) { lookAt(point_rel_world); } diff --git a/rviz_common/src/rviz_common/views_panel.cpp b/rviz_common/src/rviz_common/views_panel.cpp index 75fc3ec4c..7be5ba5e6 100644 --- a/rviz_common/src/rviz_common/views_panel.cpp +++ b/rviz_common/src/rviz_common/views_panel.cpp @@ -82,9 +82,11 @@ ViewsPanel::ViewsPanel(QWidget * parent) connect(remove_button, SIGNAL(clicked()), this, SLOT(onDeleteClicked())); connect(rename_button, SIGNAL(clicked()), this, SLOT(renameSelected())); connect(zero_button, SIGNAL(clicked()), this, SLOT(onZeroClicked())); - connect(properties_view_, SIGNAL(clicked(const QModelIndex&)), this, + connect( + properties_view_, SIGNAL(clicked(const QModelIndex&)), this, SLOT(setCurrentViewFromIndex(const QModelIndex&))); - connect(properties_view_, SIGNAL(activated(const QModelIndex&)), this, + connect( + properties_view_, SIGNAL(activated(const QModelIndex&)), this, SLOT(setCurrentViewFromIndex(const QModelIndex&))); } @@ -97,7 +99,8 @@ void ViewsPanel::setViewManager(ViewManager * view_man) { if (view_man_) { disconnect(save_button_, SIGNAL(clicked()), view_man_, SLOT(copyCurrentToList())); - disconnect(camera_type_selector_, SIGNAL(activated(int)), this, + disconnect( + camera_type_selector_, SIGNAL(activated(int)), this, SLOT(onTypeSelectorChanged(int))); disconnect(view_man_, SIGNAL(currentChanged()), this, SLOT(onCurrentChanged())); } @@ -172,8 +175,8 @@ void ViewsPanel::renameSelected() } QString old_name = view->getName(); - QString new_name = QInputDialog::getText(this, "Rename View", "New Name?", QLineEdit::Normal, - old_name); + QString new_name = QInputDialog::getText( + this, "Rename View", "New Name?", QLineEdit::Normal, old_name); if (new_name.isEmpty() || new_name == old_name) { return; diff --git a/rviz_common/src/rviz_common/visualization_frame.cpp b/rviz_common/src/rviz_common/visualization_frame.cpp index aa30c0ca6..9b3752ade 100644 --- a/rviz_common/src/rviz_common/visualization_frame.cpp +++ b/rviz_common/src/rviz_common/visualization_frame.cpp @@ -289,8 +289,8 @@ void VisualizationFrame::initialize( hide_right_dock_button_ = new QToolButton(); hide_right_dock_button_->setContentsMargins(0, 0, 0, 0); hide_right_dock_button_->setArrowType(Qt::RightArrow); - hide_right_dock_button_->setSizePolicy(QSizePolicy(QSizePolicy::Minimum, - QSizePolicy::Expanding)); + hide_right_dock_button_->setSizePolicy( + QSizePolicy(QSizePolicy::Minimum, QSizePolicy::Expanding)); hide_right_dock_button_->setFixedWidth(16); hide_right_dock_button_->setAutoRaise(true); hide_right_dock_button_->setCheckable(true); @@ -368,7 +368,8 @@ void VisualizationFrame::initialize( Q_EMIT statusUpdate("RViz is ready."); connect(manager_, SIGNAL(preUpdate()), this, SLOT(updateFps())); - connect(manager_, SIGNAL(statusUpdate(const QString&)), this, + connect( + manager_, SIGNAL(statusUpdate(const QString&)), this, SIGNAL(statusUpdate(const QString&))); } @@ -426,7 +427,8 @@ void VisualizationFrame::loadPersistentSettings() recent_configs_.clear(); int num_recent = recent_configs_list.listLength(); for (int i = 0; i < num_recent; i++) { - recent_configs_.push_back(recent_configs_list.listChildAt( + recent_configs_.push_back( + recent_configs_list.listChildAt( i).getValue().toString().toStdString()); } } else { @@ -456,15 +458,18 @@ void VisualizationFrame::initMenus() { file_menu_ = menuBar()->addMenu("&File"); - QAction * file_menu_open_action = file_menu_->addAction("&Open Config", this, SLOT( - onOpen()), QKeySequence("Ctrl+O")); + QAction * file_menu_open_action = file_menu_->addAction( + "&Open Config", this, SLOT( + onOpen()), QKeySequence("Ctrl+O")); this->addAction(file_menu_open_action); - QAction * file_menu_save_action = file_menu_->addAction("&Save Config", this, SLOT( - onSave()), QKeySequence("Ctrl+S")); + QAction * file_menu_save_action = file_menu_->addAction( + "&Save Config", this, SLOT( + onSave()), QKeySequence("Ctrl+S")); this->addAction(file_menu_save_action); QAction * file_menu_save_as_action = - file_menu_->addAction("Save Config &As", this, SLOT(onSaveAs()), - QKeySequence("Ctrl+Shift+S")); + file_menu_->addAction( + "Save Config &As", this, SLOT(onSaveAs()), + QKeySequence("Ctrl+Shift+S")); this->addAction(file_menu_save_as_action); recent_configs_menu_ = file_menu_->addMenu("&Recent Configs"); @@ -475,8 +480,9 @@ void VisualizationFrame::initMenus() } file_menu_->addSeparator(); - QAction * file_menu_quit_action = file_menu_->addAction("&Quit", this, SLOT( - close()), QKeySequence("Ctrl+Q")); + QAction * file_menu_quit_action = file_menu_->addAction( + "&Quit", this, SLOT( + close()), QKeySequence("Ctrl+Q")); this->addAction(file_menu_quit_action); view_menu_ = menuBar()->addMenu("&Panels"); @@ -484,8 +490,9 @@ void VisualizationFrame::initMenus() delete_view_menu_ = view_menu_->addMenu("&Delete Panel"); delete_view_menu_->setEnabled(false); - QAction * fullscreen_action = view_menu_->addAction("&Fullscreen", this, SLOT(setFullScreen( - bool)), Qt::Key_F11); + QAction * fullscreen_action = view_menu_->addAction( + "&Fullscreen", this, SLOT( + setFullScreen(bool)), Qt::Key_F11); fullscreen_action->setCheckable(true); this->addAction(fullscreen_action); // Also add to window, or the shortcut doest work // when the menu is hidden. @@ -513,7 +520,8 @@ void VisualizationFrame::initToolbars() toolbar_->setObjectName("Tools"); toolbar_->setToolButtonStyle(Qt::ToolButtonTextBesideIcon); toolbar_actions_ = new QActionGroup(this); - connect(toolbar_actions_, SIGNAL(triggered(QAction*)), this, + connect( + toolbar_actions_, SIGNAL(triggered(QAction*)), this, SLOT(onToolbarActionTriggered(QAction*))); view_menu_->addAction(toolbar_->toggleViewAction()); @@ -530,8 +538,9 @@ void VisualizationFrame::initToolbars() remove_tool_button->setToolTip("Remove a tool from the toolbar"); remove_tool_button->setIcon(loadPixmap("package://rviz_common/icons/minus.png")); toolbar_->addWidget(remove_tool_button); - connect(remove_tool_menu_, SIGNAL(triggered(QAction*)), this, SLOT(onToolbarRemoveTool( - QAction*))); + connect( + remove_tool_menu_, SIGNAL(triggered(QAction*)), this, SLOT( + onToolbarRemoveTool(QAction*))); } void VisualizationFrame::hideDockImpl(Qt::DockWidgetArea area, bool hide) @@ -596,13 +605,14 @@ void VisualizationFrame::openNewPanelDialog() QString display_name; QStringList empty; - NewObjectDialog * dialog = new NewObjectDialog(panel_factory_, - "Panel", - empty, - empty, - &class_id, - &display_name, - this); + NewObjectDialog * dialog = new NewObjectDialog( + panel_factory_, + "Panel", + empty, + empty, + &class_id, + &display_name, + this); manager_->stopUpdate(); if (dialog->exec() == QDialog::Accepted) { addPanelByName(display_name, class_id); @@ -616,11 +626,12 @@ void VisualizationFrame::openNewToolDialog() QStringList empty; ToolManager * tool_man = manager_->getToolManager(); - NewObjectDialog * dialog = new NewObjectDialog(tool_man->getFactory(), - "Tool", - empty, - tool_man->getToolClasses(), - &class_id); + NewObjectDialog * dialog = new NewObjectDialog( + tool_man->getFactory(), + "Tool", + empty, + tool_man->getToolClasses(), + &class_id); manager_->stopUpdate(); if (dialog->exec() == QDialog::Accepted) { tool_man->addTool(class_id); @@ -929,8 +940,9 @@ bool VisualizationFrame::prepareToExit() QMessageBox box(this); box.setWindowTitle("Failed to save."); box.setText(getErrorMessage()); - box.setInformativeText(QString::fromStdString("Save copy of " + display_config_file_ + - " to another file?")); + box.setInformativeText( + QString::fromStdString( + "Save copy of " + display_config_file_ + " to another file?")); box.setStandardButtons(QMessageBox::Save | QMessageBox::Discard | QMessageBox::Cancel); box.setDefaultButton(QMessageBox::Save); int result = box.exec(); @@ -957,9 +969,10 @@ bool VisualizationFrame::prepareToExit() void VisualizationFrame::onOpen() { manager_->stopUpdate(); - QString filename = QFileDialog::getOpenFileName(this, "Choose a file to open", - QString::fromStdString(last_config_dir_), - "RViz config files (" CONFIG_EXTENSION_WILDCARD ")"); + QString filename = QFileDialog::getOpenFileName( + this, "Choose a file to open", + QString::fromStdString(last_config_dir_), + "RViz config files (" CONFIG_EXTENSION_WILDCARD ")"); manager_->startUpdate(); if (!filename.isEmpty()) { @@ -986,8 +999,9 @@ void VisualizationFrame::onSave() QMessageBox box(this); box.setWindowTitle("Failed to save."); box.setText(getErrorMessage()); - box.setInformativeText(QString::fromStdString("Save copy of " + display_config_file_ + - " to another file?")); + box.setInformativeText( + QString::fromStdString( + "Save copy of " + display_config_file_ + " to another file?")); box.setStandardButtons(QMessageBox::Save | QMessageBox::Cancel); box.setDefaultButton(QMessageBox::Save); if (box.exec() == QMessageBox::Save) { @@ -1000,9 +1014,10 @@ void VisualizationFrame::onSave() void VisualizationFrame::onSaveAs() { manager_->stopUpdate(); - QString q_filename = QFileDialog::getSaveFileName(this, "Choose a file to save to", - QString::fromStdString(last_config_dir_), - "RViz config files (" CONFIG_EXTENSION_WILDCARD ")"); + QString q_filename = QFileDialog::getSaveFileName( + this, "Choose a file to save to", + QString::fromStdString(last_config_dir_), + "RViz config files (" CONFIG_EXTENSION_WILDCARD ")"); manager_->startUpdate(); if (!q_filename.isEmpty()) { @@ -1025,7 +1040,8 @@ void VisualizationFrame::onSaveImage() { ScreenshotDialog * dialog = new ScreenshotDialog(this, render_panel_, QString::fromStdString(last_image_dir_)); - connect(dialog, SIGNAL(savedInDirectory(const QString&)), + connect( + dialog, SIGNAL(savedInDirectory(const QString&)), this, SLOT(setImageSaveDirectory(const QString&))); dialog->show(); } diff --git a/rviz_common/src/rviz_common/visualization_manager.cpp b/rviz_common/src/rviz_common/visualization_manager.cpp index fd224057c..c29049dc3 100644 --- a/rviz_common/src/rviz_common/visualization_manager.cpp +++ b/rviz_common/src/rviz_common/visualization_manager.cpp @@ -201,18 +201,21 @@ VisualizationManager::VisualizationManager( ip->setIcon(loadPixmap("package://rviz_common/icons/options.png")); global_options_ = ip; - fixed_frame_property_ = new TfFrameProperty("Fixed Frame", "base_link", - "Frame into which all data is transformed before being displayed.", - global_options_, frame_manager_, false, - SLOT(updateFixedFrame()), this); - - background_color_property_ = new ColorProperty("Background Color", QColor(48, 48, 48), - "Background color for the 3D view.", - global_options_, SLOT(updateBackgroundColor()), this); - - fps_property_ = new IntProperty("Frame Rate", 30, - "RViz will try to render this many frames per second.", - global_options_, SLOT(updateFps()), this); + fixed_frame_property_ = new TfFrameProperty( + "Fixed Frame", "base_link", + "Frame into which all data is transformed before being displayed.", + global_options_, frame_manager_, false, + SLOT(updateFixedFrame()), this); + + background_color_property_ = new ColorProperty( + "Background Color", QColor(48, 48, 48), + "Background color for the 3D view.", + global_options_, SLOT(updateBackgroundColor()), this); + + fps_property_ = new IntProperty( + "Frame Rate", 30, + "RViz will try to render this many frames per second.", + global_options_, SLOT(updateFps()), this); root_display_group_->initialize(this); // only initialize() a Display // after its sub-properties are created. @@ -233,8 +236,8 @@ VisualizationManager::VisualizationManager( executor_->add_node(rviz_ros_node_.lock()->get_raw_node()); // TODO(wjwwood): redo with executors? #if 0 - private_->threaded_queue_threads_.create_thread(std::bind(&VisualizationManager:: - threadedQueueThreadFunc, this)); + private_->threaded_queue_threads_.create_thread( + std::bind(&VisualizationManager::threadedQueueThreadFunc, this)); #endif display_factory_ = new DisplayFactory(); @@ -460,12 +463,12 @@ void VisualizationManager::updateFrames() // fixed_prop->setToWarn(); std::stringstream ss; ss << "No tf data. Actual error: " << error; - global_status_->setStatus(StatusProperty::Warn, "Fixed Frame", QString::fromStdString( - ss.str())); + global_status_->setStatus( + StatusProperty::Warn, "Fixed Frame", QString::fromStdString(ss.str())); } else { // fixed_prop->setToError(); - global_status_->setStatus(StatusProperty::Error, "Fixed Frame", - QString::fromStdString(error)); + global_status_->setStatus( + StatusProperty::Error, "Fixed Frame", QString::fromStdString(error)); } } else { // fixed_prop->setToOK(); diff --git a/rviz_common/test/display_test.cpp b/rviz_common/test/display_test.cpp index 50fa143cb..586558ace 100644 --- a/rviz_common/test/display_test.cpp +++ b/rviz_common/test/display_test.cpp @@ -120,7 +120,8 @@ TEST(Display, save_properties) { // Since we instantiated the display directly instead of using the // DisplayFactory, it won't know its class name. - EXPECT_EQ(std::string( + EXPECT_EQ( + std::string( "Class: \"\"\n" "Color: 10; 20; 30\n" "Count: 37\n" @@ -158,7 +159,8 @@ TEST(DisplayGroup, save_properties) { // Since we instantiated the display directly instead of using the // DisplayFactory, it won't know its class name. - EXPECT_EQ(std::string( + EXPECT_EQ( + std::string( "Class: \"\"\n" "Displays:\n" " - Class: \"\"\n" diff --git a/rviz_common/test/frame_manager_test.cpp b/rviz_common/test/frame_manager_test.cpp index 8a03affb9..eec969267 100644 --- a/rviz_common/test/frame_manager_test.cpp +++ b/rviz_common/test/frame_manager_test.cpp @@ -95,7 +95,8 @@ TEST_F(FrameManagerTestFixture, transformHasProblems_uses_transformer_method) { *frame_transformer_, canTransform(_, source_frame_name, _, _)).WillOnce(Return(true)); std::string error; - EXPECT_FALSE(frame_manager_->transformHasProblems( + EXPECT_FALSE( + frame_manager_->transformHasProblems( source_frame_name, rclcpp::Time(0, 0, clock_->get_clock_type()), error)); } diff --git a/rviz_common/test/mock_frame_transformer.hpp b/rviz_common/test/mock_frame_transformer.hpp index 84e3323e8..6fcf07099 100644 --- a/rviz_common/test/mock_frame_transformer.hpp +++ b/rviz_common/test/mock_frame_transformer.hpp @@ -43,43 +43,51 @@ class MockFrameTransformer : public rviz_common::transformation::FrameTransformer { public: - MOCK_METHOD2(initialize, void( + MOCK_METHOD2( + initialize, void( rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr rviz_ros_node, rclcpp::Clock::SharedPtr clock)); MOCK_METHOD0(clear, void()); MOCK_CONST_METHOD0(getAllFrameNames, std::vector()); - MOCK_METHOD2(transform, geometry_msgs::msg::PoseStamped( + MOCK_METHOD2( + transform, geometry_msgs::msg::PoseStamped( const geometry_msgs::msg::PoseStamped & pose_in, const std::string & frame)); - MOCK_CONST_METHOD3(lookupTransform, geometry_msgs::msg::TransformStamped( + MOCK_CONST_METHOD3( + lookupTransform, geometry_msgs::msg::TransformStamped( const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time)); - MOCK_CONST_METHOD5(lookupTransform, geometry_msgs::msg::TransformStamped( + MOCK_CONST_METHOD5( + lookupTransform, geometry_msgs::msg::TransformStamped( const std::string & target_frame, const tf2::TimePoint & target_time, const std::string & source_frame, const tf2::TimePoint & source_time, const std::string & fixed_Frame)); - MOCK_CONST_METHOD4(canTransform, bool( + MOCK_CONST_METHOD4( + canTransform, bool( const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time, std::string * error_msg)); - MOCK_CONST_METHOD6(canTransform, bool( + MOCK_CONST_METHOD6( + canTransform, bool( const std::string & target_frame, const tf2::TimePoint & target_time, const std::string & source_frame, const tf2::TimePoint & source_time, const std::string & fixed_frame, std::string * error_msg)); - MOCK_METHOD5(waitForTransform, tf2_ros::TransformStampedFuture( + MOCK_METHOD5( + waitForTransform, tf2_ros::TransformStampedFuture( const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time, const tf2::Duration & timeout, tf2_ros::TransformReadyCallback callback)); MOCK_CONST_METHOD2(frameHasProblems, bool(const std::string & frame, std::string & error)); - MOCK_METHOD0(getConnector, + MOCK_METHOD0( + getConnector, rviz_common::transformation::TransformationLibraryConnector::WeakPtr()); }; diff --git a/rviz_common/test/mock_window_manager_interface.hpp b/rviz_common/test/mock_window_manager_interface.hpp index e4c4fd592..6a79c594f 100644 --- a/rviz_common/test/mock_window_manager_interface.hpp +++ b/rviz_common/test/mock_window_manager_interface.hpp @@ -42,7 +42,8 @@ class MockWindowManagerInterface : public rviz_common::WindowManagerInterface public: MOCK_METHOD0(getParentWindow, QWidget * ()); - MOCK_METHOD4(addPane, + MOCK_METHOD4( + addPane, rviz_common::PanelDockWidget *( const QString & name, QWidget * pane, Qt::DockWidgetArea area, bool floating)); diff --git a/rviz_common/test/properties/qos_profile_property_test.cpp b/rviz_common/test/properties/qos_profile_property_test.cpp index e836e9703..977a42fd7 100644 --- a/rviz_common/test/properties/qos_profile_property_test.cpp +++ b/rviz_common/test/properties/qos_profile_property_test.cpp @@ -66,11 +66,14 @@ TEST(QosProfilePropertyTest, enum_properties_set_enum_members_of_profile) { parent.childAt(3)->setValue("Volatile"); EXPECT_THAT(called, IsTrue()); - EXPECT_THAT(qos_profile.get_rmw_qos_profile().history, + EXPECT_THAT( + qos_profile.get_rmw_qos_profile().history, Eq(RMW_QOS_POLICY_HISTORY_KEEP_ALL)); - EXPECT_THAT(qos_profile.get_rmw_qos_profile().reliability, + EXPECT_THAT( + qos_profile.get_rmw_qos_profile().reliability, Eq(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT)); - EXPECT_THAT(qos_profile.get_rmw_qos_profile().durability, + EXPECT_THAT( + qos_profile.get_rmw_qos_profile().durability, Eq(RMW_QOS_POLICY_DURABILITY_VOLATILE)); } diff --git a/rviz_common/test/property_test.cpp b/rviz_common/test/property_test.cpp index f0c595275..e55f4d62f 100644 --- a/rviz_common/test/property_test.cpp +++ b/rviz_common/test/property_test.cpp @@ -74,9 +74,11 @@ TEST(Property, set_value_events) { TEST(Property, children) { Property * display = new Property("Test"); new Property("Alpha", 0.5, "The amount of transparency to apply to the grid lines.", display); - Property * beta = new Property("Beta Band", 10, "The number of betas to apply to the grid lines.", - display); - new Property("Gamma Topic", "chubby", "The topic on which to listen for Gamma messages.", + Property * beta = new Property( + "Beta Band", 10, "The number of betas to apply to the grid lines.", + display); + new Property( + "Gamma Topic", "chubby", "The topic on which to listen for Gamma messages.", display); Property * position = new Property("Position", QVariant(), "Position of the chub.", display); new Property("X", 1.1f, "X component of the position of the chub.", position); @@ -166,7 +168,8 @@ TEST(VectorProperty, set_value_events) { r.reset(); p.subProp("Z")->setValue(2.1); - EXPECT_EQ(" aboutToChange, v=0.1; 0.0001; 1000 changed, v=0.1; 0.0001; 2.1", + EXPECT_EQ( + " aboutToChange, v=0.1; 0.0001; 1000 changed, v=0.1; 0.0001; 2.1", r.result().toStdString() ); } @@ -240,12 +243,14 @@ TEST(QuaternionProperty, set_value_events) { p.connect(&p, SIGNAL(changed()), &r, SLOT(changed())); p.setQuaternion(Ogre::Quaternion(1, .1f, .0001f, 1000)); - EXPECT_EQ(" aboutToChange, v=0; 0; 0; 1 changed, v=0.1; 0.0001; 1000; 1", + EXPECT_EQ( + " aboutToChange, v=0; 0; 0; 1 changed, v=0.1; 0.0001; 1000; 1", r.result().toStdString() ); r.reset(); p.subProp("Z")->setValue(2.1); - EXPECT_EQ(" aboutToChange, v=0.1; 0.0001; 1000; 1 changed, v=0.1; 0.0001; 2.1; 1", + EXPECT_EQ( + " aboutToChange, v=0.1; 0.0001; 1000; 1 changed, v=0.1; 0.0001; 2.1; 1", r.result().toStdString() ); } diff --git a/rviz_common/test/transformation/identity_frame_transformer_test.cpp b/rviz_common/test/transformation/identity_frame_transformer_test.cpp index ccb0bf0a1..9a860e0f6 100644 --- a/rviz_common/test/transformation/identity_frame_transformer_test.cpp +++ b/rviz_common/test/transformation/identity_frame_transformer_test.cpp @@ -89,7 +89,8 @@ TEST_F(IdentityTransformerFixture, canTransform_returns_true) { EXPECT_THAT(error, Eq("")); error = ""; - EXPECT_TRUE(transformer_->canTransform( + EXPECT_TRUE( + transformer_->canTransform( "any_target", tf2::TimePointZero, "any_source", diff --git a/rviz_common/test/visualizer_app_test.cpp b/rviz_common/test/visualizer_app_test.cpp index ab9f3416f..b10d88aea 100644 --- a/rviz_common/test/visualizer_app_test.cpp +++ b/rviz_common/test/visualizer_app_test.cpp @@ -39,7 +39,8 @@ class MockRosNodeStorage : public rviz_common::ros_integration::RosClientAbstractionIface { public: - MOCK_METHOD4(init, + MOCK_METHOD4( + init, rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr( int argc, char ** argv, const std::string & name, bool anonymous_name)); MOCK_METHOD0(ok, bool()); diff --git a/rviz_default_plugins/include/rviz_default_plugins/displays/pointcloud/point_cloud_scalar_display.hpp b/rviz_default_plugins/include/rviz_default_plugins/displays/pointcloud/point_cloud_scalar_display.hpp index 168ce90a4..41a7d976d 100644 --- a/rviz_default_plugins/include/rviz_default_plugins/displays/pointcloud/point_cloud_scalar_display.hpp +++ b/rviz_default_plugins/include/rviz_default_plugins/displays/pointcloud/point_cloud_scalar_display.hpp @@ -184,7 +184,8 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC PointCloudScalarDisplay float coordinate_value = 0.0; for (int i = 0; i < 3; i++) { - memcpy(&point_cloud_message->data[point_cloud_message->fields[i].offset], + memcpy( + &point_cloud_message->data[point_cloud_message->fields[i].offset], &coordinate_value, field_size_32_); } } @@ -192,7 +193,8 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC PointCloudScalarDisplay void copyScalarValue( std::shared_ptr point_cloud_message, double scalar_value) { - memcpy(&point_cloud_message->data[point_cloud_message->fields[3].offset], + memcpy( + &point_cloud_message->data[point_cloud_message->fields[3].offset], &scalar_value, field_size_64_); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp index 4f3417075..e871d3edb 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/camera/camera_display.cpp @@ -336,7 +336,8 @@ void CameraDisplay::clear() camera_info_topic = camera_info_topic.substr(0, camera_info_topic.rfind("/") + 1) + "camera_info"; - setStatus(StatusLevel::Warn, CAM_INFO_STATUS, + setStatus( + StatusLevel::Warn, CAM_INFO_STATUS, "No CameraInfo received on [" + QString::fromStdString(camera_info_topic) + "]. " "Topic may not exist."); @@ -378,21 +379,24 @@ bool CameraDisplay::updateCamera() camera_info_topic = camera_info_topic.substr(0, camera_info_topic.rfind("/") + 1) + "camera_info"; - setStatus(StatusLevel::Warn, CAM_INFO_STATUS, + setStatus( + StatusLevel::Warn, CAM_INFO_STATUS, "Expecting Camera Info on topic [" + QString::fromStdString(camera_info_topic) + "]. " "No CameraInfo received. Topic may not exist."); return false; } if (!validateFloats(*info)) { - setStatus(StatusLevel::Error, CAM_INFO_STATUS, + setStatus( + StatusLevel::Error, CAM_INFO_STATUS, "Contains invalid floating point values (nans or infs)"); return false; } rclcpp::Time rviz_time = context_->getFrameManager()->getTime(); if (timeDifferenceInExactSyncMode(image, rviz_time)) { - setStatus(StatusLevel::Warn, TIME_STATUS, + setStatus( + StatusLevel::Warn, TIME_STATUS, QString("Time-syncing active and no image at timestamp ") + rviz_time.nanoseconds() + "."); return false; } @@ -412,7 +416,8 @@ bool CameraDisplay::updateCamera() auto dimensions = getImageDimensions(info); if (dimensions.height == 0.0 || dimensions.width == 0.0) { - setStatus(StatusLevel::Error, CAM_INFO_STATUS, + setStatus( + StatusLevel::Error, CAM_INFO_STATUS, "Could not determine width/height of image " "due to malformed CameraInfo (either width or height is 0)"); return false; @@ -420,7 +425,8 @@ bool CameraDisplay::updateCamera() translatePosition(position, info, orientation); if (!rviz_common::validateFloats(position)) { - setStatus(StatusLevel::Error, CAM_INFO_STATUS, + setStatus( + StatusLevel::Error, CAM_INFO_STATUS, "CameraInfo/P resulted in an invalid position calculation (nans or infs)"); return false; } @@ -467,14 +473,14 @@ ImageDimensions CameraDisplay::getImageDimensions( // If the image width is 0 due to a malformed caminfo, try to grab the width from the image. if (dimensions.width == 0) { - RVIZ_COMMON_LOG_DEBUG_STREAM("Malformed CameraInfo on camera" << qPrintable(getName()) << ", " - "width = 0"); + RVIZ_COMMON_LOG_DEBUG_STREAM( + "Malformed CameraInfo on camera" << qPrintable(getName()) << ", width = 0"); dimensions.width = texture_->getWidth(); } if (dimensions.height == 0) { - RVIZ_COMMON_LOG_DEBUG_STREAM("Malformed CameraInfo on camera" << qPrintable(getName()) << "," - " height = 0"); + RVIZ_COMMON_LOG_DEBUG_STREAM( + "Malformed CameraInfo on camera" << qPrintable(getName()) << ", height = 0"); dimensions.height = texture_->getHeight(); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/grid/grid_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/grid/grid_display.cpp index 0a5264eb8..d4eeff15e 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/grid/grid_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/grid/grid_display.cpp @@ -61,57 +61,67 @@ using rviz_rendering::Grid; GridDisplay::GridDisplay() { - frame_property_ = new TfFrameProperty("Reference Frame", TfFrameProperty::FIXED_FRAME_STRING, - "The TF frame this grid will use for its origin.", - this, 0, true); - - cell_count_property_ = new IntProperty("Plane Cell Count", 10, - "The number of cells to draw in the plane of the grid.", - this, SLOT(updateCellCount())); + frame_property_ = new TfFrameProperty( + "Reference Frame", TfFrameProperty::FIXED_FRAME_STRING, + "The TF frame this grid will use for its origin.", + this, 0, true); + + cell_count_property_ = new IntProperty( + "Plane Cell Count", 10, + "The number of cells to draw in the plane of the grid.", + this, SLOT(updateCellCount())); cell_count_property_->setMin(1); - height_property_ = new IntProperty("Normal Cell Count", 0, - "The number of cells to draw along the normal vector of the grid. " - " Setting to anything but 0 makes the grid 3D.", - this, SLOT(updateHeight())); + height_property_ = new IntProperty( + "Normal Cell Count", 0, + "The number of cells to draw along the normal vector of the grid. " + " Setting to anything but 0 makes the grid 3D.", + this, SLOT(updateHeight())); height_property_->setMin(0); - cell_size_property_ = new FloatProperty("Cell Size", 1.0f, - "The length, in meters, of the side of each cell.", - this, SLOT(updateCellSize())); + cell_size_property_ = new FloatProperty( + "Cell Size", 1.0f, + "The length, in meters, of the side of each cell.", + this, SLOT(updateCellSize())); cell_size_property_->setMin(0.0001f); - style_property_ = new EnumProperty("Line Style", "Lines", - "The rendering operation to use to draw the grid lines.", - this, SLOT(updateStyle())); + style_property_ = new EnumProperty( + "Line Style", "Lines", + "The rendering operation to use to draw the grid lines.", + this, SLOT(updateStyle())); style_property_->addOption("Lines", Grid::Lines); style_property_->addOption("Billboards", Grid::Billboards); - line_width_property_ = new FloatProperty("Line Width", 0.03f, - "The width, in meters, of each grid line.", - style_property_, SLOT(updateLineWidth()), this); + line_width_property_ = new FloatProperty( + "Line Width", 0.03f, + "The width, in meters, of each grid line.", + style_property_, SLOT(updateLineWidth()), this); line_width_property_->setMin(0.001f); line_width_property_->hide(); - color_property_ = new ColorProperty("Color", Qt::gray, - "The color of the grid lines.", - this, SLOT(updateColor())); - alpha_property_ = new FloatProperty("Alpha", 0.5f, - "The amount of transparency to apply to the grid lines.", - this, SLOT(updateColor())); + color_property_ = new ColorProperty( + "Color", Qt::gray, + "The color of the grid lines.", + this, SLOT(updateColor())); + alpha_property_ = new FloatProperty( + "Alpha", 0.5f, + "The amount of transparency to apply to the grid lines.", + this, SLOT(updateColor())); alpha_property_->setMin(0.0f); alpha_property_->setMax(1.0f); - plane_property_ = new EnumProperty("Plane", "XY", - "The plane to draw the grid along.", - this, SLOT(updatePlane())); + plane_property_ = new EnumProperty( + "Plane", "XY", + "The plane to draw the grid along.", + this, SLOT(updatePlane())); plane_property_->addOption("XY", XY); plane_property_->addOption("XZ", XZ); plane_property_->addOption("YZ", YZ); - offset_property_ = new VectorProperty("Offset", Ogre::Vector3::ZERO, - "Allows you to offset the grid from the origin of the reference frame. In meters.", - this, SLOT(updateOffset())); + offset_property_ = new VectorProperty( + "Offset", Ogre::Vector3::ZERO, + "Allows you to offset the grid from the origin of the reference frame. In meters.", + this, SLOT(updateOffset())); } GridDisplay::~GridDisplay() = default; @@ -122,12 +132,13 @@ void GridDisplay::onInitialize() color.setAlphaF(alpha_property_->getFloat() ); frame_property_->setFrameManager(context_->getFrameManager()); - grid_ = std::make_unique(scene_manager_, scene_node_, - (Grid::Style) style_property_->getOptionInt(), - cell_count_property_->getInt(), - cell_size_property_->getFloat(), - line_width_property_->getFloat(), - qtToOgre(color)); + grid_ = std::make_unique( + scene_manager_, scene_node_, + (Grid::Style) style_property_->getOptionInt(), + cell_count_property_->getInt(), + cell_size_property_->getFloat(), + line_width_property_->getFloat(), + qtToOgre(color)); grid_->getSceneNode()->setVisible(false); updatePlane(); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp index fd455de0c..ed180dc4a 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp @@ -61,12 +61,14 @@ GridCellsDisplay::GridCellsDisplay(rviz_common::DisplayContext * context) GridCellsDisplay::GridCellsDisplay() : last_frame_count_(uint64_t(-1)) { - color_property_ = new rviz_common::properties::ColorProperty("Color", QColor(25, 255, 0), - "Color of the grid cells.", this, SLOT(updateColor())); - - alpha_property_ = new rviz_common::properties::FloatProperty("Alpha", 1.0f, - "Amount of transparency to apply to the cells.", - this, SLOT(updateAlpha())); + color_property_ = new rviz_common::properties::ColorProperty( + "Color", QColor(25, 255, 0), + "Color of the grid cells.", this, SLOT(updateColor())); + + alpha_property_ = new rviz_common::properties::FloatProperty( + "Alpha", 1.0f, + "Amount of transparency to apply to the cells.", + this, SLOT(updateAlpha())); alpha_property_->setMin(0); alpha_property_->setMax(1); } @@ -154,19 +156,22 @@ bool validateFloats(const nav_msgs::msg::GridCells & msg) bool GridCellsDisplay::messageIsValid(nav_msgs::msg::GridCells::ConstSharedPtr msg) { if (!validateFloats(*msg)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); return false; } if (msg->cell_width == 0 || msg->cell_height == 0) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "One of the Cell's dimension is zero, cells will be invisible."); return false; } if (msg->cells.empty()) { - setStatus(rviz_common::properties::StatusProperty::Warn, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Warn, "Topic", "Message is empty: there are no cells to be shown."); return false; } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/image/ros_image_texture.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/image/ros_image_texture.cpp index 6596ce9ea..713f64e1e 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/image/ros_image_texture.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/image/ros_image_texture.cpp @@ -306,7 +306,8 @@ void ROSImageTexture::loadImageToOgreImage( { Ogre::DataStreamPtr pixel_stream; // C-style cast is used to bypass the const modifier - pixel_stream.reset(new Ogre::MemoryDataStream( + pixel_stream.reset( + new Ogre::MemoryDataStream( (uint8_t *) &image_data.data_ptr_[0], image_data.size_)); // NOLINT ogre_image.loadRawData(pixel_stream, width_, height_, 1, image_data.pixel_format_, 1, 0); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_control.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_control.cpp index 7d0a2d296..f553f29fa 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_control.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_control.cpp @@ -526,7 +526,8 @@ Ogre::Ray InteractiveMarkerControl::getMouseRayInReferenceFrame( // convert ray into reference frame mouse_ray.setOrigin(reference_node_->convertWorldToLocalPosition(mouse_ray.getOrigin())); - mouse_ray.setDirection(reference_node_->convertWorldToLocalOrientation( + mouse_ray.setDirection( + reference_node_->convertWorldToLocalOrientation( Ogre::Quaternion::IDENTITY) * mouse_ray.getDirection()); return mouse_ray; diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_display.cpp index 7f1d701e6..dbd0cf761 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/interactive_markers/interactive_marker_display.cpp @@ -113,7 +113,8 @@ void InteractiveMarkerDisplay::onInitialize() auto frame_transformer = context_->getFrameManager()->getTransformer(); rclcpp::Node::SharedPtr node = ros_node_abstraction->get_raw_node(); - interactive_marker_client_.reset(new interactive_markers::InteractiveMarkerClient( + interactive_marker_client_.reset( + new interactive_markers::InteractiveMarkerClient( node, frame_transformer, fixed_frame_.toStdString())); interactive_marker_client_->setInitializeCallback( @@ -123,10 +124,11 @@ void InteractiveMarkerDisplay::onInitialize() interactive_marker_client_->setResetCallback( std::bind(&InteractiveMarkerDisplay::resetCallback, this)); interactive_marker_client_->setStatusCallback( - std::bind(&InteractiveMarkerDisplay::statusCallback, - this, - std::placeholders::_1, - std::placeholders::_2)); + std::bind( + &InteractiveMarkerDisplay::statusCallback, + this, + std::placeholders::_1, + std::placeholders::_2)); subscribe(); } @@ -146,7 +148,8 @@ void InteractiveMarkerDisplay::namespaceChanged() unsubscribe(); if (interactive_marker_namespace_property_->isEmpty()) { - setStatus(rviz_common::properties::StatusProperty::Error, + setStatus( + rviz_common::properties::StatusProperty::Error, "Interactive Marker Client", QString("Error connecting: empty namespace")); return; diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/map/map_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/map/map_display.cpp index 487e0e275..f453bc555 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/map/map_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/map/map_display.cpp @@ -87,49 +87,57 @@ MapDisplay::MapDisplay() update_profile_property_ = new rviz_common::properties::QosProfileProperty( update_topic_property_, update_profile_); - alpha_property_ = new rviz_common::properties::FloatProperty("Alpha", 0.7f, - "Amount of transparency to apply to the map.", - this, SLOT(updateAlpha())); + alpha_property_ = new rviz_common::properties::FloatProperty( + "Alpha", 0.7f, + "Amount of transparency to apply to the map.", + this, SLOT(updateAlpha())); alpha_property_->setMin(0); alpha_property_->setMax(1); - color_scheme_property_ = new rviz_common::properties::EnumProperty("Color Scheme", "map", - "How to color the occupancy values.", - this, SLOT(updatePalette())); + color_scheme_property_ = new rviz_common::properties::EnumProperty( + "Color Scheme", "map", + "How to color the occupancy values.", + this, SLOT(updatePalette())); // Option values here must correspond to indices in palette_textures_ array in onInitialize() // below. color_scheme_property_->addOption("map", 0); color_scheme_property_->addOption("costmap", 1); color_scheme_property_->addOption("raw", 2); - draw_under_property_ = new rviz_common::properties::BoolProperty("Draw Behind", false, - "Rendering option, controls whether or not the map is always" - " drawn behind everything else.", - this, SLOT(updateDrawUnder())); + draw_under_property_ = new rviz_common::properties::BoolProperty( + "Draw Behind", false, + "Rendering option, controls whether or not the map is always" + " drawn behind everything else.", + this, SLOT(updateDrawUnder())); - resolution_property_ = new rviz_common::properties::FloatProperty("Resolution", 0, - "Resolution of the map. (not editable)", this); + resolution_property_ = new rviz_common::properties::FloatProperty( + "Resolution", 0, + "Resolution of the map. (not editable)", this); resolution_property_->setReadOnly(true); - width_property_ = new rviz_common::properties::IntProperty("Width", 0, - "Width of the map, in meters. (not editable)", this); + width_property_ = new rviz_common::properties::IntProperty( + "Width", 0, + "Width of the map, in meters. (not editable)", this); width_property_->setReadOnly(true); - height_property_ = new rviz_common::properties::IntProperty("Height", 0, - "Height of the map, in meters. (not editable)", this); + height_property_ = new rviz_common::properties::IntProperty( + "Height", 0, + "Height of the map, in meters. (not editable)", this); height_property_->setReadOnly(true); - position_property_ = new rviz_common::properties::VectorProperty("Position", Ogre::Vector3::ZERO, - "Position of the bottom left corner of the map, in meters. (not editable)", - this); + position_property_ = new rviz_common::properties::VectorProperty( + "Position", Ogre::Vector3::ZERO, + "Position of the bottom left corner of the map, in meters. (not editable)", + this); position_property_->setReadOnly(true); orientation_property_ = new rviz_common::properties::QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY, "Orientation of the map. (not editable)", this); orientation_property_->setReadOnly(true); - transform_timestamp_property_ = new rviz_common::properties::BoolProperty("Use Timestamp", false, - "Use map header timestamp when transforming", this, SLOT(transformMap())); + transform_timestamp_property_ = new rviz_common::properties::BoolProperty( + "Use Timestamp", false, + "Use map header timestamp when transforming", this, SLOT(transformMap())); } MapDisplay::~MapDisplay() @@ -197,7 +205,8 @@ void MapDisplay::subscribe() } if (topic_property_->isEmpty()) { - setStatus(rviz_common::properties::StatusProperty::Error, + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", QString("Error subscribing: Empty topic name")); return; @@ -312,7 +321,8 @@ void MapDisplay::incomingUpdate(const map_msgs::msg::OccupancyGridUpdate::ConstS QString::number(update_messages_received_) + " update messages received"); if (updateDataOutOfBounds(update)) { - setStatus(rviz_common::properties::StatusProperty::Error, + setStatus( + rviz_common::properties::StatusProperty::Error, "Update", "Update area outside of original map area."); return; } @@ -359,8 +369,9 @@ void MapDisplay::createSwatches() const size_t maximum_number_swatch_splittings = 4; for (size_t i = 0; i < maximum_number_swatch_splittings; ++i) { - RVIZ_COMMON_LOG_INFO_STREAM("Trying to create a map of size " << - width << " x " << height << " using " << number_swatches << " swatches"); + RVIZ_COMMON_LOG_INFO_STREAM( + "Trying to create a map of size " << + width << " x " << height << " using " << number_swatches << " swatches"); swatches_.clear(); try { tryCreateSwatches(width, height, resolution, swatch_width, swatch_height, number_swatches); @@ -373,16 +384,18 @@ void MapDisplay::createSwatches() doubleSwatchNumber(swatch_width, swatch_height, number_swatches); } } - RVIZ_COMMON_LOG_ERROR_STREAM("Creating " << number_swatches << "failed. " - "This map is too large to be displayed by RViz."); + RVIZ_COMMON_LOG_ERROR_STREAM( + "Creating " << number_swatches << "failed. " + "This map is too large to be displayed by RViz."); swatches_.clear(); } void MapDisplay::doubleSwatchNumber( size_t & swatch_width, size_t & swatch_height, int & number_swatches) const { - RVIZ_COMMON_LOG_ERROR_STREAM("Failed to create map using " << number_swatches << " swatches. " - "At least one swatch seems to need too much memory"); + RVIZ_COMMON_LOG_ERROR_STREAM( + "Failed to create map using " << number_swatches << " swatches. " + "At least one swatch seems to need too much memory"); if (swatch_width > swatch_height) { swatch_width /= 2; } else { @@ -405,7 +418,8 @@ void MapDisplay::tryCreateSwatches( size_t effective_width = getEffectiveDimension(width, swatch_width, x); size_t effective_height = getEffectiveDimension(height, swatch_height, y); - swatches_.push_back(std::make_shared( + swatches_.push_back( + std::make_shared( scene_manager_, scene_node_, x, y, @@ -442,7 +456,8 @@ void MapDisplay::showMap() } if (!validateFloats(current_map_)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Map", + setStatus( + rviz_common::properties::StatusProperty::Error, "Map", "Message contained invalid floating point values (nans or infs)"); return; } @@ -469,8 +484,9 @@ void MapDisplay::showMap() setStatus(rviz_common::properties::StatusProperty::Ok, "Message", "Map received"); - RVIZ_COMMON_LOG_DEBUG_STREAM("Received a " << current_map_.info.width << " X " << - current_map_.info.height << " map @ " << current_map_.info.resolution << "m/pix\n"); + RVIZ_COMMON_LOG_DEBUG_STREAM( + "Received a " << current_map_.info.width << " X " << + current_map_.info.height << " map @ " << current_map_.info.resolution << "m/pix\n"); showValidMap(); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/points_marker.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/points_marker.cpp index 6a7a9349c..b5238cde0 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/points_marker.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/points_marker.cpp @@ -61,7 +61,8 @@ void PointsMarker::onNewMessage( { (void) old_message; - assert(new_message->type == visualization_msgs::msg::Marker::POINTS || + assert( + new_message->type == visualization_msgs::msg::Marker::POINTS || new_message->type == visualization_msgs::msg::Marker::CUBE_LIST || new_message->type == visualization_msgs::msg::Marker::SPHERE_LIST); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/text_view_facing_marker.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/text_view_facing_marker.cpp index c662b9509..4f3cafff4 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/text_view_facing_marker.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/text_view_facing_marker.cpp @@ -85,7 +85,8 @@ void TextViewFacingMarker::onNewMessage( setPosition(pos); text_->setCharacterHeight(new_message->scale.z); - text_->setColor(Ogre::ColourValue( + text_->setColor( + Ogre::ColourValue( new_message->color.r, new_message->color.g, new_message->color.b, new_message->color.a)); text_->setCaption(new_message->text); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp index 52ae288dc..9a1db2f11 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/marker/markers/triangle_list_marker.cpp @@ -203,14 +203,16 @@ bool TriangleListMarker::fillManualObjectAndDetermineAlpha( if (hasVertexColors(new_message)) { any_vertex_has_alpha = any_vertex_has_alpha || (new_message->colors[i + c].a < rviz_rendering::unit_alpha_threshold); - manual_object_->colour(new_message->colors[i + c].r, + manual_object_->colour( + new_message->colors[i + c].r, new_message->colors[i + c].g, new_message->colors[i + c].b, new_message->color.a * new_message->colors[i + c].a); } else if (hasFaceColors(new_message)) { any_vertex_has_alpha = any_vertex_has_alpha || (new_message->colors[i / 3].a < rviz_rendering::unit_alpha_threshold); - manual_object_->colour(new_message->colors[i / 3].r, + manual_object_->colour( + new_message->colors[i / 3].r, new_message->colors[i / 3].g, new_message->colors[i / 3].b, new_message->color.a * new_message->colors[i / 3].a); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/odometry/odometry_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/odometry/odometry_display.cpp index 761fc0577..7a45b1752 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/odometry/odometry_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/odometry/odometry_display.cpp @@ -74,15 +74,17 @@ void OdometryDisplay::setupProperties() this); position_tolerance_property_->setMin(0); - angle_tolerance_property_ = new rviz_common::properties::FloatProperty("Angle Tolerance", 0.1f, - "Angular distance from the last arrow dropped, " - "that will cause a new arrow to drop.", - this); + angle_tolerance_property_ = new rviz_common::properties::FloatProperty( + "Angle Tolerance", 0.1f, + "Angular distance from the last arrow dropped, " + "that will cause a new arrow to drop.", + this); angle_tolerance_property_->setMin(0); - keep_property_ = new rviz_common::properties::IntProperty("Keep", 100, - "Number of arrows to keep before removing the oldest. 0 means keep all of them.", - this); + keep_property_ = new rviz_common::properties::IntProperty( + "Keep", 100, + "Number of arrows to keep before removing the oldest. 0 means keep all of them.", + this); keep_property_->setMin(0); shape_property_ = new rviz_common::properties::EnumProperty( @@ -91,9 +93,10 @@ void OdometryDisplay::setupProperties() shape_property_->addOption("Arrow", ArrowShape); shape_property_->addOption("Axes", AxesShape); - color_property_ = new rviz_common::properties::ColorProperty("Color", QColor(255, 25, 0), - "Color of the arrows.", - shape_property_, SLOT(updateColorAndAlpha()), this); + color_property_ = new rviz_common::properties::ColorProperty( + "Color", QColor(255, 25, 0), + "Color of the arrows.", + shape_property_, SLOT(updateColorAndAlpha()), this); alpha_property_ = new rviz_common::properties::FloatProperty( "Alpha", 1, "Amount of transparency to apply to the arrow.", @@ -101,21 +104,25 @@ void OdometryDisplay::setupProperties() alpha_property_->setMin(0); alpha_property_->setMax(1); - shaft_length_property_ = new rviz_common::properties::FloatProperty("Shaft Length", 1, - "Length of the each arrow's shaft, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + shaft_length_property_ = new rviz_common::properties::FloatProperty( + "Shaft Length", 1, + "Length of the each arrow's shaft, in meters.", + shape_property_, SLOT(updateArrowsGeometry()), this); - shaft_radius_property_ = new rviz_common::properties::FloatProperty("Shaft Radius", 0.05f, - "Radius of the each arrow's shaft, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + shaft_radius_property_ = new rviz_common::properties::FloatProperty( + "Shaft Radius", 0.05f, + "Radius of the each arrow's shaft, in meters.", + shape_property_, SLOT(updateArrowsGeometry()), this); - head_length_property_ = new rviz_common::properties::FloatProperty("Head Length", 0.3f, - "Length of the each arrow's head, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + head_length_property_ = new rviz_common::properties::FloatProperty( + "Head Length", 0.3f, + "Length of the each arrow's head, in meters.", + shape_property_, SLOT(updateArrowsGeometry()), this); - head_radius_property_ = new rviz_common::properties::FloatProperty("Head Radius", 0.1f, - "Radius of the each arrow's head, in meters.", - shape_property_, SLOT(updateArrowsGeometry()), this); + head_radius_property_ = new rviz_common::properties::FloatProperty( + "Head Radius", 0.1f, + "Radius of the each arrow's head, in meters.", + shape_property_, SLOT(updateArrowsGeometry()), this); axes_length_property_ = new rviz_common::properties::FloatProperty( "Axes Length", 1, "Length of each axis, in meters.", @@ -125,9 +132,10 @@ void OdometryDisplay::setupProperties() "Axes Radius", 0.1f, "Radius of each axis, in meters.", shape_property_, SLOT(updateAxisGeometry()), this); - covariance_property_ = new rviz_common::properties::CovarianceProperty("Covariance", true, - "Whether or not the covariances of the messages should be shown.", - this, SLOT(updateCovariances())); + covariance_property_ = new rviz_common::properties::CovarianceProperty( + "Covariance", true, + "Whether or not the covariances of the messages should be shown.", + this, SLOT(updateCovariances())); } OdometryDisplay::~OdometryDisplay() = default; @@ -250,10 +258,11 @@ bool validateFloats(nav_msgs::msg::Odometry msg) bool validateQuaternion(nav_msgs::msg::Odometry msg) { - return std::abs((msg.pose.pose.orientation.x * msg.pose.pose.orientation.x + - msg.pose.pose.orientation.y * msg.pose.pose.orientation.y + - msg.pose.pose.orientation.z * msg.pose.pose.orientation.z + - msg.pose.pose.orientation.w * msg.pose.pose.orientation.w) - 1.0f) < 10e-3; + return std::abs( + (msg.pose.pose.orientation.x * msg.pose.pose.orientation.x + + msg.pose.pose.orientation.y * msg.pose.pose.orientation.y + + msg.pose.pose.orientation.z * msg.pose.pose.orientation.z + + msg.pose.pose.orientation.w * msg.pose.pose.orientation.w) - 1.0f) < 10e-3; } void OdometryDisplay::processMessage(nav_msgs::msg::Odometry::ConstSharedPtr msg) @@ -284,13 +293,15 @@ bool OdometryDisplay::messageIsValid(nav_msgs::msg::Odometry::ConstSharedPtr mes // if both invalid values and unnormalized quaternion are present, both messages are printed. bool message_is_valid = true; if (!validateFloats(*message)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); message_is_valid = false; } if (!validateQuaternion(*message)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained unnormalized quaternion (squares of values don't add to 1)"); message_is_valid = false; } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/path/path_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/path/path_display.cpp index 7bd8736b0..b393d4a74 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/path/path_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/path/path_display.cpp @@ -67,72 +67,86 @@ PathDisplay::PathDisplay(rviz_common::DisplayContext * context) PathDisplay::PathDisplay() { - style_property_ = new rviz_common::properties::EnumProperty("Line Style", "Lines", - "The rendering operation to use to draw the grid lines.", - this, SLOT(updateStyle())); + style_property_ = new rviz_common::properties::EnumProperty( + "Line Style", "Lines", + "The rendering operation to use to draw the grid lines.", + this, SLOT(updateStyle())); style_property_->addOption("Lines", LINES); style_property_->addOption("Billboards", BILLBOARDS); - line_width_property_ = new rviz_common::properties::FloatProperty("Line Width", 0.03f, - "The width, in meters, of each path line." - "Only works with the 'Billboards' style.", - this, SLOT(updateLineWidth()), this); + line_width_property_ = new rviz_common::properties::FloatProperty( + "Line Width", 0.03f, + "The width, in meters, of each path line." + "Only works with the 'Billboards' style.", + this, SLOT(updateLineWidth()), this); line_width_property_->setMin(0.001f); line_width_property_->hide(); - color_property_ = new rviz_common::properties::ColorProperty("Color", QColor(25, 255, 0), - "Color to draw the path.", this); + color_property_ = new rviz_common::properties::ColorProperty( + "Color", QColor(25, 255, 0), + "Color to draw the path.", this); - alpha_property_ = new rviz_common::properties::FloatProperty("Alpha", 1.0, - "Amount of transparency to apply to the path.", this); + alpha_property_ = new rviz_common::properties::FloatProperty( + "Alpha", 1.0, + "Amount of transparency to apply to the path.", this); - buffer_length_property_ = new rviz_common::properties::IntProperty("Buffer Length", 1, - "Number of paths to display.", - this, SLOT(updateBufferLength())); + buffer_length_property_ = new rviz_common::properties::IntProperty( + "Buffer Length", 1, + "Number of paths to display.", + this, SLOT(updateBufferLength())); buffer_length_property_->setMin(1); - offset_property_ = new rviz_common::properties::VectorProperty("Offset", Ogre::Vector3::ZERO, - "Allows you to offset the path from the origin of the reference frame. In meters.", - this, SLOT(updateOffset())); + offset_property_ = new rviz_common::properties::VectorProperty( + "Offset", Ogre::Vector3::ZERO, + "Allows you to offset the path from the origin of the reference frame. In meters.", + this, SLOT(updateOffset())); - pose_style_property_ = new rviz_common::properties::EnumProperty("Pose Style", "None", - "Shape to display the pose as.", - this, SLOT(updatePoseStyle())); + pose_style_property_ = new rviz_common::properties::EnumProperty( + "Pose Style", "None", + "Shape to display the pose as.", + this, SLOT(updatePoseStyle())); pose_style_property_->addOption("None", NONE); pose_style_property_->addOption("Axes", AXES); pose_style_property_->addOption("Arrows", ARROWS); - pose_axes_length_property_ = new rviz_common::properties::FloatProperty("Length", 0.3f, - "Length of the axes.", - this, SLOT(updatePoseAxisGeometry()) ); - pose_axes_radius_property_ = new rviz_common::properties::FloatProperty("Radius", 0.03f, - "Radius of the axes.", - this, SLOT(updatePoseAxisGeometry()) ); - - pose_arrow_color_property_ = new rviz_common::properties::ColorProperty("Pose Color", - QColor(255, 85, 255), - "Color to draw the poses.", - this, SLOT(updatePoseArrowColor())); - pose_arrow_shaft_length_property_ = new rviz_common::properties::FloatProperty("Shaft Length", - 0.1f, - "Length of the arrow shaft.", - this, - SLOT(updatePoseArrowGeometry())); - pose_arrow_head_length_property_ = new rviz_common::properties::FloatProperty("Head Length", 0.2f, - "Length of the arrow head.", - this, - SLOT(updatePoseArrowGeometry())); - pose_arrow_shaft_diameter_property_ = new rviz_common::properties::FloatProperty("Shaft Diameter", - 0.1f, - "Diameter of the arrow shaft.", - this, - SLOT(updatePoseArrowGeometry())); - pose_arrow_head_diameter_property_ = new rviz_common::properties::FloatProperty("Head Diameter", - 0.3f, - "Diameter of the arrow head.", - this, - SLOT(updatePoseArrowGeometry())); + pose_axes_length_property_ = new rviz_common::properties::FloatProperty( + "Length", 0.3f, + "Length of the axes.", + this, SLOT(updatePoseAxisGeometry()) ); + pose_axes_radius_property_ = new rviz_common::properties::FloatProperty( + "Radius", 0.03f, + "Radius of the axes.", + this, SLOT(updatePoseAxisGeometry()) ); + + pose_arrow_color_property_ = new rviz_common::properties::ColorProperty( + "Pose Color", + QColor(255, 85, 255), + "Color to draw the poses.", + this, SLOT(updatePoseArrowColor())); + pose_arrow_shaft_length_property_ = new rviz_common::properties::FloatProperty( + "Shaft Length", + 0.1f, + "Length of the arrow shaft.", + this, + SLOT(updatePoseArrowGeometry())); + pose_arrow_head_length_property_ = new rviz_common::properties::FloatProperty( + "Head Length", 0.2f, + "Length of the arrow head.", + this, + SLOT(updatePoseArrowGeometry())); + pose_arrow_shaft_diameter_property_ = new rviz_common::properties::FloatProperty( + "Shaft Diameter", + 0.1f, + "Diameter of the arrow shaft.", + this, + SLOT(updatePoseArrowGeometry())); + pose_arrow_head_diameter_property_ = new rviz_common::properties::FloatProperty( + "Head Diameter", + 0.3f, + "Diameter of the arrow head.", + this, + SLOT(updatePoseArrowGeometry())); pose_axes_length_property_->hide(); pose_axes_radius_property_->hide(); pose_arrow_color_property_->hide(); @@ -173,9 +187,10 @@ void PathDisplay::allocateAxesVector(std::vector & axes_ axes_vect.reserve(num); for (auto i = vector_size; i < num; ++i) { axes_vect.push_back( - new rviz_rendering::Axes(scene_manager_, scene_node_, - pose_axes_length_property_->getFloat(), - pose_axes_radius_property_->getFloat())); + new rviz_rendering::Axes( + scene_manager_, scene_node_, + pose_axes_length_property_->getFloat(), + pose_axes_radius_property_->getFloat())); } } else if (num < vector_size) { for (auto i = num; i < vector_size; ++i) { @@ -289,7 +304,8 @@ void PathDisplay::updatePoseAxisGeometry() { for (auto & axes_vect : axes_chain_) { for (auto & axes : axes_vect) { - axes->set(pose_axes_length_property_->getFloat(), + axes->set( + pose_axes_length_property_->getFloat(), pose_axes_radius_property_->getFloat() ); } } @@ -312,7 +328,8 @@ void PathDisplay::updatePoseArrowGeometry() { for (auto & arrow_vect : arrow_chain_) { for (auto & arrow : arrow_vect) { - arrow->set(pose_arrow_shaft_length_property_->getFloat(), + arrow->set( + pose_arrow_shaft_length_property_->getFloat(), pose_arrow_shaft_diameter_property_->getFloat(), pose_arrow_head_length_property_->getFloat(), pose_arrow_head_diameter_property_->getFloat()); @@ -406,7 +423,8 @@ void PathDisplay::processMessage(nav_msgs::msg::Path::ConstSharedPtr msg) // Check if path contains invalid coordinate values if (!validateFloats(*msg)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid " + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid " "floating point " "values (nans or infs)"); return; @@ -514,7 +532,8 @@ void PathDisplay::updateArrowMarkers( QColor color = pose_arrow_color_property_->getColor(); arrow_vect[i]->setColor(color.redF(), color.greenF(), color.blueF(), 1.0f); - arrow_vect[i]->set(pose_arrow_shaft_length_property_->getFloat(), + arrow_vect[i]->set( + pose_arrow_shaft_length_property_->getFloat(), pose_arrow_shaft_diameter_property_->getFloat(), pose_arrow_head_length_property_->getFloat(), pose_arrow_head_diameter_property_->getFloat()); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/point/point_stamped_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/point/point_stamped_display.cpp index e517ebc06..d30fc977e 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/point/point_stamped_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/point/point_stamped_display.cpp @@ -122,7 +122,8 @@ void PointStampedDisplay::onlyKeepHistoryLengthNumberOfVisuals() void PointStampedDisplay::processMessage(geometry_msgs::msg::PointStamped::ConstSharedPtr msg) { if (!rviz_common::validateFloats(msg->point)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); return; } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_common.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_common.cpp index 5e8e9cba8..77989d3ba 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_common.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_common.cpp @@ -78,7 +78,8 @@ void CloudInfo::setSelectable( if (selectable) { selection_handler_ = rviz_common::interaction::createSelectionHandler (selection_box_size, this, context); - cloud_->setPickColor(rviz_common::interaction::SelectionManager::handleToColor( + cloud_->setPickColor( + rviz_common::interaction::SelectionManager::handleToColor( selection_handler_->getHandle())); } else { selection_handler_.reset(); @@ -96,13 +97,15 @@ PointCloudCommon::PointCloudCommon(rviz_common::Display * display) transformer_factory_(std::make_unique()), display_(display) { - selectable_property_ = new rviz_common::properties::BoolProperty("Selectable", true, - "Whether or not the points in this point cloud are selectable.", - display_, SLOT(updateSelectable()), this); + selectable_property_ = new rviz_common::properties::BoolProperty( + "Selectable", true, + "Whether or not the points in this point cloud are selectable.", + display_, SLOT(updateSelectable()), this); - style_property_ = new rviz_common::properties::EnumProperty("Style", "Flat Squares", - "Rendering mode to use, in order of computational complexity.", - display_, SLOT(updateStyle()), this); + style_property_ = new rviz_common::properties::EnumProperty( + "Style", "Flat Squares", + "Rendering mode to use, in order of computational complexity.", + display_, SLOT(updateStyle()), this); style_property_->addOption("Points", rviz_rendering::PointCloud::RM_POINTS); style_property_->addOption("Squares", rviz_rendering::PointCloud::RM_SQUARES); style_property_->addOption("Flat Squares", rviz_rendering::PointCloud::RM_FLAT_SQUARES); @@ -110,39 +113,48 @@ PointCloudCommon::PointCloudCommon(rviz_common::Display * display) style_property_->addOption("Boxes", rviz_rendering::PointCloud::RM_BOXES); style_property_->addOption("Tiles", rviz_rendering::PointCloud::RM_TILES); - point_world_size_property_ = new rviz_common::properties::FloatProperty("Size (m)", 0.01f, - "Point size in meters.", - display_, SLOT(updateBillboardSize()), this); + point_world_size_property_ = new rviz_common::properties::FloatProperty( + "Size (m)", 0.01f, + "Point size in meters.", + display_, SLOT(updateBillboardSize()), this); point_world_size_property_->setMin(0.0001f); - point_pixel_size_property_ = new rviz_common::properties::FloatProperty("Size (Pixels)", 3, - "Point size in pixels.", - display_, SLOT(updateBillboardSize()), this); + point_pixel_size_property_ = new rviz_common::properties::FloatProperty( + "Size (Pixels)", 3, + "Point size in pixels.", + display_, SLOT(updateBillboardSize()), this); point_pixel_size_property_->setMin(1); - alpha_property_ = new rviz_common::properties::FloatProperty("Alpha", 1.0f, - "Amount of transparency to apply to the points. Note that this is experimental " - "and does not always look correct.", - display_, SLOT(updateAlpha()), this); + alpha_property_ = new rviz_common::properties::FloatProperty( + "Alpha", 1.0f, + "Amount of transparency to apply to the points. Note that this is experimental " + "and does not always look correct.", + display_, SLOT(updateAlpha()), this); alpha_property_->setMin(0); alpha_property_->setMax(1); - decay_time_property_ = new rviz_common::properties::FloatProperty("Decay Time", 0, - "Duration, in seconds, to keep the incoming points. 0 means only show the latest points.", - display_, SLOT(queueRender())); + decay_time_property_ = new rviz_common::properties::FloatProperty( + "Decay Time", 0, + "Duration, in seconds, to keep the incoming points. 0 means only show the latest points.", + display_, SLOT(queueRender())); decay_time_property_->setMin(0); - xyz_transformer_property_ = new rviz_common::properties::EnumProperty("Position Transformer", "", - "Set the transformer to use to set the position of the points.", - display_, SLOT(updateXyzTransformer()), this); - connect(xyz_transformer_property_, SIGNAL(requestOptions( - rviz_common::properties::EnumProperty*)), + xyz_transformer_property_ = new rviz_common::properties::EnumProperty( + "Position Transformer", "", + "Set the transformer to use to set the position of the points.", + display_, SLOT(updateXyzTransformer()), this); + connect( + xyz_transformer_property_, SIGNAL( + requestOptions( + rviz_common::properties::EnumProperty*)), this, SLOT(setXyzTransformerOptions(rviz_common::properties::EnumProperty*))); - color_transformer_property_ = new rviz_common::properties::EnumProperty("Color Transformer", "", - "Set the transformer to use to set the color of the points.", - display_, SLOT(updateColorTransformer()), this); - connect(color_transformer_property_, + color_transformer_property_ = new rviz_common::properties::EnumProperty( + "Color Transformer", "", + "Set the transformer to use to set the color of the points.", + display_, SLOT(updateColorTransformer()), this); + connect( + color_transformer_property_, SIGNAL(requestOptions(rviz_common::properties::EnumProperty*)), this, SLOT(setColorTransformerOptions(rviz_common::properties::EnumProperty*))); } @@ -325,8 +337,9 @@ void PointCloudCommon::insertNewClouds(float point_decay_time, const rclcpp::Tim cloud_info->manager_ = context_->getSceneManager(); - cloud_info->scene_node_ = scene_node_->createChildSceneNode(cloud_info->position_, - cloud_info->orientation_); + cloud_info->scene_node_ = scene_node_->createChildSceneNode( + cloud_info->position_, + cloud_info->orientation_); cloud_info->scene_node_->attachObject(cloud_info->cloud_.get()); @@ -360,8 +373,8 @@ void PointCloudCommon::updateTransformerProperties() TransformerInfo & info = transformer.second; setPropertiesHidden(info.xyz_props, name != xyz_transformer_property_->getStdString()); - setPropertiesHidden(info.color_props, - name != color_transformer_property_->getStdString()); + setPropertiesHidden( + info.color_props, name != color_transformer_property_->getStdString()); if (name == xyz_transformer_property_->getStdString() || name == color_transformer_property_->getStdString()) @@ -632,10 +645,10 @@ bool PointCloudCommon::transformPoints( return false; } - xyz_trans->transform(cloud_info->message_, PointCloudTransformer::Support_XYZ, transform, - cloud_points); - color_trans->transform(cloud_info->message_, PointCloudTransformer::Support_Color, transform, - cloud_points); + xyz_trans->transform( + cloud_info->message_, PointCloudTransformer::Support_XYZ, transform, cloud_points); + color_trans->transform( + cloud_info->message_, PointCloudTransformer::Support_Color, transform, cloud_points); return true; } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler.cpp index 2255664b6..66137f503 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler.cpp @@ -86,7 +86,8 @@ void PointCloudSelectionHandler::preRenderPass(uint32_t pass) switch (pass) { case 0: - cloud_info_->cloud_->setPickColor(rviz_common::interaction::SelectionManager::handleToColor( + cloud_info_->cloud_->setPickColor( + rviz_common::interaction::SelectionManager::handleToColor( getHandle())); break; case 1: diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/polygon/polygon_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/polygon/polygon_display.cpp index d9c3851fa..cc6b9a7da 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/polygon/polygon_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/polygon/polygon_display.cpp @@ -54,10 +54,12 @@ namespace displays PolygonDisplay::PolygonDisplay() { - color_property_ = new rviz_common::properties::ColorProperty("Color", QColor(25, 255, 0), - "Color to draw the polygon.", this, SLOT(queueRender())); - alpha_property_ = new rviz_common::properties::FloatProperty("Alpha", 1.0f, - "Amount of transparency to apply to the polygon.", this, SLOT(queueRender())); + color_property_ = new rviz_common::properties::ColorProperty( + "Color", QColor(25, 255, 0), + "Color to draw the polygon.", this, SLOT(queueRender())); + alpha_property_ = new rviz_common::properties::FloatProperty( + "Alpha", 1.0f, + "Amount of transparency to apply to the polygon.", this, SLOT(queueRender())); alpha_property_->setMin(0); alpha_property_->setMax(1); @@ -96,7 +98,8 @@ bool validateFloats(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg) void PolygonDisplay::processMessage(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg) { if (!validateFloats(msg)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); return; } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display.cpp index 4fee62134..7e9b6ff3e 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/pose/pose_display.cpp @@ -101,16 +101,18 @@ void PoseDisplay::onInitialize() { MFDClass::onInitialize(); - arrow_ = std::make_unique(scene_manager_, scene_node_, - shaft_length_property_->getFloat(), - shaft_radius_property_->getFloat(), - head_length_property_->getFloat(), - head_radius_property_->getFloat()); + arrow_ = std::make_unique( + scene_manager_, scene_node_, + shaft_length_property_->getFloat(), + shaft_radius_property_->getFloat(), + head_length_property_->getFloat(), + head_radius_property_->getFloat()); arrow_->setDirection(Ogre::Vector3::UNIT_X); - axes_ = std::make_unique(scene_manager_, scene_node_, - axes_length_property_->getFloat(), - axes_radius_property_->getFloat()); + axes_ = std::make_unique( + scene_manager_, scene_node_, + axes_length_property_->getFloat(), + axes_radius_property_->getFloat()); updateShapeChoice(); updateColorAndAlpha(); @@ -151,7 +153,8 @@ void PoseDisplay::updateColorAndAlpha() void PoseDisplay::updateArrowGeometry() { - arrow_->set(shaft_length_property_->getFloat(), + arrow_->set( + shaft_length_property_->getFloat(), shaft_radius_property_->getFloat(), head_length_property_->getFloat(), head_radius_property_->getFloat()); @@ -160,7 +163,8 @@ void PoseDisplay::updateArrowGeometry() void PoseDisplay::updateAxisGeometry() { - axes_->set(axes_length_property_->getFloat(), + axes_->set( + axes_length_property_->getFloat(), axes_radius_property_->getFloat()); context_->queueRender(); } @@ -199,15 +203,17 @@ void PoseDisplay::updateShapeVisibility() void PoseDisplay::processMessage(geometry_msgs::msg::PoseStamped::ConstSharedPtr message) { if (!rviz_common::validateFloats(*message)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); return; } Ogre::Vector3 position; Ogre::Quaternion orientation; - if (!context_->getFrameManager()->transform(message->header, message->pose, position, - orientation)) + if ( + !context_->getFrameManager()->transform( + message->header, message->pose, position, orientation)) { setMissingTransformToFixedFrame(message->header.frame_id); return; diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_cov_selection_handler.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_cov_selection_handler.cpp index d9e0530a8..ddafdb0cf 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_cov_selection_handler.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_cov_selection_handler.cpp @@ -128,12 +128,14 @@ void PoseWithCovSelectionHandler::setMessage( position_property_->setVector(rviz_common::pointMsgToOgre(message->pose.pose.position)); orientation_property_->setQuaternion( rviz_common::quaternionMsgToOgre(message->pose.pose.orientation)); - covariance_position_property_->setVector(Ogre::Vector3( + covariance_position_property_->setVector( + Ogre::Vector3( message->pose.covariance[0 + 0 * 6], message->pose.covariance[1 + 1 * 6], message->pose.covariance[2 + 2 * 6])); - covariance_orientation_property_->setVector(Ogre::Vector3( + covariance_orientation_property_->setVector( + Ogre::Vector3( message->pose.covariance[3 + 3 * 6], message->pose.covariance[4 + 4 * 6], message->pose.covariance[5 + 5 * 6])); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_covariance_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_covariance_display.cpp index b1c4a781a..bc15c59cc 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_covariance_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/pose_covariance/pose_with_covariance_display.cpp @@ -157,7 +157,8 @@ void PoseWithCovarianceDisplay::updateColorAndAlpha() void PoseWithCovarianceDisplay::updateArrowGeometry() { - arrow_->set(shaft_length_property_->getFloat(), + arrow_->set( + shaft_length_property_->getFloat(), shaft_radius_property_->getFloat(), head_length_property_->getFloat(), head_radius_property_->getFloat() ); @@ -166,7 +167,8 @@ void PoseWithCovarianceDisplay::updateArrowGeometry() void PoseWithCovarianceDisplay::updateAxisGeometry() { - axes_->set(axes_length_property_->getFloat(), + axes_->set( + axes_length_property_->getFloat(), axes_radius_property_->getFloat() ); context_->queueRender(); } @@ -216,15 +218,17 @@ void PoseWithCovarianceDisplay::processMessage( if (!rviz_common::validateFloats(message->pose.pose) || !rviz_common::validateFloats(message->pose.covariance)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); return; } Ogre::Vector3 position; Ogre::Quaternion orientation; - if (!context_->getFrameManager()->transform(message->header, message->pose.pose, position, - orientation)) + if ( + !context_->getFrameManager()->transform( + message->header, message->pose.pose, position, orientation)) { setMissingTransformToFixedFrame(message->header.frame_id); return; diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/range/range_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/range/range_display.cpp index ff3ec9ca6..f6514a4a5 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/range/range_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/range/range_display.cpp @@ -104,7 +104,8 @@ void RangeDisplay::updateBufferLength() cones_.resize(buffer_length); for (auto & cone : cones_) { - cone.reset(new rviz_rendering::Shape( + cone.reset( + new rviz_rendering::Shape( rviz_rendering::Shape::Cone, context_->getSceneManager(), scene_node_)); cone->setScale(Ogre::Vector3(0, 0, 0)); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/relative_humidity/relative_humidity_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/relative_humidity/relative_humidity_display.cpp index d5ab6888e..33529ab08 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/relative_humidity/relative_humidity_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/relative_humidity/relative_humidity_display.cpp @@ -70,5 +70,6 @@ void RelativeHumidityDisplay::processMessage( } // namespace rviz_default_plugins #include // NOLINT -PLUGINLIB_EXPORT_CLASS(rviz_default_plugins::displays::RelativeHumidityDisplay, +PLUGINLIB_EXPORT_CLASS( + rviz_default_plugins::displays::RelativeHumidityDisplay, rviz_common::Display) diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/robot_model/robot_model_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/robot_model/robot_model_display.cpp index 1759e8e1f..31454c9bf 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/robot_model/robot_model_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/robot_model/robot_model_display.cpp @@ -86,34 +86,40 @@ RobotModelDisplay::RobotModelDisplay() std::make_unique>(this, "TF")) { - visual_enabled_property_ = new Property("Visual Enabled", true, - "Whether to display the visual representation of the robot.", - this, SLOT(updateVisualVisible())); - - collision_enabled_property_ = new Property("Collision Enabled", false, - "Whether to display the collision representation of the robot.", - this, SLOT(updateCollisionVisible())); - - update_rate_property_ = new FloatProperty("Update Interval", 0, - "Interval at which to update the links, in seconds. " - " 0 means to update every update cycle.", - this); + visual_enabled_property_ = new Property( + "Visual Enabled", true, + "Whether to display the visual representation of the robot.", + this, SLOT(updateVisualVisible())); + + collision_enabled_property_ = new Property( + "Collision Enabled", false, + "Whether to display the collision representation of the robot.", + this, SLOT(updateCollisionVisible())); + + update_rate_property_ = new FloatProperty( + "Update Interval", 0, + "Interval at which to update the links, in seconds. " + " 0 means to update every update cycle.", + this); update_rate_property_->setMin(0); - alpha_property_ = new FloatProperty("Alpha", 1, - "Amount of transparency to apply to the links.", - this, SLOT(updateAlpha())); + alpha_property_ = new FloatProperty( + "Alpha", 1, + "Amount of transparency to apply to the links.", + this, SLOT(updateAlpha())); alpha_property_->setMin(0.0); alpha_property_->setMax(1.0); - description_source_property_ = new EnumProperty("Description Source", "Topic", - "Source to get the robot description from.", this, SLOT(updatePropertyVisibility())); + description_source_property_ = new EnumProperty( + "Description Source", "Topic", + "Source to get the robot description from.", this, SLOT(updatePropertyVisibility())); description_source_property_->addOption("Topic", DescriptionSource::TOPIC); description_source_property_->addOption("File", DescriptionSource::FILE); - description_file_property_ = new FilePickerProperty("Description File", "", - "Path to the robot description.", - this, SLOT(updateRobotDescription())); + description_file_property_ = new FilePickerProperty( + "Description File", "", + "Path to the robot description.", + this, SLOT(updateRobotDescription())); this->moveChild(topic_property_->rowNumberInParent(), this->numChildren() - 1); topic_property_->setDescription("Topic where filepath to urdf is published."); @@ -121,10 +127,11 @@ RobotModelDisplay::RobotModelDisplay() qos_profile = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local(); - tf_prefix_property_ = new StringProperty("TF Prefix", "", - "Robot Model normally assumes the link name is the same as the tf frame name. " - " This option allows you to set a prefix. Mainly useful for multi-robot situations.", - this, SLOT(updateTfPrefix())); + tf_prefix_property_ = new StringProperty( + "TF Prefix", "", + "Robot Model normally assumes the link name is the same as the tf frame name. " + " This option allows you to set a prefix. Mainly useful for multi-robot situations.", + this, SLOT(updateTfPrefix())); } RobotModelDisplay::~RobotModelDisplay() = default; @@ -265,7 +272,8 @@ void RobotModelDisplay::display_urdf_content() void RobotModelDisplay::updateRobot() { - robot_->update(robot::TFLinkUpdater( + robot_->update( + robot::TFLinkUpdater( context_->getFrameManager(), [this](auto arg1, auto arg2, auto arg3) {linkUpdaterStatusFunction(arg1, arg2, arg3, this);}, tf_prefix_property_->getStdString())); diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/tf/frame_selection_handler.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/tf/frame_selection_handler.cpp index 35c98afcf..d28c9b5ba 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/tf/frame_selection_handler.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/tf/frame_selection_handler.cpp @@ -72,12 +72,14 @@ void FrameSelectionHandler::createProperties(const Picked & obj, Property * pare { (void) obj; (void) display_; - category_property_ = new Property("Frame " + QString::fromStdString(frame_->name_), - QVariant(), "", parent_property); + category_property_ = new Property( + "Frame " + QString::fromStdString(frame_->name_), + QVariant(), "", parent_property); enabled_property_ = - new BoolProperty("Enabled", true, "", category_property_, SLOT( - updateVisibilityFromSelection()), frame_); + new BoolProperty( + "Enabled", true, "", category_property_, SLOT( + updateVisibilityFromSelection()), frame_); parent_property_ = new StringProperty("Parent", "", "", category_property_); parent_property_->setReadOnly(true); @@ -85,8 +87,9 @@ void FrameSelectionHandler::createProperties(const Picked & obj, Property * pare position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "", category_property_); position_property_->setReadOnly(true); - orientation_property_ = new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY, "", - category_property_); + orientation_property_ = new QuaternionProperty( + "Orientation", Ogre::Quaternion::IDENTITY, "", + category_property_); orientation_property_->setReadOnly(true); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/displays/wrench/wrench_display.cpp b/rviz_default_plugins/src/rviz_default_plugins/displays/wrench/wrench_display.cpp index 783bbe9f6..6c3cf3a85 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/displays/wrench/wrench_display.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/displays/wrench/wrench_display.cpp @@ -128,7 +128,8 @@ bool validateFloats(const geometry_msgs::msg::WrenchStamped & msg) void WrenchDisplay::processMessage(geometry_msgs::msg::WrenchStamped::ConstSharedPtr msg) { if (!validateFloats(*msg)) { - setStatus(rviz_common::properties::StatusProperty::Error, "Topic", + setStatus( + rviz_common::properties::StatusProperty::Error, "Topic", "Message contained invalid floating point values (nans or infs)"); return; } diff --git a/rviz_default_plugins/src/rviz_default_plugins/robot/robot.cpp b/rviz_default_plugins/src/rviz_default_plugins/robot/robot.cpp index bfd5c49e5..a1563bf23 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/robot/robot.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/robot/robot.cpp @@ -223,7 +223,8 @@ void Robot::update(const LinkUpdater & updater) log_error(link, "collision", "position"); continue; } - link->setTransforms(visual_position, visual_orientation, collision_position, + link->setTransforms( + visual_position, visual_orientation, collision_position, collision_orientation); for (const auto & child_joint_name : link->getChildJointNames()) { @@ -379,7 +380,8 @@ void Robot::calculateJointCheckboxes() int child_links_with_geom; int child_links_with_geom_checked; int child_links_with_geom_unchecked; - child_joint->calculateJointCheckboxesRecursive(child_links_with_geom, + child_joint->calculateJointCheckboxesRecursive( + child_links_with_geom, child_links_with_geom_checked, child_links_with_geom_unchecked); links_with_geom_checked += child_links_with_geom_checked; diff --git a/rviz_default_plugins/src/rviz_default_plugins/robot/robot_joint.cpp b/rviz_default_plugins/src/rviz_default_plugins/robot/robot_joint.cpp index baed1c74b..28a07dc96 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/robot/robot_joint.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/robot/robot_joint.cpp @@ -74,7 +74,8 @@ RobotJoint::RobotJoint(Robot * robot, const urdf::JointConstSharedPtr & joint) nullptr, SLOT(updateChildVisibility()), this); - robot_element_property_->setIcon(rviz_common::loadPixmap( + robot_element_property_->setIcon( + rviz_common::loadPixmap( "package://rviz_default_plugins/icons/classes/RobotJoint.png")); details_ = new Property("Details", QVariant(), "", nullptr); @@ -283,7 +284,8 @@ void RobotJoint::getChildLinkState( int child_links_with_geom; int child_links_with_geom_checked; int child_links_with_geom_unchecked; - child_joint->getChildLinkState(child_links_with_geom, child_links_with_geom_checked, + child_joint->getChildLinkState( + child_links_with_geom, child_links_with_geom_checked, child_links_with_geom_unchecked, recursive); links_with_geom_checked += child_links_with_geom_checked; links_with_geom_unchecked += child_links_with_geom_unchecked; diff --git a/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp b/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp index b13615349..d47057758 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/robot/robot_link.cpp @@ -123,15 +123,15 @@ void RobotLinkSelectionHandler::createProperties( rviz_common::properties::Property * parent_property) { (void) obj; - Property * group = new Property("Link " + QString::fromStdString(link_->getName()), - QVariant(), "", parent_property); + Property * group = new Property( + "Link " + QString::fromStdString(link_->getName()), QVariant(), "", parent_property); properties_.push_back(group); position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "", group); position_property_->setReadOnly(true); - orientation_property_ = new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY, "", - group); + orientation_property_ = new QuaternionProperty( + "Orientation", Ogre::Quaternion::IDENTITY, "", group); orientation_property_->setReadOnly(true); group->expand(); @@ -218,7 +218,8 @@ RobotLink::RobotLink( createDescription(link); if (!hasGeometry()) { - robot_element_property_->setIcon(rviz_common::loadPixmap( + robot_element_property_->setIcon( + rviz_common::loadPixmap( "package://rviz_default_plugins/icons/classes/RobotLinkNoGeom.png")); alpha_property_->hide(); robot_element_property_->setValue(QVariant()); @@ -229,31 +230,37 @@ void RobotLink::setProperties(const urdf::LinkConstSharedPtr & link) { robot_element_property_ = new Property( link->name.c_str(), true, "", nullptr, SLOT(updateVisibility()), this); - robot_element_property_->setIcon(rviz_common::loadPixmap( + robot_element_property_->setIcon( + rviz_common::loadPixmap( "package://rviz_default_plugins/icons/classes/RobotLink.png")); details_ = new Property("Details", QVariant(), "", nullptr); - alpha_property_ = new FloatProperty("Alpha", 1, - "Amount of transparency to apply to this link.", - robot_element_property_, SLOT(updateAlpha()), this); - - trail_property_ = new Property("Show Trail", false, - "Enable/disable a 2 meter \"ribbon\" which follows this link.", - robot_element_property_, SLOT(updateTrail()), this); - - axes_property_ = new Property("Show Axes", false, - "Enable/disable showing the axes of this link.", - robot_element_property_, SLOT(updateAxes()), this); - - position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, - "Position of this link, in the current Fixed Frame. (Not editable)", - robot_element_property_); + alpha_property_ = new FloatProperty( + "Alpha", 1, + "Amount of transparency to apply to this link.", + robot_element_property_, SLOT(updateAlpha()), this); + + trail_property_ = new Property( + "Show Trail", false, + "Enable/disable a 2 meter \"ribbon\" which follows this link.", + robot_element_property_, SLOT(updateTrail()), this); + + axes_property_ = new Property( + "Show Axes", false, + "Enable/disable showing the axes of this link.", + robot_element_property_, SLOT(updateAxes()), this); + + position_property_ = new VectorProperty( + "Position", Ogre::Vector3::ZERO, + "Position of this link, in the current Fixed Frame. (Not editable)", + robot_element_property_); position_property_->setReadOnly(true); - orientation_property_ = new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY, - "Orientation of this link, in the current Fixed Frame. (Not editable)", - robot_element_property_); + orientation_property_ = new QuaternionProperty( + "Orientation", Ogre::Quaternion::IDENTITY, + "Orientation of this link, in the current Fixed Frame. (Not editable)", + robot_element_property_); orientation_property_->setReadOnly(true); robot_element_property_->collapse(); @@ -740,7 +747,8 @@ void RobotLink::loadMaterialFromTexture( try { image.load(stream, extension); - Ogre::TextureManager::getSingleton().loadImage(filename, + Ogre::TextureManager::getSingleton().loadImage( + filename, RVIZ_RESOURCE_GROUP, image); } catch (Ogre::Exception & e) { diff --git a/rviz_default_plugins/src/rviz_default_plugins/tools/goal_pose/goal_tool.cpp b/rviz_default_plugins/src/rviz_default_plugins/tools/goal_pose/goal_tool.cpp index a611a004e..8401f8618 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/tools/goal_pose/goal_tool.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/tools/goal_pose/goal_tool.cpp @@ -49,9 +49,10 @@ GoalTool::GoalTool() { shortcut_key_ = 'g'; - topic_property_ = new rviz_common::properties::StringProperty("Topic", "goal_pose", - "The topic on which to publish goals.", - getPropertyContainer(), SLOT(updateTopic()), this); + topic_property_ = new rviz_common::properties::StringProperty( + "Topic", "goal_pose", + "The topic on which to publish goals.", + getPropertyContainer(), SLOT(updateTopic()), this); qos_profile_property_ = new rviz_common::properties::QosProfileProperty( topic_property_, qos_profile_); diff --git a/rviz_default_plugins/src/rviz_default_plugins/tools/pose/pose_tool.cpp b/rviz_default_plugins/src/rviz_default_plugins/tools/pose/pose_tool.cpp index ad9c21267..2ea673d67 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/tools/pose/pose_tool.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/tools/pose/pose_tool.cpp @@ -128,8 +128,9 @@ void PoseTool::makeArrowVisibleAndSetOrientation(double angle) // we need base_orient, since the arrow goes along the -z axis by default // (for historical reasons) - Ogre::Quaternion orient_x = Ogre::Quaternion(Ogre::Radian(-Ogre::Math::HALF_PI), - Ogre::Vector3::UNIT_Y); + Ogre::Quaternion orient_x = Ogre::Quaternion( + Ogre::Radian(-Ogre::Math::HALF_PI), + Ogre::Vector3::UNIT_Y); arrow_->setOrientation(Ogre::Quaternion(Ogre::Radian(angle), Ogre::Vector3::UNIT_Z) * orient_x); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/tools/pose_estimate/initial_pose_tool.cpp b/rviz_default_plugins/src/rviz_default_plugins/tools/pose_estimate/initial_pose_tool.cpp index f82cb19b2..35690effb 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/tools/pose_estimate/initial_pose_tool.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/tools/pose_estimate/initial_pose_tool.cpp @@ -50,9 +50,10 @@ InitialPoseTool::InitialPoseTool() { shortcut_key_ = 'p'; - topic_property_ = new rviz_common::properties::StringProperty("Topic", "initialpose", - "The topic on which to publish initial pose estimates.", - getPropertyContainer(), SLOT(updateTopic()), this); + topic_property_ = new rviz_common::properties::StringProperty( + "Topic", "initialpose", + "The topic on which to publish initial pose estimates.", + getPropertyContainer(), SLOT(updateTopic()), this); qos_profile_property_ = new rviz_common::properties::QosProfileProperty( topic_property_, qos_profile_); diff --git a/rviz_default_plugins/src/rviz_default_plugins/view_controllers/orbit/orbit_view_controller.cpp b/rviz_default_plugins/src/rviz_default_plugins/view_controllers/orbit/orbit_view_controller.cpp index d7c005d74..fdba3517c 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/view_controllers/orbit/orbit_view_controller.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/view_controllers/orbit/orbit_view_controller.cpp @@ -69,27 +69,33 @@ using rviz_rendering::Shape; OrbitViewController::OrbitViewController() : focal_shape_(nullptr), dragging_(false) { - distance_property_ = new FloatProperty("Distance", DISTANCE_START, - "Distance from the focal point.", this); + distance_property_ = new FloatProperty( + "Distance", DISTANCE_START, + "Distance from the focal point.", this); distance_property_->setMin(0.01f); - focal_shape_size_property_ = new FloatProperty("Focal Shape Size", FOCAL_SHAPE_SIZE_START, - "Focal shape size.", this); + focal_shape_size_property_ = new FloatProperty( + "Focal Shape Size", FOCAL_SHAPE_SIZE_START, + "Focal shape size.", this); focal_shape_size_property_->setMin(0.001f); - focal_shape_fixed_size_property_ = new BoolProperty("Focal Shape Fixed Size", - FOCAL_SHAPE_FIXED_SIZE, "Focal shape size.", this); + focal_shape_fixed_size_property_ = new BoolProperty( + "Focal Shape Fixed Size", + FOCAL_SHAPE_FIXED_SIZE, "Focal shape size.", this); - yaw_property_ = new FloatProperty("Yaw", YAW_START, - "Rotation of the camera around the Z (up) axis.", this); + yaw_property_ = new FloatProperty( + "Yaw", YAW_START, + "Rotation of the camera around the Z (up) axis.", this); - pitch_property_ = new FloatProperty("Pitch", PITCH_START, - "How much the camera is tipped downward.", this); + pitch_property_ = new FloatProperty( + "Pitch", PITCH_START, + "How much the camera is tipped downward.", this); pitch_property_->setMax(Ogre::Math::HALF_PI - 0.001f); pitch_property_->setMin(-pitch_property_->getMax()); - focal_point_property_ = new VectorProperty("Focal Point", Ogre::Vector3::ZERO, - "The center point which the camera orbits.", this); + focal_point_property_ = new VectorProperty( + "Focal Point", Ogre::Vector3::ZERO, + "The center point which the camera orbits.", this); } void OrbitViewController::onInitialize() @@ -157,7 +163,8 @@ void OrbitViewController::handleMouseEvent(rviz_common::ViewportMouseEvent & eve void OrbitViewController::setShiftOrbitStatus() { - setStatus("Left-Click: Move X/Y. " + setStatus( + "Left-Click: Move X/Y. " "Right-Click:: Move Z. " "Mouse Wheel:: Zoom."); } @@ -295,7 +302,8 @@ void OrbitViewController::lookAt(const Ogre::Vector3 & point) { Ogre::SceneNode * camera_parent = camera_->getParentSceneNode(); Ogre::Vector3 camera_position = camera_parent->getPosition(); - focal_point_property_->setVector(target_scene_node_->getOrientation().Inverse() * + focal_point_property_->setVector( + target_scene_node_->getOrientation().Inverse() * (point - target_scene_node_->getPosition())); distance_property_->setFloat(focal_point_property_->getVector().distance(camera_position)); updateFocalShapeSize(); @@ -367,7 +375,8 @@ void OrbitViewController::updateFocalShapeSize() distance_property = 1; } - focal_shape_->setScale(Ogre::Vector3( + focal_shape_->setScale( + Ogre::Vector3( fshape_size * distance_property, fshape_size * distance_property, fshape_size * distance_property / 5.0f)); diff --git a/rviz_default_plugins/src/rviz_default_plugins/view_controllers/ortho/fixed_orientation_ortho_view_controller.cpp b/rviz_default_plugins/src/rviz_default_plugins/view_controllers/ortho/fixed_orientation_ortho_view_controller.cpp index 9087d743c..94f647b46 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/view_controllers/ortho/fixed_orientation_ortho_view_controller.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/view_controllers/ortho/fixed_orientation_ortho_view_controller.cpp @@ -176,7 +176,8 @@ void FixedOrientationOrthoViewController::onTargetFrameChanged( { (void) old_reference_orientation; - move(old_reference_position.x - reference_position_.x, + move( + old_reference_position.x - reference_position_.x, old_reference_position.y - reference_position_.y); } @@ -198,7 +199,8 @@ void FixedOrientationOrthoViewController::updateCamera() // For Z, we use a value that seems to work very well in the past. It once was connected to // half the far_clip_distance. auto camera_parent = getCameraParent(camera_); - camera_parent->setPosition(Ogre::Vector3( + camera_parent->setPosition( + Ogre::Vector3( x_property_->getFloat(), y_property_->getFloat(), ORTHO_VIEW_CONTROLLER_CAMERA_Z)); } diff --git a/rviz_default_plugins/src/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller.cpp b/rviz_default_plugins/src/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller.cpp index 41fcd4945..7fcdcd2a6 100644 --- a/rviz_default_plugins/src/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller.cpp +++ b/rviz_default_plugins/src/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller.cpp @@ -204,5 +204,6 @@ void XYOrbitViewController::handleWheelEvent( } // namespace rviz_default_plugins #include // NOLINT -PLUGINLIB_EXPORT_CLASS(rviz_default_plugins::view_controllers::XYOrbitViewController, +PLUGINLIB_EXPORT_CLASS( + rviz_default_plugins::view_controllers::XYOrbitViewController, rviz_common::ViewController) diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp index cf0203af4..a8687ce21 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/display_test_fixture.cpp @@ -85,7 +85,9 @@ void DisplayTestFixture::mockValidTransform(Ogre::Vector3 position, Ogre::Quater EXPECT_CALL( *frame_manager_, transform(::testing::_, ::testing::_, ::testing::_, ::testing::_, ::testing::_)) // NOLINT - .WillRepeatedly(::testing::DoAll( // NOLINT + .WillRepeatedly( + // NOLINT + ::testing::DoAll( ::testing::SetArgReferee<3>(position), ::testing::SetArgReferee<4>(orientation), ::testing::Return(true) @@ -94,7 +96,9 @@ void DisplayTestFixture::mockValidTransform(Ogre::Vector3 position, Ogre::Quater EXPECT_CALL( *frame_manager_, getTransform(::testing::_, ::testing::_, ::testing::_, ::testing::_)) - .WillRepeatedly(::testing::DoAll( // NOLINT + .WillRepeatedly( + // NOLINT + ::testing::DoAll( ::testing::SetArgReferee<2>(position), ::testing::SetArgReferee<3>(orientation), ::testing::Return(true) diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/fluid_pressure/fluid_pressure_display_visual_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/fluid_pressure/fluid_pressure_display_visual_test.cpp index c5782c454..9874aec64 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/fluid_pressure/fluid_pressure_display_visual_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/fluid_pressure/fluid_pressure_display_visual_test.cpp @@ -63,7 +63,8 @@ TEST_F(VisualTestFixture, sphere_changes_color_depending_on_fluid_pressure) { fluid_pressure_publisher->setFluidPressure(99000); captureMainWindow("fluid_pressure_display_low_fluid_pressure"); - executor_->queueAction([fluid_pressure_publisher]() + executor_->queueAction( + [fluid_pressure_publisher]() { fluid_pressure_publisher->setFluidPressure(104000); }); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/illuminance/illuminance_display_visual_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/illuminance/illuminance_display_visual_test.cpp index 330e198fb..57534da2c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/illuminance/illuminance_display_visual_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/illuminance/illuminance_display_visual_test.cpp @@ -63,7 +63,8 @@ TEST_F(VisualTestFixture, sphere_changes_color_depending_on_illuminance) { illuminance_publisher->setIlluminance(150); captureMainWindow("illuminance_display_low_illuminance"); - executor_->queueAction([illuminance_publisher]() + executor_->queueAction( + [illuminance_publisher]() { illuminance_publisher->setIlluminance(800); }); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp index 02eb9de5f..30b5b4867 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_test.cpp @@ -161,7 +161,9 @@ TEST_F(MapTestFixture, showMap_defaults_empty_frame_id_to_map) { EXPECT_CALL( *frame_manager_, transform("/map", _, _, _, _)) // NOLINT - .WillRepeatedly(DoAll( // NOLINT + .WillRepeatedly( + // NOLINT + DoAll( SetArgReferee<3>(position), SetArgReferee<4>(orientation), Return(true))); auto message = createMapMessage(); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_visual_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_visual_test.cpp index 380e7d431..fb60aa5b4 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_visual_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/map/map_display_visual_test.cpp @@ -42,7 +42,8 @@ TEST_F(VisualTestFixture, test_map_display_with_large_map) { auto publishers = std::vector(); publishers.emplace_back(PublisherWithFrame(std::make_shared(), "map_frame")); - publishers.emplace_back(PublisherWithFrame( + publishers.emplace_back( + PublisherWithFrame( std::make_shared(), "marker_frame")); auto map_publisher = std::make_unique(publishers); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp index 4cc31f70c..cf52ca96a 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/marker_common_test.cpp @@ -91,7 +91,8 @@ visualization_msgs::msg::Marker::SharedPtr createSharedPtrMessage( TEST_F(MarkerCommonFixture, processMessage_creates_correct_marker_on_add_type) { mockValidTransform(); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::TEXT_VIEW_FACING)); auto text = rviz_rendering::findOneMovableText(scene_manager_->getRootSceneNode()); @@ -103,17 +104,20 @@ TEST_F(MarkerCommonFixture, processMessage_creates_correct_marker_on_add_type) { TEST_F(MarkerCommonFixture, processMessage_deletes_correct_marker_on_delete_type) { mockValidTransform(); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, 0)); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::POINTS, 1)); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::DELETE, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, 0)); @@ -125,17 +129,20 @@ TEST_F(MarkerCommonFixture, processMessage_deletes_correct_marker_on_delete_type TEST_F(MarkerCommonFixture, processMessage_with_deleteall_deletes_all_markers) { mockValidTransform(); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, 0)); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::POINTS, 1)); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::DELETEALL, visualization_msgs::msg::Marker::TEXT_VIEW_FACING, 3)); @@ -156,7 +163,8 @@ TEST_F(MarkerCommonFixture, proccesMessage_add_all_markers_correctly) { marker->type = visualization_msgs::msg::Marker::MESH_RESOURCE; common_->processMessage(marker); - ASSERT_TRUE(rviz_rendering::findEntityByMeshName( + ASSERT_TRUE( + rviz_rendering::findEntityByMeshName( scene_manager_->getRootSceneNode(), marker->mesh_resource)); common_->deleteAllMarkers(); @@ -181,7 +189,8 @@ TEST_F(MarkerCommonFixture, proccesMessage_add_all_markers_correctly) { marker->type = visualization_msgs::msg::Marker::CYLINDER; common_->processMessage(marker); - ASSERT_TRUE(rviz_rendering::findEntityByMeshName( + ASSERT_TRUE( + rviz_rendering::findEntityByMeshName( scene_manager_->getRootSceneNode(), "rviz_cylinder.mesh")); common_->deleteAllMarkers(); @@ -201,14 +210,16 @@ TEST_F(MarkerCommonFixture, proccesMessage_add_all_markers_correctly) { TEST_F(MarkerCommonFixture, processMessage_adds_two_markers_of_same_type_if_ids_are_different) { mockValidTransform(); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::ARROW, 0)); EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::ARROW, 1)); @@ -216,7 +227,8 @@ TEST_F(MarkerCommonFixture, processMessage_adds_two_markers_of_same_type_if_ids_ EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(2)); } -TEST_F(MarkerCommonFixture, +TEST_F( + MarkerCommonFixture, processMessage_adds_two_markers_of_same_type_if_namespaces_are_different) { mockValidTransform(); @@ -236,14 +248,16 @@ TEST_F(MarkerCommonFixture, TEST_F(MarkerCommonFixture, processMessage_does_not_create_new_marker_if_id_already_exists) { mockValidTransform(); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::ARROW, 0)); EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::ARROW, 0)); @@ -273,14 +287,16 @@ TEST_F(MarkerCommonFixture, processMessage_updates_modified_marker) { TEST_F(MarkerCommonFixture, processMessage_using_modify_works_like_add) { mockValidTransform(); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::ARROW, 0)); EXPECT_THAT(rviz_rendering::findAllArrows(scene_manager_->getRootSceneNode()), SizeIs(1)); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::MODIFY, visualization_msgs::msg::Marker::ARROW, 0)); @@ -300,12 +316,14 @@ TEST_F(MarkerCommonFixture, update_retransforms_frame_locked_messages) { EXPECT_CALL( *frame_manager_, transform(_, _, _, _, _)) // NOLINT - .WillOnce(DoAll( + .WillOnce( + DoAll( SetArgReferee<3>(starting_position), SetArgReferee<4>(starting_orientation), Return(true) )) - .WillOnce(DoAll( + .WillOnce( + DoAll( SetArgReferee<3>(next_position), SetArgReferee<4>(next_orientation), Return(true))); @@ -315,13 +333,15 @@ TEST_F(MarkerCommonFixture, update_retransforms_frame_locked_messages) { auto pointCloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); ASSERT_TRUE(pointCloud); EXPECT_THAT(pointCloud->getParentSceneNode()->getPosition(), Vector3Eq(starting_position)); - EXPECT_THAT(pointCloud->getParentSceneNode()->getOrientation(), + EXPECT_THAT( + pointCloud->getParentSceneNode()->getOrientation(), QuaternionEq(starting_orientation)); common_->update(0, 0); EXPECT_THAT(pointCloud->getParentSceneNode()->getPosition(), Vector3Eq(next_position)); - EXPECT_THAT(pointCloud->getParentSceneNode()->getOrientation(), + EXPECT_THAT( + pointCloud->getParentSceneNode()->getOrientation(), QuaternionEq(next_orientation)); } @@ -335,7 +355,8 @@ TEST_F(MarkerCommonFixture, update_does_not_retransform_normal_messages) { EXPECT_CALL( *frame_manager_, transform(_, _, _, _, _)) // NOLINT - .WillOnce(DoAll( + .WillOnce( + DoAll( SetArgReferee<3>(starting_position), SetArgReferee<4>(starting_orientation), Return(true) @@ -346,13 +367,15 @@ TEST_F(MarkerCommonFixture, update_does_not_retransform_normal_messages) { auto pointCloud = rviz_rendering::findOnePointCloud(scene_manager_->getRootSceneNode()); ASSERT_TRUE(pointCloud); EXPECT_THAT(pointCloud->getParentSceneNode()->getPosition(), Vector3Eq(starting_position)); - EXPECT_THAT(pointCloud->getParentSceneNode()->getOrientation(), + EXPECT_THAT( + pointCloud->getParentSceneNode()->getOrientation(), QuaternionEq(starting_orientation)); common_->update(0, 0); EXPECT_THAT(pointCloud->getParentSceneNode()->getPosition(), Vector3Eq(starting_position)); - EXPECT_THAT(pointCloud->getParentSceneNode()->getOrientation(), + EXPECT_THAT( + pointCloud->getParentSceneNode()->getOrientation(), QuaternionEq(starting_orientation)); } @@ -366,25 +389,30 @@ TEST_F(MarkerCommonFixture, processMessage_adds_new_namespace_for_message) { common_->processMessage(marker); - ASSERT_THAT(display_->findProperty("Namespaces")->childAt(0)->getName().toStdString(), + ASSERT_THAT( + display_->findProperty("Namespaces")->childAt(0)->getName().toStdString(), StrEq("test_ns")); } TEST_F(MarkerCommonFixture, processMessage_does_not_add_new_namespace_if_already_present) { mockValidTransform(); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::POINTS)); ASSERT_THAT(display_->findProperty("Namespaces")->numChildren(), Eq(1)); - ASSERT_THAT(display_->findProperty("Namespaces")->childAt(0)->getName().toStdString(), + ASSERT_THAT( + display_->findProperty("Namespaces")->childAt(0)->getName().toStdString(), StrEq("test_ns")); - common_->processMessage(createSharedPtrMessage( + common_->processMessage( + createSharedPtrMessage( visualization_msgs::msg::Marker::ADD, visualization_msgs::msg::Marker::TEXT_VIEW_FACING)); ASSERT_THAT(display_->findProperty("Namespaces")->numChildren(), Eq(1)); - ASSERT_THAT(display_->findProperty("Namespaces")->childAt(0)->getName().toStdString(), + ASSERT_THAT( + display_->findProperty("Namespaces")->childAt(0)->getName().toStdString(), StrEq("test_ns")); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp index 24d5eeaab..047fd0cc4 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/line_marker_test.cpp @@ -148,15 +148,18 @@ TEST_F(MarkersTestFixture, setMessage_adds_billboard_line_with_one_color) { EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); EXPECT_THAT(billboard_chain->getNumChainElements(0), Eq(2u)); - EXPECT_THAT(billboard_chain->getChainElement(0, 1).position, + EXPECT_THAT( + billboard_chain->getChainElement(0, 1).position, Vector3Eq(Ogre::Vector3(first_point.x, first_point.y, first_point.z))); - EXPECT_THAT(billboard_chain->getChainElement(0, 0).position, + EXPECT_THAT( + billboard_chain->getChainElement(0, 0).position, Vector3Eq(Ogre::Vector3(second_point.x, second_point.y, second_point.z))); assertColorEquals(message.color, billboard_chain, 0); assertColorEquals(message.color, billboard_chain, 1); } -TEST_F(MarkersTestFixture, +TEST_F( + MarkersTestFixture, setMessage_adds_billboard_line_with_many_colors_if_all_points_have_color_information) { marker_ = makeMarker(); mockValidTransform(); @@ -179,9 +182,11 @@ TEST_F(MarkersTestFixture, EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); EXPECT_THAT(billboard_chain->getNumChainElements(0), Eq(2u)); - EXPECT_THAT(billboard_chain->getChainElement(0, 1).position, + EXPECT_THAT( + billboard_chain->getChainElement(0, 1).position, Vector3Eq(Ogre::Vector3(first_point.x, first_point.y, first_point.z))); - EXPECT_THAT(billboard_chain->getChainElement(0, 0).position, + EXPECT_THAT( + billboard_chain->getChainElement(0, 0).position, Vector3Eq(Ogre::Vector3(second_point.x, second_point.y, second_point.z))); assertColorEquals(second_point_color, billboard_chain, 0); assertColorEquals(first_point_color, billboard_chain, 1); @@ -222,10 +227,13 @@ TEST_F(MarkersTestFixture, setMessage_adds_many_points_into_same_chain) { EXPECT_TRUE(billboard_chain->isVisible()); EXPECT_THAT(billboard_chain->getNumberOfChains(), Eq(1u)); EXPECT_THAT(billboard_chain->getNumChainElements(0), Eq(3u)); - EXPECT_THAT(billboard_chain->getChainElement(0, 2).position, + EXPECT_THAT( + billboard_chain->getChainElement(0, 2).position, Vector3Eq(Ogre::Vector3(first_point.x, first_point.y, first_point.z))); - EXPECT_THAT(billboard_chain->getChainElement(0, 1).position, + EXPECT_THAT( + billboard_chain->getChainElement(0, 1).position, Vector3Eq(Ogre::Vector3(second_point.x, second_point.y, second_point.z))); - EXPECT_THAT(billboard_chain->getChainElement(0, 0).position, + EXPECT_THAT( + billboard_chain->getChainElement(0, 0).position, Vector3Eq(Ogre::Vector3(third_point.x, third_point.y, third_point.z))); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp index 4e9243c56..08852653a 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/marker/markers/mesh_resource_marker_test.cpp @@ -79,8 +79,8 @@ TEST_F(MarkersTestFixture, setMessage_with_transform_sets_position_and_orientati ASSERT_TRUE(entity); EXPECT_TRUE(entity->isVisible()); EXPECT_THAT(entity->getParentSceneNode()->getPosition(), Vector3Eq(Ogre::Vector3(0, 1, 0))); - EXPECT_THAT(entity->getParentSceneNode()->getOrientation(), - QuaternionEq(Ogre::Quaternion(0, 0, 1, 0))); + EXPECT_THAT( + entity->getParentSceneNode()->getOrientation(), QuaternionEq(Ogre::Quaternion(0, 0, 1, 0))); } TEST_F(MarkersTestFixture, setMessage_does_not_attach_entity_when_mesh_is_missing) { diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp index 3f0c5df20..604d64eed 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/odometry_display_test.cpp @@ -141,7 +141,8 @@ TEST_F(OdometryDisplayFixture, processMessage_returns_early_if_transform_is_miss EXPECT_THAT(axes, IsEmpty()); } -TEST_F(OdometryDisplayFixture, +TEST_F( + OdometryDisplayFixture, processMessage_returns_early_if_message_position_and_orientation_are_close_to_previous_ones) { mockValidTransform(); auto odometry_message = createOdometryMessage(); @@ -190,18 +191,22 @@ TEST_F( display_->processMessage(odometry_message); - EXPECT_TRUE(rviz_default_plugins::arrowIsVisible( + EXPECT_TRUE( + rviz_default_plugins::arrowIsVisible( rviz_rendering::findOneArrow(scene_manager_->getRootSceneNode()))); - EXPECT_FALSE(rviz_default_plugins::axesAreVisible( + EXPECT_FALSE( + rviz_default_plugins::axesAreVisible( rviz_rendering::findOneAxes(scene_manager_->getRootSceneNode()))); shape_property->setString("Axes"); odometry_message->pose.pose.position.x = 35; display_->processMessage(odometry_message); - EXPECT_FALSE(rviz_default_plugins::arrowIsVisible( + EXPECT_FALSE( + rviz_default_plugins::arrowIsVisible( rviz_rendering::findOneArrow(scene_manager_->getRootSceneNode()))); - EXPECT_TRUE(rviz_default_plugins::axesAreVisible( + EXPECT_TRUE( + rviz_default_plugins::axesAreVisible( rviz_rendering::findOneAxes(scene_manager_->getRootSceneNode()))); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/quaternion_helper_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/quaternion_helper_test.cpp index e4653bff5..6543d4105 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/quaternion_helper_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/odometry/quaternion_helper_test.cpp @@ -40,8 +40,8 @@ using namespace ::testing; // NOLINT TEST(QuaternionHelper, ogreQuaternionHelper_returns_0_for_equal_inputs) { Ogre::Quaternion quaternion(1.0f, 0.0f, 0.0f, 0.0f); - EXPECT_THAT(rviz_default_plugins::ogreQuaternionAngularDistance(quaternion, quaternion), - Eq(0.0f)); + EXPECT_THAT( + rviz_default_plugins::ogreQuaternionAngularDistance(quaternion, quaternion), Eq(0.0f)); } TEST(QuaternionHelper, ogreQuaternionHelper_returns_angle) { @@ -54,8 +54,10 @@ TEST(QuaternionHelper, ogreQuaternionHelper_returns_angle) { Ogre::Quaternion quaternion3; quaternion3.FromAngleAxis(Ogre::Radian(1.2f), axis); - EXPECT_THAT(rviz_default_plugins::ogreQuaternionAngularDistance(quaternion1, quaternion2), + EXPECT_THAT( + rviz_default_plugins::ogreQuaternionAngularDistance(quaternion1, quaternion2), FloatNear(0.5f, 0.001f)); - EXPECT_THAT(rviz_default_plugins::ogreQuaternionAngularDistance(quaternion1, quaternion3), + EXPECT_THAT( + rviz_default_plugins::ogreQuaternionAngularDistance(quaternion1, quaternion3), FloatNear(1.2f, 0.001f)); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp index 02dac6265..0f86071d3 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/point/point_stamped_display_test.cpp @@ -79,8 +79,9 @@ void assertPointsPresent(std::vector entities, Ogre::Vector3 pos { bool found = false; for (auto entity : entities) { - if (Matches(Vector3Eq(position))(entity->getParentSceneNode() - ->getParentSceneNode()->getPosition())) + if ( + Matches(Vector3Eq(position))( + entity->getParentSceneNode()->getParentSceneNode()->getPosition())) { found = true; } @@ -98,8 +99,8 @@ TEST_F(PointStampedTestFixture, processMessage_adds_nothing_to_scene_if_invalid_ EXPECT_THAT(objects.size(), Eq(0u)); } -TEST_F(PointStampedTestFixture, - processMessage_stores_no_more_messages_in_scene_than_history_allows) +TEST_F( + PointStampedTestFixture, processMessage_stores_no_more_messages_in_scene_than_history_allows) { mockValidTransform(); EXPECT_THAT(point_stamped_display_->childAt(4)->getNameStd(), StrEq("History Length")); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp index 218820c37..1c1e67582 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_common_test.cpp @@ -182,7 +182,8 @@ TEST_F(PointCloudCommonTestFixture, update_colors_the_points_using_the_selected_ EXPECT_THAT(point_cloud->getPoints()[0].color, ColourValueEq(Ogre::ColourValue(1, 0, 0))); } -TEST_F(PointCloudCommonTestFixture, +TEST_F( + PointCloudCommonTestFixture, sending_a_point_cloud_with_not_enough_data_results_in_error_but_no_crash) { point_cloud_common_->initialize( diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp index b479604a0..75f00e1f8 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_selection_handler_test.cpp @@ -148,7 +148,8 @@ TEST_F(PointCloudSelectionHandlerFixture, onSelect_selects_only_points_actually_ ContainsWireBoxWithBoundingBox(Ogre::AxisAlignedBox(0.5f, -1.5f, 0.5f, 1.5f, -0.5f, 1.5f))); } -TEST_F(PointCloudSelectionHandlerFixture, +TEST_F( + PointCloudSelectionHandlerFixture, onDeselect_destroys_wired_bounding_boxes_for_unpicked_objects) { std::vector message_points = @@ -177,7 +178,8 @@ TEST_F(PointCloudSelectionHandlerFixture, ContainsWireBoxWithBoundingBox(Ogre::AxisAlignedBox(0.5f, -1.5f, 0.5f, 1.5f, -0.5f, 1.5f))); } -TEST_F(PointCloudSelectionHandlerFixture, +TEST_F( + PointCloudSelectionHandlerFixture, createProperties_creates_tree_of_properties_without_color_for_simple_clouds) { std::vector message_points = @@ -199,17 +201,20 @@ TEST_F(PointCloudSelectionHandlerFixture, auto first_point_property = parent->childAt(0); ASSERT_THAT(first_point_property, HasNumberOfSubproperties(1)); EXPECT_THAT(first_point_property->getNameStd(), StartsWith("Point 0 [cloud")); - EXPECT_THAT(first_point_property->childAt(0), + EXPECT_THAT( + first_point_property->childAt(0), HasPositionPropertyWithPosition(Ogre::Vector3(1, 1, 1))); auto second_point_property = parent->childAt(1); ASSERT_THAT(second_point_property, HasNumberOfSubproperties(1)); EXPECT_THAT(second_point_property->getNameStd(), StartsWith("Point 3 [cloud")); - EXPECT_THAT(second_point_property->childAt(0), + EXPECT_THAT( + second_point_property->childAt(0), HasPositionPropertyWithPosition(Ogre::Vector3(1, -1, 1))); } -TEST_F(PointCloudSelectionHandlerFixture, +TEST_F( + PointCloudSelectionHandlerFixture, createProperties_creates_tree_of_properties_with_color_for_clouds_with_rgb) { std::vector message_points = @@ -234,7 +239,8 @@ TEST_F(PointCloudSelectionHandlerFixture, EXPECT_THAT(parent->childAt(1), HasColorProperty("1; 1; 1", 0.0f)); } -TEST_F(PointCloudSelectionHandlerFixture, +TEST_F( + PointCloudSelectionHandlerFixture, createProperties_creates_tree_of_properties_with_intensity_for_clouds_with_intensity) { std::vector message_points = diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/intensity_pc_transformer_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/intensity_pc_transformer_test.cpp index 4ed4e32e0..8cb071bb4 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/intensity_pc_transformer_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pointcloud/point_cloud_transformers/intensity_pc_transformer_test.cpp @@ -62,7 +62,8 @@ TEST(IntensityPCTransformer, transform_returns_points_colored_depending_on_the_i ASSERT_THAT(points_out[2].color, Eq(Ogre::ColourValue(1, 0, 1))); // 1 } -TEST(IntensityPCTransformer, +TEST( + IntensityPCTransformer, transform_interpolates_between_min_and_max_color_if_use_rainbow_is_diabled) { PointWithIntensity p1 = {0, 0, 0, 0}; PointWithIntensity p2 = {0, 0, 0, 1}; @@ -94,7 +95,8 @@ TEST(IntensityPCTransformer, ASSERT_THAT(points_out[2].color, Eq(Ogre::ColourValue(1, 0, 0))); // 1 } -TEST(IntensityPCTransformer, +TEST( + IntensityPCTransformer, transform_uses_default_min_max_intensity_if_autocompute_bounds_is_disabled) { PointWithIntensity p1 = {0, 0, 0, 0}; PointWithIntensity p2 = {0, 0, 0, 1024}; diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp index a9355c5d5..b0ee55c63 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/pose_array/pose_array_display_test.cpp @@ -123,7 +123,8 @@ TEST_F(PoseArrayDisplayFixture, at_startup_only_flat_arrows_propertie_are_visibl EXPECT_FALSE(arrow_2d_length_property_->getHidden()); } -TEST_F(PoseArrayDisplayFixture, +TEST_F( + PoseArrayDisplayFixture, processMessage_corrctly_manages_property_visibility_from_arrow2d_to_arrow3d) { mockValidTransform(); auto msg = createMessageWithOnePose(); @@ -142,7 +143,8 @@ TEST_F(PoseArrayDisplayFixture, EXPECT_TRUE(arrow_2d_length_property_->getHidden()); } -TEST_F(PoseArrayDisplayFixture, +TEST_F( + PoseArrayDisplayFixture, processMessage_corrctly_manages_property_visibility_from_arrow2d_to_axes) { mockValidTransform(); auto msg = createMessageWithOnePose(); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/relative_humidity/relative_humidity_display_visual_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/relative_humidity/relative_humidity_display_visual_test.cpp index 564f96d07..a892cae8c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/relative_humidity/relative_humidity_display_visual_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/relative_humidity/relative_humidity_display_visual_test.cpp @@ -63,7 +63,8 @@ TEST_F(VisualTestFixture, sphere_changes_color_depending_on_relative_humidity) { relative_humidity_publisher->setRelativeHumidity(0.15); captureMainWindow("relative_humidity_display_low_relative_humidity"); - executor_->queueAction([relative_humidity_publisher]() + executor_->queueAction( + [relative_humidity_publisher]() { relative_humidity_publisher->setRelativeHumidity(0.85); }); diff --git a/rviz_default_plugins/test/rviz_default_plugins/displays/temperature/temperature_display_visual_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/displays/temperature/temperature_display_visual_test.cpp index 0533a1a31..45123c2a1 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/displays/temperature/temperature_display_visual_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/displays/temperature/temperature_display_visual_test.cpp @@ -63,7 +63,8 @@ TEST_F(VisualTestFixture, sphere_changes_color_depending_on_temperature) { temperature_publisher->setTemperature(15.); captureMainWindow("temperature_display_low_temperature"); - executor_->queueAction([temperature_publisher]() + executor_->queueAction( + [temperature_publisher]() { temperature_publisher->setTemperature(85.); }); diff --git a/rviz_default_plugins/test/rviz_default_plugins/mock_frame_manager.hpp b/rviz_default_plugins/test/rviz_default_plugins/mock_frame_manager.hpp index a3afd597a..053a12e7d 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/mock_frame_manager.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/mock_frame_manager.hpp @@ -53,9 +53,11 @@ class MockFrameManager : public rviz_common::FrameManagerIface MOCK_METHOD0(getTime, rclcpp::Time()); MOCK_METHOD3(getTransform, bool(const std::string &, Ogre::Vector3 &, Ogre::Quaternion &)); - MOCK_METHOD4(getTransform, bool( + MOCK_METHOD4( + getTransform, bool( const std::string &, rclcpp::Time, Ogre::Vector3 &, Ogre::Quaternion &)); - MOCK_METHOD5(transform, bool( + MOCK_METHOD5( + transform, bool( const std::string &, rclcpp::Time, const geometry_msgs::msg::Pose &, @@ -66,8 +68,8 @@ class MockFrameManager : public rviz_common::FrameManagerIface MOCK_METHOD2(transformHasProblems, bool(const std::string &, std::string &)); MOCK_METHOD3(transformHasProblems, bool(const std::string &, rclcpp::Time, std::string &)); MOCK_METHOD0(getFixedFrame, const std::string & ()); - MOCK_METHOD0(getConnector, - rviz_common::transformation::TransformationLibraryConnector::WeakPtr()); + MOCK_METHOD0( + getConnector, rviz_common::transformation::TransformationLibraryConnector::WeakPtr()); MOCK_METHOD0(getTransformer, std::shared_ptr()); MOCK_METHOD0(getAllFrameNames, std::vector()); MOCK_METHOD1( diff --git a/rviz_default_plugins/test/rviz_default_plugins/mock_handler_manager.hpp b/rviz_default_plugins/test/rviz_default_plugins/mock_handler_manager.hpp index 2c19ff227..48074359a 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/mock_handler_manager.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/mock_handler_manager.hpp @@ -48,12 +48,14 @@ class MockHandlerManager : public rviz_common::interaction::HandlerManagerIface public: MOCK_METHOD0(createHandle, rviz_common::interaction::CollObjectHandle()); - MOCK_METHOD2(addHandler, void(rviz_common::interaction::CollObjectHandle, + MOCK_METHOD2( + addHandler, void(rviz_common::interaction::CollObjectHandle, rviz_common::interaction::SelectionHandlerWeakPtr)); MOCK_METHOD1(removeHandler, void(rviz_common::interaction::CollObjectHandle)); MOCK_METHOD1(addListener, void(rviz_common::interaction::HandlerManagerListener *)); MOCK_METHOD1(removeListener, void(rviz_common::interaction::HandlerManagerListener *)); - MOCK_METHOD1(getHandler, + MOCK_METHOD1( + getHandler, rviz_common::interaction::SelectionHandlerPtr(rviz_common::interaction::CollObjectHandle)); MOCK_METHOD1(enableInteraction, void(bool)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/mock_window_manager_interface.hpp b/rviz_default_plugins/test/rviz_default_plugins/mock_window_manager_interface.hpp index 83f19752c..24d572b20 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/mock_window_manager_interface.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/mock_window_manager_interface.hpp @@ -41,7 +41,8 @@ class MockWindowManagerInterface : public rviz_common::WindowManagerInterface public: MOCK_METHOD0(getParentWindow, QWidget * ()); - MOCK_METHOD4(addPane, + MOCK_METHOD4( + addPane, rviz_common::PanelDockWidget *( const QString & name, QWidget * pane, Qt::DockWidgetArea area, bool floating)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/robot/mock_link_updater.hpp b/rviz_default_plugins/test/rviz_default_plugins/robot/mock_link_updater.hpp index 6507eb3af..5d158be90 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/robot/mock_link_updater.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/robot/mock_link_updater.hpp @@ -44,14 +44,16 @@ class MockLinkUpdater : public rviz_default_plugins::robot::LinkUpdater { public: - MOCK_CONST_METHOD5(getLinkTransforms, bool( + MOCK_CONST_METHOD5( + getLinkTransforms, bool( const std::string & link_name, Ogre::Vector3 & visual_position, Ogre::Quaternion & visual_orientation, Ogre::Vector3 & collision_position, Ogre::Quaternion & collision_orientation)); - MOCK_CONST_METHOD3(setLinkStatus, void( + MOCK_CONST_METHOD3( + setLinkStatus, void( rviz_common::properties::StatusLevel level, const std::string & link_name, const std::string & text)); diff --git a/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp index 5b3040c73..d6d54ca3d 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/robot/robot_test.cpp @@ -128,13 +128,16 @@ TEST_F(RobotTestFixture, load_creates_links_and_sets_the_scene_node_positions) { auto link1 = robot_->getLink("test_robot_link"); EXPECT_THAT(link1->getVisualNode()->getChild(0)->getPosition(), Vector3Eq(Ogre::Vector3::ZERO)); EXPECT_THAT(link1->getVisualNode()->getChild(0)->getScale(), Vector3Eq(Ogre::Vector3(1, 1, 1))); - EXPECT_THAT(link1->getCollisionNode()->getChild(0)->getPosition(), + EXPECT_THAT( + link1->getCollisionNode()->getChild(0)->getPosition(), Vector3Eq(Ogre::Vector3::ZERO)); - EXPECT_THAT(link1->getCollisionNode()->getChild(0)->getScale(), + EXPECT_THAT( + link1->getCollisionNode()->getChild(0)->getScale(), Vector3Eq(Ogre::Vector3(1, 1, 1))); auto link3 = robot_->getLink("test_robot_link_head"); - EXPECT_THAT(link3->getVisualNode()->getChild(0)->getPosition(), + EXPECT_THAT( + link3->getVisualNode()->getChild(0)->getPosition(), Vector3Eq(Ogre::Vector3(0, 0, 2))); EXPECT_THAT(link3->getVisualNode()->getChild(0)->getScale(), Vector3Eq(Ogre::Vector3(2, 2, 2))); EXPECT_THAT(link3->getCollisionNode()->numChildren(), Eq(0u)); @@ -144,16 +147,20 @@ TEST_F(RobotTestFixture, load_sets_joint_parents_and_children) { robot_->load(urdf_model_); EXPECT_THAT(robot_->getJoint("test_robot_fixed1")->getParentLinkName(), StrEq("test_robot_link")); - EXPECT_THAT(robot_->getJoint("test_robot_fixed1")->getChildLinkName(), + EXPECT_THAT( + robot_->getJoint("test_robot_fixed1")->getChildLinkName(), StrEq("test_robot_link_right_arm")); EXPECT_THAT(robot_->getJoint("test_robot_fixed2")->getParentLinkName(), StrEq("test_robot_link")); - EXPECT_THAT(robot_->getJoint("test_robot_fixed2")->getChildLinkName(), + EXPECT_THAT( + robot_->getJoint("test_robot_fixed2")->getChildLinkName(), StrEq("test_robot_link_left_arm")); - EXPECT_THAT(robot_->getJoint("test_robot_continuous")->getParentLinkName(), + EXPECT_THAT( + robot_->getJoint("test_robot_continuous")->getParentLinkName(), StrEq("test_robot_link")); - EXPECT_THAT(robot_->getJoint("test_robot_continuous")->getChildLinkName(), + EXPECT_THAT( + robot_->getJoint("test_robot_continuous")->getChildLinkName(), StrEq("test_robot_link_head")); } @@ -245,7 +252,8 @@ TEST_F(RobotTestFixture, update_sets_position_and_orientation_in_links_and_joint Ogre::Quaternion collision_orientation(0, 0, 0, 1); EXPECT_CALL(link_updater, getLinkTransforms(StrEq("test_robot_link"), _, _, _, _)) - .WillOnce(DoAll( + .WillOnce( + DoAll( SetArgReferee<1>(visual_position), SetArgReferee<2>(visual_orientation), SetArgReferee<3>(collision_position), @@ -275,10 +283,12 @@ TEST_F(RobotTestFixture, link_descriptions_show_correct_hierarchy) { EXPECT_THAT(prop->numChildren(), Eq(9)); EXPECT_THAT(prop->childAt(0)->getNameStd(), StrEq("Link Tree Style")); EXPECT_THAT(prop->childAt(5)->getNameStd(), StrEq("test_robot_link")); - EXPECT_THAT(prop->childAt(5)->getDescription().toStdString(), - StrEq("Root Link test_robot_link has 3 child joints: " - "test_robot_continuous, test_robot_fixed1, test_robot_fixed2. " - "Check/uncheck to show/hide this link in the display." + EXPECT_THAT( + prop->childAt(5)->getDescription().toStdString(), + StrEq( + "Root Link test_robot_link has 3 child joints: " + "test_robot_continuous, test_robot_fixed1, test_robot_fixed2. " + "Check/uncheck to show/hide this link in the display." ) ); } @@ -292,10 +302,12 @@ TEST_F(RobotTestFixture, joint_descriptions_show_correct_hierarchy) { EXPECT_THAT(prop->numChildren(), Eq(8)); EXPECT_THAT(prop->childAt(0)->getNameStd(), StrEq("Link Tree Style")); EXPECT_THAT(prop->childAt(5)->getNameStd(), StrEq("test_robot_continuous")); - EXPECT_THAT(prop->childAt(5)->getDescription().toStdString(), - StrEq("Joint test_robot_continuous with parent link test_robot_link " - "and child link test_robot_link_head. " - "Check/uncheck to show/hide this joint's child link." + EXPECT_THAT( + prop->childAt(5)->getDescription().toStdString(), + StrEq( + "Joint test_robot_continuous with parent link test_robot_link " + "and child link test_robot_link_head. " + "Check/uncheck to show/hide this joint's child link." ) ); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp index 0defd4186..5e2abe406 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/tools/pose/pose_tool_test.cpp @@ -107,7 +107,8 @@ TEST_F(PoseToolTestFixture, processMouseEvent_sets_arrow_position_below_mouse_cu EXPECT_THAT(arrows[0]->getPosition(), Vector3Eq(Ogre::Vector3(10, 15, 0))); } -TEST_F(PoseToolTestFixture, +TEST_F( + PoseToolTestFixture, processMouseEvent_sets_arrow_orientation_in_direction_of_the_mouse_while_making_it_visible) { auto left_click_event = generateMousePressEvent(10, 10); auto move_mouse_event = generateMouseMoveWhileLeftClickedEvent(0, 0); diff --git a/rviz_default_plugins/test/rviz_default_plugins/tools/select/selection_tool_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/tools/select/selection_tool_test.cpp index 0d70c3df1..e5ca2e003 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/tools/select/selection_tool_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/tools/select/selection_tool_test.cpp @@ -84,7 +84,8 @@ TEST_F(SelectionToolTestFixture, processMouseEvent_replaces_selection_on_mouse_r selection_tool_->processMouseEvent(click_event); auto release_event = generateMouseReleaseEvent(100, 200); - EXPECT_CALL(*selection_manager_, select( + EXPECT_CALL( + *selection_manager_, select( _, click_event.x, click_event.y, release_event.x, release_event.y, @@ -97,7 +98,8 @@ TEST_F(SelectionToolTestFixture, processMouseEvent_adds_to_selection_when_holdin selection_tool_->processMouseEvent(click_event); auto release_event = generateMouseReleaseEvent(100, 200, Qt::ShiftModifier); - EXPECT_CALL(*selection_manager_, select( + EXPECT_CALL( + *selection_manager_, select( _, click_event.x, click_event.y, release_event.x, release_event.y, @@ -110,7 +112,8 @@ TEST_F(SelectionToolTestFixture, processMouseEvent_removes_from_selection_when_h selection_tool_->processMouseEvent(click_event); auto release_event = generateMouseReleaseEvent(100, 200, Qt::ControlModifier); - EXPECT_CALL(*selection_manager_, select( + EXPECT_CALL( + *selection_manager_, select( _, click_event.x, click_event.y, release_event.x, release_event.y, diff --git a/rviz_default_plugins/test/rviz_default_plugins/transformation/frame_transformer_tf_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/transformation/frame_transformer_tf_test.cpp index 4ee803d7c..ede3d4c9c 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/transformation/frame_transformer_tf_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/transformation/frame_transformer_tf_test.cpp @@ -113,7 +113,8 @@ TEST_F(FrameTransformerTfFixture, canTransform_returns_false_if_frame_does_not_e std::string error; std::string expected_error = "For frame [another_frame]: Frame [another_frame] does not exist"; - EXPECT_FALSE(tf_transformer_->canTransform( + EXPECT_FALSE( + tf_transformer_->canTransform( "fixed_frame", "another_frame", tf2::get_now(), &error)); EXPECT_THAT(error, testing::StrEq(expected_error)); } @@ -124,15 +125,18 @@ TEST_F(FrameTransformerTfFixture, canTransform_returns_false_if_fixed_frame_does std::string error; std::string expected_error = "For frame [frame]: Fixed Frame [another_fixed_frame] does not exist"; - EXPECT_FALSE(tf_transformer_->canTransform( + EXPECT_FALSE( + tf_transformer_->canTransform( "another_fixed_frame", "frame", tf2::get_now(), &error)); EXPECT_THAT(error, testing::StrEq(expected_error)); } TEST_F(FrameTransformerTfFixture, canTransform_returns_false_if_transform_does_not_exist) { tf_wrapper_->getBuffer()->setTransform(getTransformStamped(), "test", true); - tf_wrapper_->getBuffer()->setTransform(getTransformStamped("third_frame", - "fourth_frame"), "test", true); + tf_wrapper_->getBuffer()->setTransform( + getTransformStamped( + "third_frame", + "fourth_frame"), "test", true); std::string error; std::string partial_expected_error = "No transform to fixed frame"; @@ -146,6 +150,7 @@ TEST_F(FrameTransformerTfFixture, canTransform_returns_true_if_transform_exists) tf_wrapper_->getBuffer()->setTransform(getTransformStamped(), "test", true); std::string error; - EXPECT_TRUE(tf_transformer_->canTransform( + EXPECT_TRUE( + tf_transformer_->canTransform( "fixed_frame", "frame", tf2::get_now(), &error)); } diff --git a/rviz_default_plugins/test/rviz_default_plugins/transformation/mock_frame_transformer.hpp b/rviz_default_plugins/test/rviz_default_plugins/transformation/mock_frame_transformer.hpp index 6a6186b93..9bcbf731d 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/transformation/mock_frame_transformer.hpp +++ b/rviz_default_plugins/test/rviz_default_plugins/transformation/mock_frame_transformer.hpp @@ -43,38 +43,45 @@ class MockFrameTransformer : public rviz_common::transformation::FrameTransformer { public: - MOCK_METHOD2(initialize, void( + MOCK_METHOD2( + initialize, void( rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr, rclcpp::Clock::SharedPtr)); MOCK_METHOD0(clear, void()); MOCK_CONST_METHOD0(getAllFrameNames, std::vector()); MOCK_METHOD2( transform, geometry_msgs::msg::PoseStamped( const geometry_msgs::msg::PoseStamped &, const std::string &)); - MOCK_CONST_METHOD3(lookupTransform, geometry_msgs::msg::TransformStamped( + MOCK_CONST_METHOD3( + lookupTransform, geometry_msgs::msg::TransformStamped( const std::string &, const std::string &, const tf2::TimePoint &)); - MOCK_CONST_METHOD5(lookupTransform, geometry_msgs::msg::TransformStamped( + MOCK_CONST_METHOD5( + lookupTransform, geometry_msgs::msg::TransformStamped( const std::string &, const tf2::TimePoint &, const std::string &, const tf2::TimePoint &, const std::string &)); - MOCK_CONST_METHOD4(canTransform, bool( + MOCK_CONST_METHOD4( + canTransform, bool( const std::string &, const std::string &, const tf2::TimePoint &, std::string *)); - MOCK_CONST_METHOD6(canTransform, bool( + MOCK_CONST_METHOD6( + canTransform, bool( const std::string &, const tf2::TimePoint &, const std::string &, const tf2::TimePoint &, const std::string &, std::string *)); - MOCK_METHOD5(waitForTransform, tf2_ros::TransformStampedFuture( + MOCK_METHOD5( + waitForTransform, tf2_ros::TransformStampedFuture( const std::string &, const std::string &, const tf2::TimePoint &, const tf2::Duration &, tf2_ros::TransformReadyCallback)); MOCK_CONST_METHOD2(frameHasProblems, bool(const std::string &, std::string &)); - MOCK_METHOD0(getConnector, + MOCK_METHOD0( + getConnector, rviz_common::transformation::TransformationLibraryConnector::WeakPtr()); }; diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp index e6f3964a8..2ff7ea8a4 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/fps/fps_view_controller_test.cpp @@ -135,7 +135,8 @@ TEST_F(FPSViewControllerTestFixture, moving_the_wheel_moves_camera_in_looking_di EXPECT_THAT(z_position->getValue().toFloat(), FloatNear(0, 0.001f)); } -TEST_F(FPSViewControllerTestFixture, +TEST_F( + FPSViewControllerTestFixture, moving_the_mouse_with_right_button_moves_camera_in_looking_direction) { setCameraToDefaultPosition(); diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp index 215a209a8..2c218ce79 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/orbit/orbit_view_controller_test.cpp @@ -160,7 +160,8 @@ TEST_F(OrbitViewControllerTestFixture, moving_the_mouse_with_shift_and_left_move EXPECT_THAT(z_property->getValue().toFloat(), FloatNear(7.27013f, 0.001f)); } -TEST_F(OrbitViewControllerTestFixture, +TEST_F( + OrbitViewControllerTestFixture, mimic_does_not_change_view_when_given_any_orbit_view_controller) { auto xy_orbit_view = @@ -183,7 +184,8 @@ TEST_F(OrbitViewControllerTestFixture, EXPECT_THAT(pitch_property->getValue().toFloat(), FloatNear(0.5f, 0.001f)); } -TEST_F(OrbitViewControllerTestFixture, +TEST_F( + OrbitViewControllerTestFixture, mimic_keeps_focal_point_and_view_from_top_down_ortho_view_controller) { auto ortho_view = diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp index 236d01733..145b721cd 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/ortho/ortho_view_controller_test.cpp @@ -143,7 +143,8 @@ TEST_F(OrthoViewControllerTestFixture, update_sets_camera_to_position_indicated_ EXPECT_THAT(camera_parent->getPosition(), Vector3Eq(Ogre::Vector3(-2, 2, 500))); } -TEST_F(OrthoViewControllerTestFixture, +TEST_F( + OrthoViewControllerTestFixture, mimic_sets_camera_above_focal_point_when_given_an_orbit_view_controller) { auto orbit_view = std::make_shared(); @@ -163,7 +164,8 @@ TEST_F(OrthoViewControllerTestFixture, EXPECT_THAT(camera_parent->getPosition(), Vector3Eq(Ogre::Vector3(10, 12, 500))); } -TEST_F(OrthoViewControllerTestFixture, +TEST_F( + OrthoViewControllerTestFixture, mimic_does_not_move_camera_when_given_same_class_controller) { auto old_ortho_view = @@ -181,7 +183,8 @@ TEST_F(OrthoViewControllerTestFixture, EXPECT_THAT(y_property->getValue().toFloat(), FloatNear(0, 0.001f)); } -TEST_F(OrthoViewControllerTestFixture, +TEST_F( + OrthoViewControllerTestFixture, mimic_sets_camera_at_view_controller_camera_position_when_given_any_view_controller) { auto controller = std::make_shared(); diff --git a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp index 369d8c520..67be2fd4d 100644 --- a/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp +++ b/rviz_default_plugins/test/rviz_default_plugins/view_controllers/xy_orbit/xy_orbit_view_controller_test.cpp @@ -181,7 +181,8 @@ TEST_F(XYOrbitViewControllerTestFixture, moving_the_focal_point_from_above_moves EXPECT_THAT(z_property->getValue().toFloat(), FloatNear(0, 0.001f)); } -TEST_F(XYOrbitViewControllerTestFixture, +TEST_F( + XYOrbitViewControllerTestFixture, mimic_does_not_change_view_when_changing_back_and_forth_between_orbit_view_controllers) { auto orbit_view = @@ -213,7 +214,8 @@ TEST_F(XYOrbitViewControllerTestFixture, // moving away from frame origin } -TEST_F(XYOrbitViewControllerTestFixture, +TEST_F( + XYOrbitViewControllerTestFixture, mimic_keeps_focal_point_and_view_from_top_down_ortho_view_controller) { auto ortho_view = @@ -240,7 +242,8 @@ TEST_F(XYOrbitViewControllerTestFixture, EXPECT_THAT(z_property->getValue().toFloat(), FloatNear(0, 0.001f)); } -TEST_F(XYOrbitViewControllerTestFixture, +TEST_F( + XYOrbitViewControllerTestFixture, mimic_does_not_move_camera_when_given_same_class_controller) { auto old_orbit_view = @@ -264,12 +267,9 @@ TEST_F(XYOrbitViewControllerTestFixture, auto z_property = xy_orbit_->childAt(9)->childAt(2); auto yaw_property = xy_orbit_->childAt(7); auto pitch_property = xy_orbit_->childAt(8); - EXPECT_THAT(x_property->getValue().toFloat(), - FloatNear(old_x_value, 0.001f)); - EXPECT_THAT(y_property->getValue().toFloat(), - FloatNear(old_y_value, 0.001f)); - EXPECT_THAT(z_property->getValue().toFloat(), - FloatNear(old_z_value, 0.001f)); + EXPECT_THAT(x_property->getValue().toFloat(), FloatNear(old_x_value, 0.001f)); + EXPECT_THAT(y_property->getValue().toFloat(), FloatNear(old_y_value, 0.001f)); + EXPECT_THAT(z_property->getValue().toFloat(), FloatNear(old_z_value, 0.001f)); EXPECT_THAT(yaw_property->getValue().toFloat(), FloatNear(0, 0.001f)); EXPECT_THAT(pitch_property->getValue().toFloat(), FloatNear(0.5f, 0.001f)); } diff --git a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp index 2a7ae4df9..6b033af1a 100644 --- a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp +++ b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/assimp_loader.cpp @@ -230,9 +230,10 @@ Ogre::MeshPtr AssimpLoader::meshFromAssimpScene(const std::string & name, const const aiScene * AssimpLoader::getScene(const std::string & resource_path) { - return importer_->ReadFile(resource_path, - aiProcess_SortByPType | aiProcess_GenNormals | aiProcess_Triangulate | - aiProcess_GenUVCoords | aiProcess_FlipUVs); + return importer_->ReadFile( + resource_path, + aiProcess_SortByPType | aiProcess_GenNormals | aiProcess_Triangulate | + aiProcess_GenUVCoords | aiProcess_FlipUVs); } std::string AssimpLoader::getErrorMessage() diff --git a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/stl_loader.cpp b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/stl_loader.cpp index 3a3dc4c35..b5a269e22 100644 --- a/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/stl_loader.cpp +++ b/rviz_rendering/src/rviz_rendering/mesh_loader_helpers/stl_loader.cpp @@ -57,31 +57,34 @@ bool STLLoader::load(uint8_t * buffer, const size_t num_bytes, const std::string // check for "endsolid" as well if (buffer_str.find("endsolid", 5) != std::string::npos) { - RVIZ_RENDERING_LOG_ERROR_STREAM("The STL file '" << origin << "' is malformed. It " - "starts with the word 'solid' and also contains the " - "word 'endsolid', indicating that it's an ASCII STL " - "file, but rviz can only load binary STL files so it " - "will not be loaded. Please convert it to a " - "binary STL file."); + RVIZ_RENDERING_LOG_ERROR_STREAM( + "The STL file '" << origin << "' is malformed. It " + "starts with the word 'solid' and also contains the " + "word 'endsolid', indicating that it's an ASCII STL " + "file, but rviz can only load binary STL files so it " + "will not be loaded. Please convert it to a " + "binary STL file."); return false; } // chastise the user for malformed files - RVIZ_RENDERING_LOG_WARNING_STREAM("The STL file '" << origin << "' is malformed. It starts " - "with the word 'solid', indicating that it's an ASCII " - "STL file, but it does not contain the word 'endsolid' so " - "it is either a malformed ASCII STL file or it is actually " - "a binary STL file. Trying to interpret it as a binary " - "STL file instead."); + RVIZ_RENDERING_LOG_WARNING_STREAM( + "The STL file '" << origin << "' is malformed. It starts " + "with the word 'solid', indicating that it's an ASCII " + "STL file, but it does not contain the word 'endsolid' so " + "it is either a malformed ASCII STL file or it is actually " + "a binary STL file. Trying to interpret it as a binary " + "STL file instead."); } // make sure there's enough data for a binary STL header and triangle count static const size_t binary_stl_header_len = 84; if (num_bytes <= binary_stl_header_len) { - RVIZ_RENDERING_LOG_ERROR_STREAM("The STL file '" << origin << "' is malformed. It " - "appears to be a binary STL file but does not contain " - "enough data for the 80 byte header and 32-bit integer " - "triangle count."); + RVIZ_RENDERING_LOG_ERROR_STREAM( + "The STL file '" << origin << "' is malformed. It " + "appears to be a binary STL file but does not contain " + "enough data for the 80 byte header and 32-bit integer " + "triangle count."); return false; } @@ -90,15 +93,17 @@ bool STLLoader::load(uint8_t * buffer, const size_t num_bytes, const std::string static const size_t number_of_bytes_per_triangle = 50; size_t expected_size = binary_stl_header_len + num_triangles * number_of_bytes_per_triangle; if (num_bytes < expected_size) { - RVIZ_RENDERING_LOG_ERROR_STREAM("The STL file '" << origin << "' is malformed. According " - "to the binary STL header it should have '" << - num_triangles << "' triangles, but it has too little data for that to be the case."); + RVIZ_RENDERING_LOG_ERROR_STREAM( + "The STL file '" << origin << "' is malformed. According " + "to the binary STL header it should have '" << + num_triangles << "' triangles, but it has too little data for that to be the case."); return false; } else if (num_bytes > expected_size) { - RVIZ_RENDERING_LOG_WARNING_STREAM("The STL file '" << origin << "' is malformed. According " - "to the binary STL header it should have '" << - num_triangles << "' triangles, but it has too much" << - " data for that to be the case. The extra data will be ignored."); + RVIZ_RENDERING_LOG_WARNING_STREAM( + "The STL file '" << origin << "' is malformed. According " + "to the binary STL header it should have '" << + num_triangles << "' triangles, but it has too much" << + " data for that to be the case. The extra data will be ignored."); } // load the binary STL data diff --git a/rviz_rendering/src/rviz_rendering/objects/arrow.cpp b/rviz_rendering/src/rviz_rendering/objects/arrow.cpp index f07b39588..f70e6cba6 100644 --- a/rviz_rendering/src/rviz_rendering/objects/arrow.cpp +++ b/rviz_rendering/src/rviz_rendering/objects/arrow.cpp @@ -120,8 +120,8 @@ void Arrow::setOrientation(const Ogre::Quaternion & orientation) { // "forward" (negative z) should always be our identity orientation // ... wouldn't need to mangle the orientation if we just fix the cylinders! - scene_node_->setOrientation(orientation * - Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_X) ); + scene_node_->setOrientation( + orientation * Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_X) ); } void Arrow::setDirection(const Ogre::Vector3 & direction) diff --git a/rviz_rendering/src/rviz_rendering/objects/billboard_line.cpp b/rviz_rendering/src/rviz_rendering/objects/billboard_line.cpp index 739620247..f986a5e20 100644 --- a/rviz_rendering/src/rviz_rendering/objects/billboard_line.cpp +++ b/rviz_rendering/src/rviz_rendering/objects/billboard_line.cpp @@ -176,7 +176,8 @@ void BillboardLine::addPoint(const Ogre::Vector3 & point) void BillboardLine::addPoint(const Ogre::Vector3 & point, const Ogre::ColourValue & color) { assert(current_line_ < num_lines_); - assert(chain_containers_[current_chain_container_]-> + assert( + chain_containers_[current_chain_container_]-> getNumChainElements(current_line_ % chains_per_container_) <= max_points_per_line_); incrementChainContainerIfNecessary(); @@ -204,7 +205,8 @@ void BillboardLine::setLineWidth(float width) { width_ = width; - changeAllElements([width](Ogre::BillboardChain::Element element) { + changeAllElements( + [width](Ogre::BillboardChain::Element element) { element.width = width; return element; }); @@ -232,7 +234,8 @@ void BillboardLine::setColor(float r, float g, float b, float a) color_ = Ogre::ColourValue(r, g, b, a); - changeAllElements([this](Ogre::BillboardChain::Element element) { + changeAllElements( + [this](Ogre::BillboardChain::Element element) { element.colour = color_; return element; }); diff --git a/rviz_rendering/src/rviz_rendering/objects/covariance_visual.cpp b/rviz_rendering/src/rviz_rendering/objects/covariance_visual.cpp index d47e98c14..475be7a89 100644 --- a/rviz_rendering/src/rviz_rendering/objects/covariance_visual.cpp +++ b/rviz_rendering/src/rviz_rendering/objects/covariance_visual.cpp @@ -125,12 +125,14 @@ diagonalizeCovariance( eigenvectors = eigensolver.eigenvectors(); if (eigenvalues.minCoeff() < 0) { - RVIZ_RENDERING_LOG_WARNING("Negative eigenvalue found for position. Is the " + RVIZ_RENDERING_LOG_WARNING( + "Negative eigenvalue found for position. Is the " "covariance matrix correct (positive semidefinite)?"); covariance_valid = false; } } else { - RVIZ_RENDERING_LOG_WARNING("failed to compute eigen vectors/values for position. Is the " + RVIZ_RENDERING_LOG_WARNING( + "failed to compute eigen vectors/values for position. Is the " "covariance matrix correct?"); covariance_valid = false; } @@ -198,9 +200,11 @@ computeShapeScaleAndOrientation2D(const Eigen::Matrix2d & covariance, Plane plan Ogre::Quaternion orientation; switch (plane) { case Plane::YZ_PLANE: - orientation.FromRotationMatrix(Ogre::Matrix3(1, 0, 0, - 0, eigenvectors[0][0], eigenvectors[0][1], - 0, eigenvectors[1][0], eigenvectors[1][1])); + orientation.FromRotationMatrix( + Ogre::Matrix3( + 1, 0, 0, + 0, eigenvectors[0][0], eigenvectors[0][1], + 0, eigenvectors[1][0], eigenvectors[1][1])); scale.x = 0; scale.y = 2.f * std::sqrt(eigenvalues[0]); @@ -208,9 +212,11 @@ computeShapeScaleAndOrientation2D(const Eigen::Matrix2d & covariance, Plane plan break; case Plane::XZ_PLANE: - orientation.FromRotationMatrix(Ogre::Matrix3(eigenvectors[0][0], 0, eigenvectors[0][1], - 0, 1, 0, - eigenvectors[1][0], 0, eigenvectors[1][1])); + orientation.FromRotationMatrix( + Ogre::Matrix3( + eigenvectors[0][0], 0, eigenvectors[0][1], + 0, 1, 0, + eigenvectors[1][0], 0, eigenvectors[1][1])); scale.x = 2.f * std::sqrt(eigenvalues[0]); scale.y = 0; @@ -218,9 +224,11 @@ computeShapeScaleAndOrientation2D(const Eigen::Matrix2d & covariance, Plane plan break; case Plane::XY_PLANE: - orientation.FromRotationMatrix(Ogre::Matrix3(eigenvectors[0][0], eigenvectors[0][1], 0, - eigenvectors[1][0], eigenvectors[1][1], 0, - 0, 0, 1)); + orientation.FromRotationMatrix( + Ogre::Matrix3( + eigenvectors[0][0], eigenvectors[0][1], 0, + eigenvectors[1][0], eigenvectors[1][1], 0, + 0, 0, 1)); scale.x = 2.f * std::sqrt(eigenvalues[0]); scale.y = 2.f * std::sqrt(eigenvalues[1]); diff --git a/rviz_rendering/src/rviz_rendering/objects/movable_text.cpp b/rviz_rendering/src/rviz_rendering/objects/movable_text.cpp index d2e5285d7..7c9df6fbf 100644 --- a/rviz_rendering/src/rviz_rendering/objects/movable_text.cpp +++ b/rviz_rendering/src/rviz_rendering/objects/movable_text.cpp @@ -119,7 +119,8 @@ void MovableText::setFontName(const Ogre::String & font_name) font_name_ = font_name; font_ = Ogre::FontManager::getSingleton().getByName(font_name_, MATERIAL_GROUP).get(); if (!font_) { - throw Ogre::Exception(Ogre::Exception::ERR_ITEM_NOT_FOUND, "Could not find font " + + throw Ogre::Exception( + Ogre::Exception::ERR_ITEM_NOT_FOUND, "Could not find font " + font_name, "MovableText::setFontName"); } @@ -351,7 +352,8 @@ Ogre::HardwareVertexBufferSharedPtr MovableText::setupHardwareBuffers() const offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3); if (!declaration->findElementBySemantic(Ogre::VES_TEXTURE_COORDINATES)) { - declaration->addElement(POS_TEX_BINDING, offset, Ogre::VET_FLOAT2, + declaration->addElement( + POS_TEX_BINDING, offset, Ogre::VET_FLOAT2, Ogre::VES_TEXTURE_COORDINATES, 0); } diff --git a/rviz_rendering/src/rviz_rendering/objects/point_cloud.cpp b/rviz_rendering/src/rviz_rendering/objects/point_cloud.cpp index 28387b01b..0f8fffbc6 100644 --- a/rviz_rendering/src/rviz_rendering/objects/point_cloud.cpp +++ b/rviz_rendering/src/rviz_rendering/objects/point_cloud.cpp @@ -275,8 +275,10 @@ float PointCloud::getBoundingRadius() const { return bounding_box_.isNull() ? 0.0f : - Ogre::Math::Sqrt(std::max(bounding_box_.getMaximum().squaredLength(), - bounding_box_.getMinimum().squaredLength())); + Ogre::Math::Sqrt( + std::max( + bounding_box_.getMaximum().squaredLength(), + bounding_box_.getMinimum().squaredLength())); } void PointCloud::getWorldTransforms(Ogre::Matrix4 * xform) const @@ -479,14 +481,16 @@ void PointCloud::addPoints( if (internals.bufferIsFull()) { assert(internals.noBufferOverflowOccurred()); - finishRenderable(internals, + finishRenderable( + internals, static_cast(internals.rend->getBuffer()->getNumVertices())); internals = createNewRenderable(static_cast(stop_iterator - current_point)); } internals.aabb.merge(current_point->position); - internals = addPointToHardwareBuffer(internals, current_point, - static_cast(current_point - start_iterator)); + internals = addPointToHardwareBuffer( + internals, current_point, + static_cast(current_point - start_iterator)); } finishRenderable(internals, internals.current_vertex_count); @@ -502,8 +506,9 @@ PointCloud::RenderableInternals PointCloud::createNewRenderable(uint32_t number_of_points_to_be_added) { RenderableInternals internals; - internals.buffer_size = std::min(VERTEX_BUFFER_CAPACITY, - number_of_points_to_be_added * getVerticesPerPoint()); + internals.buffer_size = std::min( + VERTEX_BUFFER_CAPACITY, + number_of_points_to_be_added * getVerticesPerPoint()); internals.rend = createRenderable(internals.buffer_size, getRenderOperationType()); @@ -595,7 +600,8 @@ PointCloud::addPointToHardwareBuffer( *iptr = color; ++float_buffer; - assert(reinterpret_cast(float_buffer) <= + assert( + reinterpret_cast(float_buffer) <= reinterpret_cast(float_buffer) + internals.rend->getBuffer()->getNumVertices() * internals.rend->getRenderOperation()->vertexData->vertexDeclaration->getVertexSize(0)); @@ -696,8 +702,8 @@ PointCloudRenderablePtr PointCloud::createRenderable( int num_points, Ogre::RenderOperation::OperationType operation_type) { - PointCloudRenderablePtr rend(new PointCloudRenderable(this, num_points, - !current_mode_supports_geometry_shader_, operation_type)); + PointCloudRenderablePtr rend(new PointCloudRenderable( + this, num_points, !current_mode_supports_geometry_shader_, operation_type)); rend->setMaterial(current_material_); Ogre::Vector4 alpha(alpha_, 0.0f, 0.0f, 0.0f); Ogre::Vector4 highlight(0.0f, 0.0f, 0.0f, 0.0f); diff --git a/rviz_rendering/src/rviz_rendering/objects/point_cloud_renderable.cpp b/rviz_rendering/src/rviz_rendering/objects/point_cloud_renderable.cpp index d7c35680e..98e682e3c 100644 --- a/rviz_rendering/src/rviz_rendering/objects/point_cloud_renderable.cpp +++ b/rviz_rendering/src/rviz_rendering/objects/point_cloud_renderable.cpp @@ -67,8 +67,10 @@ void PointCloudRenderable::_notifyCurrentCamera(Ogre::Camera * camera) Ogre::Real PointCloudRenderable::getBoundingRadius() const { - return Ogre::Math::Sqrt(std::max(mBox.getMaximum().squaredLength(), - mBox.getMinimum().squaredLength())); + return Ogre::Math::Sqrt( + std::max( + mBox.getMaximum().squaredLength(), + mBox.getMinimum().squaredLength())); } Ogre::Real PointCloudRenderable::getSquaredViewDepth(const Ogre::Camera * cam) const diff --git a/rviz_rendering/src/rviz_rendering/render_system.cpp b/rviz_rendering/src/rviz_rendering/render_system.cpp index 384007ea3..836adb9c6 100644 --- a/rviz_rendering/src/rviz_rendering/render_system.cpp +++ b/rviz_rendering/src/rviz_rendering/render_system.cpp @@ -173,9 +173,8 @@ RenderSystem::setupDummyWindowId() XVisualInfo * visual = glXChooseVisual(display, screen, attribList); - dummy_window_id_ = XCreateSimpleWindow(display, - RootWindow(display, screen), - 0, 0, 1, 1, 0, 0, 0); + dummy_window_id_ = XCreateSimpleWindow( + display, RootWindow(display, screen), 0, 0, 1, 1, 0, 0, 0); GLXContext context = glXCreateContext(display, visual, nullptr, 1); @@ -368,8 +367,8 @@ void RenderSystem::addAdditionalResourcesFromAmentIndex() const for (auto resource : resource_locations) { std::string content; std::string prefix_path; - if (ament_index_cpp::get_resource(RVIZ_OGRE_MEDIA_RESOURCE_NAME, resource.first, content, - &prefix_path)) + if (ament_index_cpp::get_resource( + RVIZ_OGRE_MEDIA_RESOURCE_NAME, resource.first, content, &prefix_path)) { std::vector filenames = string_helper::splitStringIntoTrimmedItems(content, '\n'); @@ -378,8 +377,8 @@ void RenderSystem::addAdditionalResourcesFromAmentIndex() const if (!QDir(QString::fromStdString(resource_path)).exists()) { RVIZ_RENDERING_LOG_WARNING_STREAM("Could not find folder " << resource_path); } - Ogre::ResourceGroupManager::getSingleton().addResourceLocation(resource_path, "FileSystem", - "rviz_rendering"); + Ogre::ResourceGroupManager::getSingleton().addResourceLocation( + resource_path, "FileSystem", "rviz_rendering"); } } } diff --git a/rviz_rendering/src/rviz_rendering/string_helper.cpp b/rviz_rendering/src/rviz_rendering/string_helper.cpp index 91bb39d4c..8cf250d98 100644 --- a/rviz_rendering/src/rviz_rendering/string_helper.cpp +++ b/rviz_rendering/src/rviz_rendering/string_helper.cpp @@ -43,12 +43,14 @@ std::vector rviz_rendering::string_helper::splitStringIntoTrimmedIt std::string item; std::vector filenames; while (std::getline(stringstream, item, delimiter)) { - auto whitespace_front = std::find_if_not(item.begin(), item.end(), [](char character) { - return std::isspace(character, std::locale("")); - }); - auto whitespace_back = std::find_if_not(item.rbegin(), item.rend(), [](char character) { - return std::isspace(character, std::locale("")); - }); + auto whitespace_front = std::find_if_not( + item.begin(), item.end(), [](char character) { + return std::isspace(character, std::locale("")); + }); + auto whitespace_back = std::find_if_not( + item.rbegin(), item.rend(), [](char character) { + return std::isspace(character, std::locale("")); + }); item.erase(whitespace_back.base(), item.end()); item.erase(item.begin(), whitespace_front); if (!item.empty()) { diff --git a/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp b/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp index 34e72ab43..ed03d253e 100644 --- a/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/billboard_line_test.cpp @@ -124,8 +124,8 @@ TEST_F(BillboardLineTestFixture, new_billboard_contains_correct_points_as_boundi auto chains = grid_cell->getChains(); // chains are basically bounded by the square - auto bounding_box = Ogre::AxisAlignedBox(Ogre::Vector3(-1.1f, -1.1f, -0.1f), - Ogre::Vector3(1.1f, 1.1f, 0.1f)); + auto bounding_box = Ogre::AxisAlignedBox( + Ogre::Vector3(-1.1f, -1.1f, -0.1f), Ogre::Vector3(1.1f, 1.1f, 0.1f)); ASSERT_THAT(chains[0]->getBoundingBox(), Eq(bounding_box)); } diff --git a/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp b/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp index da9adcebf..8cfabe724 100644 --- a/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/covariance_visual_test.cpp @@ -115,10 +115,12 @@ void assertCovarianceOrientationOffsetIsPresent( { bool found = false; for (auto entity : entities) { - if (Matches(Vector3Eq(direction))(entity->getParentSceneNode()->getParentSceneNode() - ->getParentSceneNode()->getPosition()) && - Matches(Vector3Eq(Ogre::Vector3(length, length, length)))(entity->getParentSceneNode() - ->getParentSceneNode()->getParentSceneNode()->getParentSceneNode()->getScale())) + if (Matches(Vector3Eq(direction))( + entity->getParentSceneNode()->getParentSceneNode() + ->getParentSceneNode()->getPosition()) && + Matches(Vector3Eq(Ogre::Vector3(length, length, length)))( + entity->getParentSceneNode() + ->getParentSceneNode()->getParentSceneNode()->getParentSceneNode()->getScale())) { found = true; } @@ -135,19 +137,23 @@ TEST_F(CovarianceVisualTestFixture, covariance_visual_3D) EXPECT_THAT(covariance_visual_node_->getPosition(), Vector3Eq(position)); auto all_spheres = findAllSpheres(covariance_visual_node_); ASSERT_THAT(all_spheres, SizeIs(1)); - EXPECT_THAT(all_spheres[0]->getParentSceneNode()->getPosition(), + EXPECT_THAT( + all_spheres[0]->getParentSceneNode()->getPosition(), Vector3Eq(Ogre::Vector3(0.0, 0.0, 0.0))); EXPECT_TRUE(all_spheres[0]->isVisible()); auto all_orientation_uncertainties = findAllCylinders(covariance_visual_node_); ASSERT_THAT(all_orientation_uncertainties, SizeIs(3)); - assertCovarianceOrientationOffsetIsPresent(all_orientation_uncertainties, + assertCovarianceOrientationOffsetIsPresent( + all_orientation_uncertainties, Ogre::Vector3::UNIT_Y, offset); EXPECT_TRUE(all_orientation_uncertainties[0]->isVisible()); - assertCovarianceOrientationOffsetIsPresent(all_orientation_uncertainties, + assertCovarianceOrientationOffsetIsPresent( + all_orientation_uncertainties, Ogre::Vector3::UNIT_X, offset); EXPECT_TRUE(all_orientation_uncertainties[1]->isVisible()); - assertCovarianceOrientationOffsetIsPresent(all_orientation_uncertainties, + assertCovarianceOrientationOffsetIsPresent( + all_orientation_uncertainties, Ogre::Vector3::UNIT_Z, offset); EXPECT_TRUE(all_orientation_uncertainties[2]->isVisible()); @@ -165,7 +171,8 @@ TEST_F(CovarianceVisualTestFixture, covariance_visual_2D) EXPECT_THAT(covariance_visual_node_->getPosition(), Vector3Eq(position)); auto all_spheres = findAllSpheres(covariance_visual_node_); ASSERT_THAT(all_spheres, SizeIs(1)); - EXPECT_THAT(all_spheres[0]->getParentSceneNode()->getPosition(), + EXPECT_THAT( + all_spheres[0]->getParentSceneNode()->getPosition(), Vector3Eq(Ogre::Vector3(0.0, 0.0, 0.0))); EXPECT_TRUE(all_spheres[0]->isVisible()); diff --git a/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp b/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp index fa43955d2..82a128ee4 100644 --- a/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/grid_test.cpp @@ -76,12 +76,14 @@ Ogre::AxisAlignedBox expectedBoxForBillboards( float cell_length, float line_width) { return Ogre::AxisAlignedBox( - Ogre::Vector3(-cell_length * cell_count / 2 - line_width, - -cell_length * height_count / 2 - line_width, - -cell_length * cell_count / 2 - line_width), - Ogre::Vector3(cell_length * cell_count / 2 + line_width, - cell_length * height_count / 2 + line_width, - cell_length * cell_count / 2 + line_width)); + Ogre::Vector3( + -cell_length * cell_count / 2 - line_width, + -cell_length * height_count / 2 - line_width, + -cell_length * cell_count / 2 - line_width), + Ogre::Vector3( + cell_length * cell_count / 2 + line_width, + cell_length * height_count / 2 + line_width, + cell_length * cell_count / 2 + line_width)); } Ogre::AxisAlignedBox expectedBoxForLines( @@ -118,14 +120,15 @@ TEST_F(GridTestFixture, setHeight_creates_object_with_correct_height_in_bounding ASSERT_THAT(manual_object->getBoundingBox(), Eq(expected_bounding_box)); } -TEST_F(GridTestFixture, +TEST_F( + GridTestFixture, createGrid_returns_billboard_object_with_bounding_box_bounding_cells_including_billboard_size) { uint32_t cell_count = 2; float cell_length = 2.0f; float line_width = 0.1f; - auto grid = createGrid(rviz_rendering::Grid::Style::Billboards, - cell_count, cell_length, line_width); + auto grid = createGrid( + rviz_rendering::Grid::Style::Billboards, cell_count, cell_length, line_width); grid.create(); @@ -139,8 +142,8 @@ TEST_F(GridTestFixture, setStyle_creates_a_new_grid_with_new_style) { float cell_length = 2.0f; float line_width = 0.1f; - auto grid = createGrid(rviz_rendering::Grid::Style::Lines, - cell_count, cell_length, line_width); + auto grid = createGrid( + rviz_rendering::Grid::Style::Lines, cell_count, cell_length, line_width); grid.create(); grid.setStyle(rviz_rendering::Grid::Style::Billboards); diff --git a/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp b/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp index 5bd326fc3..f1c3a4f16 100644 --- a/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/movable_text_test.cpp @@ -121,7 +121,8 @@ TEST_F(MovableTextTestFixture, larger_char_height_makes_characters_wider) { TEST_F(MovableTextTestFixture, horizontal_alignment_center_centers_x_coordinate) { auto movable_text = std::make_shared("W"); - movable_text->setTextAlignment(rviz_rendering::MovableText::HorizontalAlignment::H_CENTER, + movable_text->setTextAlignment( + rviz_rendering::MovableText::HorizontalAlignment::H_CENTER, rviz_rendering::MovableText::VerticalAlignment::V_BELOW); movable_text->update(); @@ -137,7 +138,8 @@ TEST_F(MovableTextTestFixture, horizontal_alignment_center_centers_x_coordinate) TEST_F(MovableTextTestFixture, vertical_alignment_center_centers_y_coordinate) { auto movable_text = std::make_shared("W"); - movable_text->setTextAlignment(rviz_rendering::MovableText::HorizontalAlignment::H_LEFT, + movable_text->setTextAlignment( + rviz_rendering::MovableText::HorizontalAlignment::H_LEFT, rviz_rendering::MovableText::VerticalAlignment::V_CENTER); movable_text->update(); @@ -153,7 +155,8 @@ TEST_F(MovableTextTestFixture, vertical_alignment_center_centers_y_coordinate) { TEST_F(MovableTextTestFixture, vertical_alignment_above_puts_y_coordinate_above_zero) { auto movable_text = std::make_shared("W"); - movable_text->setTextAlignment(rviz_rendering::MovableText::HorizontalAlignment::H_LEFT, + movable_text->setTextAlignment( + rviz_rendering::MovableText::HorizontalAlignment::H_LEFT, rviz_rendering::MovableText::VerticalAlignment::V_ABOVE); movable_text->update(); @@ -169,7 +172,8 @@ TEST_F(MovableTextTestFixture, vertical_alignment_above_puts_y_coordinate_above_ TEST_F(MovableTextTestFixture, vertical_alignment_above_puts_y_coordinate_above) { auto movable_text = std::make_shared("W\nW"); - movable_text->setTextAlignment(rviz_rendering::MovableText::HorizontalAlignment::H_LEFT, + movable_text->setTextAlignment( + rviz_rendering::MovableText::HorizontalAlignment::H_LEFT, rviz_rendering::MovableText::VerticalAlignment::V_ABOVE); movable_text->update(); @@ -217,7 +221,8 @@ TEST_F(MovableTextTestFixture, setLineSpacing_changes_space_between_lines) { TEST_F(MovableTextTestFixture, horizontal_alignment_works_correctly_with_spaces) { auto movable_text = std::make_shared("A A"); - movable_text->setTextAlignment(rviz_rendering::MovableText::HorizontalAlignment::H_CENTER, + movable_text->setTextAlignment( + rviz_rendering::MovableText::HorizontalAlignment::H_CENTER, rviz_rendering::MovableText::VerticalAlignment::V_BELOW); movable_text->update(); diff --git a/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp b/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp index 0db21a258..23210ead4 100644 --- a/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/point_cloud_renderable_test.cpp @@ -92,7 +92,8 @@ TEST_F(PointCloudRenderableTestFixture, renderable_contains_a_correctly_filled_b renderable_->getRenderOperation()->operationType, Eq(Ogre::RenderOperation::OT_TRIANGLE_LIST)); } -TEST_F(PointCloudRenderableTestFixture, +TEST_F( + PointCloudRenderableTestFixture, getSquaredViewDepth_returns_squared_length_to_center_of_bounding_box_for_default_camera) { Ogre::Camera * camera = Ogre::Root::getSingletonPtr() ->createSceneManager() diff --git a/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp b/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp index d7d45ac57..23c4b45f7 100644 --- a/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp +++ b/rviz_rendering/test/rviz_rendering/objects/point_cloud_test.cpp @@ -112,7 +112,8 @@ TEST_F(PointCloudTestFixture, clear_resets_bounding_box_bounding_radius_and_clea ASSERT_THAT(point_cloud->getBoundingRadius(), FloatEq(0.0f)); } -TEST_F(PointCloudTestFixture, +TEST_F( + PointCloudTestFixture, getBoundingRadius_returns_length_to_point_farthest_away_from_origin) { auto point_cloud = std::make_shared(); @@ -121,7 +122,8 @@ TEST_F(PointCloudTestFixture, ASSERT_THAT(point_cloud->getBoundingRadius(), FloatEq(Ogre::Math::Sqrt(2))); } -TEST_F(PointCloudTestFixture, +TEST_F( + PointCloudTestFixture, for_one_point_getBoundingBox_returns_bounding_box_containing_only_one_point) { auto point_cloud = std::make_shared(); @@ -240,7 +242,8 @@ TEST_F(PointCloudTestFixture, setRenderMode_changes_material) { } } -TEST_F(PointCloudTestFixture, +TEST_F( + PointCloudTestFixture, setRenderMode_regenerates_renderables_with_different_size_when_geometry_support_changes) { auto point_cloud = std::make_shared(); point_cloud->addPoints(singlePointArray.begin(), singlePointArray.end()); @@ -296,7 +299,8 @@ TEST_F(PointCloudTestFixture, addPoints_adds_vertices_with_correct_geometry_when ASSERT_THAT(number_of_vertices_in_all_renderables, Eq(number_of_vertices_per_flat_square * 5)); } -TEST_F(PointCloudTestFixture, +TEST_F( + PointCloudTestFixture, adding_and_removing_points_many_times_does_not_lead_to_superfluous_renderables) { auto point_cloud = std::make_shared(); point_cloud->setRenderMode(rviz_rendering::PointCloud::RM_BOXES); diff --git a/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp b/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp index 325c17f4e..4b6acaaf0 100644 --- a/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp +++ b/rviz_rendering/test/rviz_rendering/scene_graph_introspection.cpp @@ -165,8 +165,8 @@ std::vector findAllAxes(Ogre::SceneNode * scene_node) ->getParentSceneNode() // SceneNode from cylinder_entity ->getParentSceneNode(); // SceneNode from axes if (axes_scene_node) { - auto local_cylinder_entities = findAllEntitiesByMeshName(axes_scene_node, - "rviz_cylinder.mesh"); + auto local_cylinder_entities = findAllEntitiesByMeshName( + axes_scene_node, "rviz_cylinder.mesh"); if (local_cylinder_entities.size() == 3 && std::find(axes.begin(), axes.end(), axes_scene_node) == axes.end()) { @@ -187,7 +187,8 @@ Ogre::SceneNode * findOneAxes(Ogre::SceneNode * scene_node) std::vector getPositionsFromNodes(const std::vector & nodes) { std::vector positions(nodes.size(), Ogre::Vector3::ZERO); - std::transform(nodes.cbegin(), nodes.cend(), positions.begin(), [](auto node) { + std::transform( + nodes.cbegin(), nodes.cend(), positions.begin(), [](auto node) { return node->getPosition(); }); return positions; @@ -196,7 +197,8 @@ std::vector getPositionsFromNodes(const std::vector getOrientationsFromNodes(const std::vector & nodes) { std::vector orientations(nodes.size(), Ogre::Quaternion::IDENTITY); - std::transform(nodes.cbegin(), nodes.cend(), orientations.begin(), [](auto node) { + std::transform( + nodes.cbegin(), nodes.cend(), orientations.begin(), [](auto node) { return node->getOrientation(); }); return orientations; diff --git a/rviz_rendering_tests/test/test_rviz_ogre_media_exports.cpp b/rviz_rendering_tests/test/test_rviz_ogre_media_exports.cpp index da0e32ef9..6fad5d083 100644 --- a/rviz_rendering_tests/test/test_rviz_ogre_media_exports.cpp +++ b/rviz_rendering_tests/test/test_rviz_ogre_media_exports.cpp @@ -38,18 +38,21 @@ TEST(CMake_Macro__Test, correctly_registers_plugin_in_ament_index) { std::string content; std::string prefix_path; - ASSERT_TRUE(ament_index_cpp::get_resource("rviz_ogre_media_exports", "rviz_rendering_tests", - content, - &prefix_path)); + ASSERT_TRUE( + ament_index_cpp::get_resource( + "rviz_ogre_media_exports", "rviz_rendering_tests", + content, + &prefix_path)); } TEST(CMake_Macro__Test, ament_index_resource_file_has_correct_content) { std::string content; std::string prefix_path; - ament_index_cpp::get_resource("rviz_ogre_media_exports", "rviz_rendering_tests", content, - &prefix_path); + ament_index_cpp::get_resource( + "rviz_ogre_media_exports", "rviz_rendering_tests", content, &prefix_path); - ASSERT_EQ(content, + ASSERT_EQ( + content, "rviz_rendering_tests/ogre_media_resources/scripts\n" "rviz_rendering_tests/ogre_media_resources/meshes\n"); } @@ -57,8 +60,8 @@ TEST(CMake_Macro__Test, ament_index_resource_file_has_correct_content) { TEST(CMake_Macro__Test, folders_are_installed_to_correct_location) { std::string content; std::string prefix_path; - ament_index_cpp::get_resource("rviz_ogre_media_exports", "rviz_rendering_tests", content, - &prefix_path); + ament_index_cpp::get_resource( + "rviz_ogre_media_exports", "rviz_rendering_tests", content, &prefix_path); struct stat info; std::string scripts = prefix_path + "/share/rviz_rendering_tests/ogre_media_resources/scripts"; diff --git a/rviz_visual_testing_framework/src/internal/display_handler.cpp b/rviz_visual_testing_framework/src/internal/display_handler.cpp index 04e97174b..29d59de38 100644 --- a/rviz_visual_testing_framework/src/internal/display_handler.cpp +++ b/rviz_visual_testing_framework/src/internal/display_handler.cpp @@ -115,7 +115,8 @@ void DisplayHandler::removeAllDisplays() void DisplayHandler::removeDisplay(std::shared_ptr display) { - executor_->queueAction([this, display]() { + executor_->queueAction( + [this, display]() { this->removeDisplayWithoutDelay(display->getDisplayId()); } ); @@ -123,7 +124,8 @@ void DisplayHandler::removeDisplay(std::shared_ptr display) void DisplayHandler::openAddDisplayDialog() { - executor_->queueAction([this]() { + executor_->queueAction( + [this]() { auto add_display_button = this->getAddDisplayButton(); QTest::mouseClick(add_display_button, Qt::MouseButton::LeftButton); @@ -133,7 +135,8 @@ void DisplayHandler::openAddDisplayDialog() void DisplayHandler::selectDisplayAndConfirm(std::shared_ptr page_object) { - executor_->queueAction([page_object]() { + executor_->queueAction( + [page_object]() { auto add_display_dialog_window = QApplication::activeWindow(); auto create_visualization_type_box = add_display_dialog_window->findChild( diff --git a/rviz_visual_testing_framework/src/internal/image_tester.cpp b/rviz_visual_testing_framework/src/internal/image_tester.cpp index 64f1bc118..e4a714aa6 100644 --- a/rviz_visual_testing_framework/src/internal/image_tester.cpp +++ b/rviz_visual_testing_framework/src/internal/image_tester.cpp @@ -76,7 +76,8 @@ void ImageTester::assertImageIdentity( ".\n"; } - resizeAndCropImage(image_name, test_image, reference_image_width, + resizeAndCropImage( + image_name, test_image, reference_image_width, reference_image_height, test_image_width, test_image_height); size_t different_pixels_number = pixelDifference( diff --git a/rviz_visual_testing_framework/src/internal/rviz_scene_test.cpp b/rviz_visual_testing_framework/src/internal/rviz_scene_test.cpp index 7b3f68797..2de7a4577 100644 --- a/rviz_visual_testing_framework/src/internal/rviz_scene_test.cpp +++ b/rviz_visual_testing_framework/src/internal/rviz_scene_test.cpp @@ -88,7 +88,8 @@ void RvizTestScene::takeTestShot(Ogre::String name) void RvizTestScene::takeScreenShot(Ogre::String name) { - executor_->queueAction([this, name] { + executor_->queueAction( + [this, name] { render_window_->captureScreenShot(name); } ); diff --git a/rviz_visual_testing_framework/src/internal/visual_test.cpp b/rviz_visual_testing_framework/src/internal/visual_test.cpp index abb99bfaa..508581d28 100644 --- a/rviz_visual_testing_framework/src/internal/visual_test.cpp +++ b/rviz_visual_testing_framework/src/internal/visual_test.cpp @@ -80,8 +80,9 @@ void VisualTest::takeReferenceScreenShot( Ogre::String screenshot_name, std::shared_ptr display) { std::string images_name = QDir::toNativeSeparators( - QString::fromStdString(source_directory_path_ + reference_images_path_suffix_ + - screenshot_name)).toStdString(); + QString::fromStdString( + source_directory_path_ + reference_images_path_suffix_ + + screenshot_name)).toStdString(); if (display) { display->captureDisplayRenderWindow(images_name + "_ref.png"); @@ -94,8 +95,9 @@ void VisualTest::takeTestScreenShot( Ogre::String screenshot_name, std::shared_ptr display) { std::string images_name = QDir::toNativeSeparators( - QString::fromStdString(build_directory_path_ + test_images_path_suffix_ + - screenshot_name)).toStdString(); + QString::fromStdString( + build_directory_path_ + test_images_path_suffix_ + + screenshot_name)).toStdString(); if (display) { display->captureDisplayRenderWindow(images_name + ".png"); @@ -148,8 +150,9 @@ void VisualTest::setTesterThreshold(double threshold) bool VisualTest::checkImageExists(std::string & name) { const std::string reference_image_name = QDir::toNativeSeparators( - QString::fromStdString(source_directory_path_ + reference_images_path_suffix_ + - name + "_ref.png")).toStdString(); + QString::fromStdString( + source_directory_path_ + reference_images_path_suffix_ + + name + "_ref.png")).toStdString(); struct stat buffer; return stat(reference_image_name.c_str(), &buffer) == 0; @@ -157,8 +160,9 @@ bool VisualTest::checkImageExists(std::string & name) bool VisualTest::directoriesDoNotExist() { - const std::string reference_directory = QDir::toNativeSeparators(QString::fromStdString( - source_directory_path_ + reference_images_path_suffix_)).toStdString(); + const std::string reference_directory = QDir::toNativeSeparators( + QString::fromStdString( + source_directory_path_ + reference_images_path_suffix_)).toStdString(); const std::string test_directory = QDir::toNativeSeparators( QString::fromStdString(build_directory_path_ + test_images_path_suffix_)).toStdString(); struct stat buffer; diff --git a/rviz_visual_testing_framework/src/page_objects/base_page_object.cpp b/rviz_visual_testing_framework/src/page_objects/base_page_object.cpp index 7447e0170..bcb8c3f6e 100644 --- a/rviz_visual_testing_framework/src/page_objects/base_page_object.cpp +++ b/rviz_visual_testing_framework/src/page_objects/base_page_object.cpp @@ -79,7 +79,8 @@ void BasePageObject::setComboBox( const QString & value_to_set, std::vector super_properties) { - executor_->queueAction([this, value_to_set, property_to_change, + executor_->queueAction( + [this, value_to_set, property_to_change, super_properties{std::move(super_properties)}] { auto index_to_change = getValueToChangeFromAllProperties(property_to_change, super_properties); @@ -258,7 +259,8 @@ QString BasePageObject::getDisplayName() const void BasePageObject::collapse() { - executor_->queueAction([this] { + executor_->queueAction( + [this] { int display_index = helpers::findIndex(display_id_, *all_display_ids_vector_); auto relative_display_index = helpers::getDisplaysTreeView()->model()->index( diff --git a/rviz_visual_testing_framework/src/page_objects/page_object_with_window.cpp b/rviz_visual_testing_framework/src/page_objects/page_object_with_window.cpp index 1b70a0e2e..711bc2af6 100644 --- a/rviz_visual_testing_framework/src/page_objects/page_object_with_window.cpp +++ b/rviz_visual_testing_framework/src/page_objects/page_object_with_window.cpp @@ -41,7 +41,8 @@ PageObjectWithWindow::PageObjectWithWindow(int display_category, QString display void PageObjectWithWindow::captureDisplayRenderWindow(std::string image_name) { - executor_->queueAction([this, image_name] { + executor_->queueAction( + [this, image_name] { if (!render_window_) { setRenderWindow(); } diff --git a/rviz_visual_testing_framework/src/visual_test_fixture.cpp b/rviz_visual_testing_framework/src/visual_test_fixture.cpp index d0c8c6f3f..a674a4f99 100644 --- a/rviz_visual_testing_framework/src/visual_test_fixture.cpp +++ b/rviz_visual_testing_framework/src/visual_test_fixture.cpp @@ -56,13 +56,17 @@ void VisualTestFixture::SetUpTestCase() std::string package_share_directory = ament_index_cpp::get_package_share_directory( "rviz_visual_testing_framework"); if (VisualTest::generateReferenceImages()) { - visualizer_app_->loadConfig(QDir::toNativeSeparators( - QString::fromStdString(package_share_directory + - "/config/visual_tests_default_config.rviz"))); + visualizer_app_->loadConfig( + QDir::toNativeSeparators( + QString::fromStdString( + package_share_directory + + "/config/visual_tests_default_config.rviz"))); } else { - visualizer_app_->loadConfig(QDir::toNativeSeparators( - QString::fromStdString(package_share_directory + - "/config/visual_tests_test_image_config.rviz"))); + visualizer_app_->loadConfig( + QDir::toNativeSeparators( + QString::fromStdString( + package_share_directory + + "/config/visual_tests_test_image_config.rviz"))); } } @@ -101,7 +105,8 @@ void VisualTestFixture::setCamLookAt(Ogre::Vector3 camera_look_at_vector) void VisualTestFixture::updateCamWithDelay(Ogre::Vector3 new_pose, Ogre::Vector3 new_look_at) { - executor_->queueAction([this, new_pose, new_look_at] { + executor_->queueAction( + [this, new_pose, new_look_at] { visual_test_->setCamPose(new_pose); visual_test_->setCamLookAt(new_look_at); });