36 #include <std_msgs/Float32.h>
37 #include <std_msgs/Float64.h>
38 #include <marti_common_msgs/Float32Stamped.h>
39 #include <marti_common_msgs/Float64Stamped.h>
40 #include <marti_sensor_msgs/Velocity.h>
42 #include <QFontDialog>
58 config_widget_(new QWidget()),
70 p.setColor(QPalette::Background, Qt::white);
74 QPalette p3(
ui_.status->palette());
75 p3.setColor(QPalette::Text, Qt::red);
76 ui_.status->setPalette(p3);
78 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this, SLOT(
SelectTopic()));
79 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this, SLOT(
TopicEdited()));
80 QObject::connect(
ui_.anchor, SIGNAL(activated(QString)),
this, SLOT(
SetAnchor(QString)));
81 QObject::connect(
ui_.units, SIGNAL(activated(QString)),
this, SLOT(
SetUnits(QString)));
82 QObject::connect(
ui_.offsetx, SIGNAL(valueChanged(
int)),
this, SLOT(
SetOffsetX(
int)));
83 QObject::connect(
ui_.offsety, SIGNAL(valueChanged(
int)),
this, SLOT(
SetOffsetY(
int)));
84 QObject::connect(
ui_.font_button, SIGNAL(clicked()),
this, SLOT(
SelectFont()));
85 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor &)),
this, SLOT(
SelectColor()));
86 QObject::connect(
ui_.postfix, SIGNAL(editingFinished()),
this, SLOT(
PostfixEdited()));
88 font_.setFamily(tr(
"Helvetica"));
90 ui_.font_button->setText(
font_.family());
115 painter->resetTransform();
116 painter->setFont(
font_);
127 QPen invisPen(QBrush(Qt::transparent), 1);
128 painter->setPen(invisPen);
132 QPen pen(QBrush(
color_), 1);
133 painter->setPen(pen);
153 y_offset =
static_cast<int>((float)(
offset_y_ *
canvas_->height()) / 100.0);
156 int right =
static_cast<int>((float)
canvas_->width() -
message_.size().width()) - x_offset;
157 int bottom =
static_cast<int>((float)
canvas_->height() -
message_.size().height()) - y_offset;
158 int yCenter =
static_cast<int>((float)
canvas_->height() / 2.0 -
message_.size().height()/2.0);
159 int xCenter =
static_cast<int>((float)
canvas_->width() / 2.0 -
message_.size().width()/2.0);
166 ulPoint.setX(x_offset);
167 ulPoint.setY(y_offset);
170 ulPoint.setX(xCenter);
171 ulPoint.setY(y_offset);
175 ulPoint.setY(y_offset);
178 ulPoint.setX(x_offset);
179 ulPoint.setY(yCenter);
182 ulPoint.setX(xCenter);
183 ulPoint.setY(yCenter);
187 ulPoint.setY(yCenter);
190 ulPoint.setX(x_offset);
191 ulPoint.setY(bottom);
194 ulPoint.setX(xCenter);
195 ulPoint.setY(bottom);
199 ulPoint.setY(bottom);
202 painter->drawStaticText(ulPoint,
message_);
209 ui_.topic->setText(QString(node[
TOPIC_KEY].as<std::string>().c_str()));
215 font_.fromString(QString(node[
FONT_KEY].as<std::string>().c_str()));
217 ui_.font_button->setText(
font_.family());
223 ui_.color->setColor(QColor(
color_.name().toStdString().c_str()));
228 std::string anchor = node[
ANCHOR_KEY].as<std::string>();
229 ui_.anchor->setCurrentIndex(
ui_.anchor->findText(anchor.c_str()));
235 std::string units = node[
UNITS_KEY].as<std::string>();
236 ui_.units->setCurrentIndex(
ui_.units->findText(units.c_str()));
261 emitter << YAML::Key <<
FONT_KEY << YAML::Value <<
font_.toString().toStdString();
262 emitter << YAML::Key <<
COLOR_KEY << YAML::Value <<
color_.name().toStdString();
263 emitter << YAML::Key <<
TOPIC_KEY << YAML::Value <<
ui_.topic->text().toStdString();
311 ui_.font_button->setText(
font_.family());
317 std::vector<std::string> topics;
318 topics.push_back(
"std_msgs/Float32");
319 topics.push_back(
"std_msgs/Float64");
320 topics.push_back(
"marti_common_msgs/Float32Stamped");
321 topics.push_back(
"marti_common_msgs/Float64Stamped");
322 topics.push_back(
"marti_sensor_msgs/Velocity");
325 if (!topic.
name.empty())
327 ui_.topic->setText(QString::fromStdString(topic.
name));
334 std::string topic =
ui_.topic->text().trimmed().toStdString();
355 if (anchor ==
"top left")
359 else if (anchor ==
"top center")
363 else if (anchor ==
"top right")
367 else if (anchor ==
"center left")
371 else if (anchor ==
"center")
375 else if (anchor ==
"center right")
379 else if (anchor ==
"bottom left")
383 else if (anchor ==
"bottom center")
387 else if (anchor ==
"bottom right")
395 if (units ==
"pixels")
399 else if (units ==
"percent")
415 template <
class T,
class M>
418 return msg->getDataType() == ros::message_traits::datatype<T>();
424 if (is_instance<std_msgs::Float32>(
msg))
426 value =
msg->instantiate<std_msgs::Float32>()->
data;
428 if (is_instance<std_msgs::Float64>(
msg))
430 value =
msg->instantiate<std_msgs::Float64>()->
data;
432 else if (is_instance<marti_common_msgs::Float32Stamped>(
msg))
434 value =
msg->instantiate<marti_common_msgs::Float32Stamped>()->value;
436 else if (is_instance<marti_common_msgs::Float64Stamped>(
msg))
438 value =
msg->instantiate<marti_common_msgs::Float64Stamped>()->value;
440 else if (is_instance<marti_sensor_msgs::Velocity>(
msg))
442 value =
msg->instantiate<marti_sensor_msgs::Velocity>()->velocity;
445 std::string str = std::to_string(value);
447 message_.setText(QString(str.c_str()));
458 std::string anchor_string =
"top left";
462 anchor_string =
"top left";
466 anchor_string =
"top center";
470 anchor_string =
"top right";
474 anchor_string =
"center left";
476 else if (anchor ==
CENTER)
478 anchor_string =
"center";
482 anchor_string =
"center right";
486 anchor_string =
"bottom left";
490 anchor_string =
"bottom center";
494 anchor_string =
"bottom right";
497 return anchor_string;
502 std::string units_string =
"pixels";
506 units_string =
"pixels";
510 units_string =
"percent";