Class CalibrationGuiBase

Inheritance Relationships

Base Type

Derived Types

Class Documentation

class CalibrationGuiBase : public multisensor_calibration::GuiBase

Base class of all calibration GUIs.

This holds and orchestrate the different UI elements of the calibration gui, i.e. the main window as well as the data view windows.

This also couples the ROS event loop to the Qt event loop. In this, a QTimer is instantiated which periodically triggers the spinning of the ROS loop.

Subclassed by multisensor_calibration::CameraLidarCalibrationGui, multisensor_calibration::CameraReferenceCalibrationGui, multisensor_calibration::LidarLidarCalibrationGui, multisensor_calibration::LidarReferenceCalibrationGui

Public Functions

CalibrationGuiBase(const std::string &iAppTitle, const std::string &iGuiSubNamespace)

Default constructor.

Parameters:
  • iAppTitle[in] Application title.

  • iGuiSubNamespace[in] Sub namespace of the gui.

virtual ~CalibrationGuiBase()

Destructor.

std::string getCalibratorNodeName() const

Get the name of the calibrator node.

virtual bool init(const std::shared_ptr<rclcpp::Executor> &ipExec, const rclcpp::NodeOptions &iNodeOpts = rclcpp::NodeOptions()) override

Method to call the initialization routine.

Parameters:
  • ipExec[in] Pointer to executor.

  • iNodeOpts[in] Options for ros node wihtin gui.

void hideProgressDialog()

Hide progress dialog and mark UI as ready.

void showProgressDialog(const QString &iBusyText)

Show progress dialog and mark UI as busy.

Parameters:

iBusyText[in] Text to display on progress dialog.

Signals

void closed()

Signal emitted when calibration gui is closed.

Protected Functions

virtual void initializeGuiContents()

Method to initialize content of the GUI elements, i.e. connect them to the data publishers.

virtual bool initializeSubscribers(rclcpp::Node *ipNode)

Method to initialize subscribers.

Returns:

True, if all settings are valid. False, otherwise.

virtual void loadVisualizer() = 0

Pure virtual method to load visualizer.

virtual void onCalibrationResultReceived(const CalibrationResult_Message_T::ConstSharedPtr &ipResultMsg)

Callback function handling calibration results messages.

Parameters:

ipResultMsg[in] Calibration result message.

void onLogMessageReceived(const rcl_interfaces::msg::Log::ConstSharedPtr pLogMsg)

Callback function to handle log messages subscribed to by logSubsc_.

virtual bool setupGuiElements()

Method to setup gui elements.

Returns:

False, if not successful. In this case pCalibControlWindow is null.

Protected Attributes

rclcpp::Subscription<rcl_interfaces::msg::Log>::SharedPtr pLogSubsc_

Subscriber to log messages.

rclcpp::Subscription<CalibrationResult_Message_T>::SharedPtr pCalibResultSubsc_

Subscriber to calibration result messages.

std::string calibratorNodeName_

Name of the calibrator node.

std::string guidanceNodeName_

Name of the guidance node.

std::string visualizerNodeName_

Name of the node to fuse the data and visualize calibration.

std::shared_ptr<interf::srv::CalibrationMetaData::Response> pCalibrationMetaData_

Member variable holding calibration meta data.

QTimer calibMetaDataTimer_

QTimer object to trigger service call to get calibration meta data. This needs to be a QTimer, since the event loop runs in Qt.

QRect screenGeometry_

Member rectangle holding the screen geometry. This is initialized at the beginning of setting up the GUI elements.

int titleBarHeight_

Height of titlebar of each window. This is initialized at the beginning of setting up the GUI elements.

std::shared_ptr<CalibrationControlWindow> pCalibControlWindow_

Pointer to object of CalibrationControlWindow.

std::shared_ptr<QProgressDialog> pProgressDialog_

Pointer to object of QProgressDialog.

std::shared_ptr<QProcess> pRqtReconfigureProcess_

Pointer to process of rqt_reconfigure.