40 #include <Eigen/Geometry>
47 : QWidget(parent), calibration_display_(pdisplay), context_(context)
49 setMinimumSize(695, 460);
51 QVBoxLayout* layout =
new QVBoxLayout();
56 description->setText(QString(
"Configure the position and orientation of your 3D sensors to work with MoveIt"));
59 layout->addWidget(description);
62 QTabWidget* tabs =
new QTabWidget(
this);
63 tab_target_ =
new TargetTabWidget(calibration_display_);
67 tab_context_ =
new ContextTabWidget(calibration_display_);
68 tab_context_->setTFTool(tf_tools_);
69 connect(tab_target_, SIGNAL(cameraInfoChanged(sensor_msgs::CameraInfo)), tab_context_,
70 SLOT(setCameraInfo(sensor_msgs::CameraInfo)));
71 connect(tab_target_, SIGNAL(opticalFrameChanged(
const std::string&)), tab_context_,
72 SLOT(setOpticalFrame(
const std::string&)));
74 tab_control_ =
new ControlTabWidget(calibration_display_);
75 tab_control_->setTFTool(tf_tools_);
76 tab_control_->UpdateSensorMountType(0);
77 connect(tab_context_, SIGNAL(sensorMountTypeChanged(
int)), tab_control_, SLOT(UpdateSensorMountType(
int)));
78 connect(tab_context_, SIGNAL(frameNameChanged(std::map<std::string, std::string>)), tab_control_,
79 SLOT(updateFrameNames(std::map<std::string, std::string>)));
80 connect(tab_control_, SIGNAL(sensorPoseUpdate(
double,
double,
double,
double,
double,
double)), tab_context_,
81 SLOT(updateCameraPose(
double,
double,
double,
double,
double,
double)));
83 tabs->addTab(tab_target_,
"Target");
84 tabs->addTab(tab_context_,
"Context");
85 tabs->addTab(tab_control_,
"Calibrate");
86 layout->addWidget(tabs);