41 #include <QFileDialog> 54 RobotImagePlugin::RobotImagePlugin() :
55 config_widget_(new QWidget()),
59 texture_loaded_(false),
66 p.setColor(QPalette::Background, Qt::white);
70 QPalette p3(
ui_.status->palette());
71 p3.setColor(QPalette::Text, Qt::red);
72 ui_.status->setPalette(p3);
76 QObject::connect(
ui_.browse, SIGNAL(clicked()),
this, SLOT(
SelectFile()));
77 QObject::connect(
ui_.selectframe, SIGNAL(clicked()),
this, SLOT(
SelectFrame()));
78 QObject::connect(
ui_.frame, SIGNAL(editingFinished()),
this, SLOT(
FrameEdited()));
79 QObject::connect(
ui_.width, SIGNAL(valueChanged(
double)),
this, SLOT(
WidthChanged(
double)));
80 QObject::connect(
ui_.height, SIGNAL(valueChanged(
double)),
this, SLOT(
HeightChanged(
double)));
93 dialog.setFileMode(QFileDialog::ExistingFile);
94 dialog.setNameFilter(tr(
"PNG Image Files (*.png)"));
98 if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
100 ui_.image->setText(dialog.selectedFiles().first());
101 filename_ = dialog.selectedFiles().first().toStdString();
111 ui_.frame->setText(QString::fromStdString(frame));
131 if(
ui_.ratio_equal->isChecked()){
134 else if(
ui_.ratio_original->isChecked()){
151 ui_.height->setEnabled(
false);
160 ui_.height->setEnabled(
true);
169 ui_.height->setEnabled(
false);
215 glColor3f(1.0
f, 1.0
f, 1.0
f);
216 glEnable(GL_TEXTURE_2D);
217 glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(
texture_id_));
228 glDisable(GL_TEXTURE_2D);
265 glDeleteTextures(1, &ids[0]);
271 int width =
image_.width();
272 int height =
image_.height();
275 float max_dim = std::max(width, height);
276 dimension_ =
static_cast<int>(std::pow(2, std::ceil(std::log(max_dim) / std::log(2.0
f))));
286 glGenTextures(1, &ids[0]);
289 glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(
texture_id_));
292 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
293 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
295 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
296 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
299 if(
ui_.ratio_original->isChecked() )
309 catch (
const std::exception& e)
311 PrintError(
"Failed to load image. Exception occured.");
320 ui_.frame->setText(source_frame_.c_str());
326 ui_.image->setText(filename_.c_str());
332 ui_.width->setValue(width_);
338 ui_.height->setValue(height_);
344 node[
"ratio"] >> value;
347 ui_.ratio_equal->setChecked(
true);
349 else if(value ==
"custom")
351 ui_.ratio_custom->setChecked(
true);
353 else if(value ==
"original")
355 ui_.ratio_original->setChecked(
true);
366 emitter << YAML::Key <<
"frame" << YAML::Value <<
ui_.frame->text().toStdString();
367 emitter << YAML::Key <<
"image" << YAML::Value <<
ui_.image->text().toStdString();
368 emitter << YAML::Key <<
"width" << YAML::Value <<
width_;
369 emitter << YAML::Key <<
"height" << YAML::Value <<
height_;
370 if(
ui_.ratio_custom->isChecked())
372 emitter << YAML::Key <<
"ratio" << YAML::Value <<
"custom";
374 else if(
ui_.ratio_equal->isChecked())
376 emitter << YAML::Key <<
"ratio" << YAML::Value <<
"equal";
378 else if(
ui_.ratio_original->isChecked())
380 emitter << YAML::Key <<
"ratio" << YAML::Value <<
"original";
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
void PrintWarning(const std::string &message)
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
void PrintError(const std::string &message)
void RatioOriginalToggled(bool toggled)
void HeightChanged(double value)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
QWidget * GetConfigWidget(QWidget *parent)
std::string target_frame_
void PrintInfo(const std::string &message)
tf::Point bottom_left_transformed_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Draw(double x, double y, double scale)
virtual ~RobotImagePlugin()
std::string source_frame_
tf::Point top_left_transformed_
void RatioEqualToggled(bool toggled)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
void RatioCustomToggled(bool toggled)
tf::Point bottom_right_transformed_
bool Initialize(QGLWidget *canvas)
tf::Point top_right_transformed_
boost::shared_ptr< tf::TransformListener > tf_
void LoadConfig(const YAML::Node &node, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Ui::robot_image_config ui_
void WidthChanged(double value)