48 GridPlugin::GridPlugin() :
49 config_widget_(new QWidget()),
59 ui_.color->setColor(Qt::red);
63 p.setColor(QPalette::Background, Qt::white);
67 QPalette p3(
ui_.status->palette());
68 p3.setColor(QPalette::Text, Qt::red);
69 ui_.status->setPalette(p3);
71 QObject::connect(
ui_.select_frame, SIGNAL(clicked()),
this, SLOT(
SelectFrame()));
72 QObject::connect(
ui_.frame, SIGNAL(textEdited(
const QString&)),
this, SLOT(
FrameEdited()));
73 QObject::connect(
ui_.alpha, SIGNAL(valueChanged(
double)),
this, SLOT(
SetAlpha(
double)));
74 QObject::connect(
ui_.x, SIGNAL(valueChanged(
double)),
this, SLOT(
SetX(
double)));
75 QObject::connect(
ui_.y, SIGNAL(valueChanged(
double)),
this, SLOT(
SetY(
double)));
76 QObject::connect(
ui_.size, SIGNAL(valueChanged(
double)),
this, SLOT(
SetSize(
double)));
77 QObject::connect(
ui_.rows, SIGNAL(valueChanged(
int)),
this, SLOT(
SetRows(
int)));
78 QObject::connect(
ui_.columns, SIGNAL(valueChanged(
int)),
this, SLOT(
SetColumns(
int)));
79 connect(
ui_.color, SIGNAL(colorEdited(
const QColor &)),
this, SLOT(
DrawIcon()));
96 icon.fill(Qt::transparent);
98 QPainter painter(&icon);
99 painter.setRenderHint(QPainter::Antialiasing,
true);
101 QPen pen(QColor(
ui_.color->color()));
104 pen.setCapStyle(Qt::SquareCap);
107 painter.drawLine(2, 2, 14, 2);
108 painter.drawLine(2, 2, 2, 14);
109 painter.drawLine(14, 2, 14, 14);
110 painter.drawLine(2, 14, 14, 14);
111 painter.drawLine(8, 2, 8, 14);
112 painter.drawLine(2, 8, 14, 8);
163 ui_.frame->setText(QString::fromStdString(frame));
212 QColor color =
ui_.color->color();
215 glColor4d(color.redF(), color.greenF(), color.blueF(),
alpha_);
222 glVertex2d(transformed_left_it->getX(), transformed_left_it->getY());
223 glVertex2d(transformed_right_it->getX(), transformed_right_it->getY());
225 ++transformed_right_it;
232 glVertex2d(transformed_top_it->getX(), transformed_top_it->getY());
233 glVertex2d(transformed_bottom_it->getX(), transformed_bottom_it->getY());
235 ++transformed_bottom_it;
271 for (
int r = 0; r <=
rows_; r++)
300 std::list<tf::Point>::iterator points_it = src.begin();
301 std::list<tf::Point>::iterator transformed_it = dst.begin();
302 for (; points_it != src.end() && transformed_it != dst.end(); ++points_it)
304 (*transformed_it) =
transform_ * (*points_it);
315 node[
"color"] >> color;
316 ui_.color->setColor(QColor(color.c_str()));
322 node[
"frame"] >> frame;
323 ui_.frame->setText(QString::fromStdString(frame));
343 ui_.alpha->setValue(alpha_);
348 node[
"size"] >>
size_;
349 ui_.size->setValue(size_);
354 node[
"rows"] >>
rows_;
355 ui_.rows->setValue(rows_);
361 ui_.columns->setValue(columns_);
369 emitter << YAML::Key <<
"color" << YAML::Value <<
ui_.color->color().name().toStdString();
371 emitter << YAML::Key <<
"alpha" << YAML::Value <<
alpha_;
373 std::string frame =
ui_.frame->text().toStdString();
374 emitter << YAML::Key <<
"frame" << YAML::Value << frame;
376 emitter << YAML::Key <<
"x" << YAML::Value <<
top_left_.
getX();
377 emitter << YAML::Key <<
"y" << YAML::Value <<
top_left_.
getY();
378 emitter << YAML::Key <<
"size" << YAML::Value <<
size_;
379 emitter << YAML::Key <<
"rows" << YAML::Value <<
rows_;
380 emitter << YAML::Key <<
"columns" << YAML::Value <<
columns_;
void LoadConfig(const YAML::Node &node, const std::string &path)
bool Initialize(QGLWidget *canvas)
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
swri_transform_util::Transform transform_
std::list< tf::Point > transformed_left_points_
void Draw(double x, double y, double scale)
TFSIMD_FORCE_INLINE void setX(tfScalar x)
TFSIMD_FORCE_INLINE void setY(tfScalar y)
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)
TFSIMD_FORCE_INLINE const tfScalar & getY() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintError(const std::string &message)
void PrintWarning(const std::string &message)
std::string source_frame_
std::list< tf::Point > right_points_
std::list< tf::Point > transformed_top_points_
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::list< tf::Point > top_points_
void PrintInfo(const std::string &message)
std::list< tf::Point > transformed_bottom_points_
void SetAlpha(double alpha)
std::list< tf::Point > bottom_points_
QWidget * GetConfigWidget(QWidget *parent)
TFSIMD_FORCE_INLINE const tfScalar & getX() const
std::list< tf::Point > transformed_right_points_
boost::shared_ptr< tf::TransformListener > tf_
std::list< tf::Point > left_points_
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void SetColumns(int columns)
void SetSize(double size)