41 #include <QFileDialog> 
   56     config_widget_(new QWidget()),
 
   62     texture_loaded_(false),
 
   69     p.setColor(QPalette::Background, Qt::white);
 
   73     QPalette p3(
ui_.status->palette());
 
   74     p3.setColor(QPalette::Text, Qt::red);
 
   75     ui_.status->setPalette(p3);
 
   79     QObject::connect(
ui_.browse, SIGNAL(clicked()), 
this, SLOT(
SelectFile()));
 
   80     QObject::connect(
ui_.selectframe, SIGNAL(clicked()), 
this, SLOT(
SelectFrame()));
 
   81     QObject::connect(
ui_.frame, SIGNAL(editingFinished()), 
this, SLOT(
FrameEdited()));
 
   82     QObject::connect(
ui_.image, SIGNAL(editingFinished()), 
this, SLOT(
ImageEdited()));
 
   83     QObject::connect(
ui_.width, SIGNAL(valueChanged(
double)), 
this, SLOT(
WidthChanged(
double)));
 
   84     QObject::connect(
ui_.height, SIGNAL(valueChanged(
double)), 
this, SLOT(
HeightChanged(
double)));
 
   85     QObject::connect(
ui_.offset_x, SIGNAL(valueChanged(
double)), 
this, SLOT(
OffsetXChanged(
double)));
 
   86     QObject::connect(
ui_.offset_y, SIGNAL(valueChanged(
double)), 
this, SLOT(
OffsetYChanged(
double)));
 
   87     ui_.offset_x->setMinimum(-99.99); 
 
   88     ui_.offset_y->setMinimum(-99.99);
 
  101     dialog.setFileMode(QFileDialog::ExistingFile);
 
  102     dialog.setNameFilter(tr(
"PNG Image Files (*.png)"));
 
  106     if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1)
 
  108       ui_.image->setText(dialog.selectedFiles().first());
 
  109       filename_ = dialog.selectedFiles().first().toStdString();
 
  119       ui_.frame->setText(QString::fromStdString(frame));
 
  145     if( 
ui_.ratio_equal->isChecked()){
 
  148     else if( 
ui_.ratio_original->isChecked()){
 
  177       ui_.height->setEnabled(
false);
 
  186       ui_.height->setEnabled(
true);
 
  196       ui_.height->setEnabled(
false);
 
  244       glColor3f(1.0
f, 1.0
f, 1.0
f);
 
  245       glEnable(GL_TEXTURE_2D);
 
  246       glBindTexture(GL_TEXTURE_2D, 
static_cast<GLuint
>(
texture_id_));
 
  257       glDisable(GL_TEXTURE_2D);
 
  294         glDeleteTextures(1, &ids[0]);
 
  298       const std::string prefix = 
"$(find ";
 
  299       std::string real_filename;
 
  301       bool has_close = spos != -1 ? 
filename_.find(
')', spos) != -1: 
false;
 
  302       if (spos != -1 && spos + prefix.length() < 
filename_.size() && has_close)
 
  304         std::string 
package = filename_.substr(spos + prefix.length());
 
  305         package = package.substr(0, package.find(")"));
 
  315       if (
image_.load(real_filename.c_str()))
 
  317         int width = 
image_.width();
 
  318         int height = 
image_.height();
 
  321         float max_dim = std::max(width, height);
 
  322         dimension_ = 
static_cast<int>(std::pow(2, std::ceil(std::log(max_dim) / std::log(2.0
f))));
 
  332         glGenTextures(1, &ids[0]);
 
  335         glBindTexture(GL_TEXTURE_2D, 
static_cast<GLuint
>(
texture_id_));
 
  338         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
 
  339         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
 
  341         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
 
  342         glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
 
  345         if( 
ui_.ratio_original->isChecked() )
 
  355     catch (
const std::exception& e)
 
  357       PrintError(
"Failed to load image.  Exception occured.");
 
  368     if (node[
"offset_x"])
 
  374     if (node[
"offset_y"])
 
  401       node[
"ratio"] >> value;
 
  404         ui_.ratio_equal->setChecked(
true);
 
  406       else if(value == 
"custom")
 
  408         ui_.ratio_custom->setChecked(
true);
 
  410       else if(value == 
"original")
 
  412         ui_.ratio_original->setChecked(
true);
 
  423     emitter << YAML::Key << 
"frame" << YAML::Value << 
ui_.frame->text().toStdString();
 
  424     emitter << YAML::Key << 
"image" << YAML::Value << 
ui_.image->text().toStdString();
 
  425     emitter << YAML::Key << 
"width" << YAML::Value << 
width_;
 
  426     emitter << YAML::Key << 
"height" << YAML::Value << 
height_;
 
  427     emitter << YAML::Key << 
"offset_x" << YAML::Value << 
offset_x_;
 
  428     emitter << YAML::Key << 
"offset_y" << YAML::Value << 
offset_y_;
 
  429     if( 
ui_.ratio_custom->isChecked())
 
  431       emitter << YAML::Key << 
"ratio" << YAML::Value << 
"custom";
 
  433     else if( 
ui_.ratio_equal->isChecked())
 
  435       emitter << YAML::Key << 
"ratio" << YAML::Value << 
"equal";
 
  437     else if( 
ui_.ratio_original->isChecked())
 
  439       emitter << YAML::Key << 
"ratio" << YAML::Value << 
"original";