Class MultiSensorCalibrationGui
Defined in File MultiSensorCalibrationGui.h
Inheritance Relationships
Base Type
public multisensor_calibration::GuiBase
(Class GuiBase)
Class Documentation
-
class MultiSensorCalibrationGui : public multisensor_calibration::GuiBase
GUI for the multi-sensor-calibration.
This subclasses the GuiBase and will first instantiate the CalibrationConfigDialog and then instantiate the appropriate calibration according to the values given in the calibration configurator.
Public Functions
-
MultiSensorCalibrationGui(const std::string &iAppTitle, const std::string &iGuiSubNamespace)
Default constructor.
- Parameters:
iAppTitle – [in] Application title.
iGuiSubNamespace – [in] Sub namespace of the gui.
-
virtual ~MultiSensorCalibrationGui()
Destructor.
Method to call the initialization routine. At the end of the routine the spin timer is started to start the ROS spin loop.
Protected Attributes
-
std::shared_ptr<CalibrationConfigDialog> pCalibConfigDialog_
Pointer to object of CalibrationConfigDialog.
-
std::shared_ptr<CalibrationGuiBase> pCalibrationGui_
Pointer to object of calibration gui.
-
std::shared_ptr<CalibrationBase> pCalibration_
Pointer to object of calibration.
-
std::thread calibrationThread_
-
std::shared_ptr<GuidanceBase> pGuidance_
Pointer to object of guidance.
-
std::thread guidanceThread_
-
rclcpp::NodeOptions nodeOptions_
Node options.
-
MultiSensorCalibrationGui(const std::string &iAppTitle, const std::string &iGuiSubNamespace)