31 #include <opencv2/core/core.hpp> 50 ui_.color->setColor(Qt::green);
54 p.setColor(QPalette::Background, Qt::white);
58 QPalette p3(
ui_.status->palette());
59 p3.setColor(QPalette::Text, Qt::red);
60 ui_.status->setPalette(p3);
62 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this,
64 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this,
66 QObject::connect(
ui_.positiontolerance, SIGNAL(valueChanged(
double)),
this,
68 QObject::connect(
ui_.buffersize, SIGNAL(valueChanged(
int)),
this,
70 QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)),
this,
72 QObject::connect(
ui_.static_arrow_sizes, SIGNAL(clicked(
bool)),
74 QObject::connect(
ui_.arrow_size, SIGNAL(valueChanged(
int)),
76 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
78 QObject::connect(
ui_.show_laps, SIGNAL(toggled(
bool)),
this,
80 QObject::connect(
ui_.buttonResetBuffer, SIGNAL(pressed()),
this,
93 if (!topic.
name.empty())
95 ui_.topic->setText(QString::fromStdString(topic.
name));
102 std::string topic =
ui_.topic->text().trimmed().toStdString();
135 stamped_point.
stamp = gps->header.stamp;
139 tf_manager_->LocalXyUtil()->ToLocalXy(gps->latitude, gps->longitude, x, y);
196 node[
"topic"] >> topic;
197 ui_.topic->setText(topic.c_str());
203 node[
"color"] >> color;
204 QColor qcolor(color.c_str());
206 ui_.color->setColor(qcolor);
209 if (node[
"draw_style"])
211 std::string draw_style;
212 node[
"draw_style"] >> draw_style;
214 if (draw_style ==
"lines")
216 ui_.drawstyle->setCurrentIndex(0);
219 else if (draw_style ==
"points")
221 ui_.drawstyle->setCurrentIndex(1);
224 else if (draw_style ==
"arrows")
226 ui_.drawstyle->setCurrentIndex(2);
231 if (node[
"position_tolerance"])
233 double position_tolerance;
234 node[
"position_tolerance"] >> position_tolerance;
235 ui_.positiontolerance->setValue(position_tolerance);
239 if (node[
"buffer_size"])
242 node[
"buffer_size"] >> buffer_size;
243 ui_.buffersize->setValue(buffer_size);
247 if (node[
"show_laps"])
249 bool show_laps =
false;
250 node[
"show_laps"] >> show_laps;
251 ui_.show_laps->setChecked(show_laps);
255 if (node[
"static_arrow_sizes"])
257 bool static_arrow_sizes = node[
"static_arrow_sizes"].as<
bool>();
258 ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
262 if (node[
"arrow_size"])
264 int arrow_size = node[
"arrow_size"].as<
int>();
265 ui_.arrow_size->setValue(arrow_size);
274 std::string topic =
ui_.topic->text().toStdString();
275 emitter << YAML::Key <<
"topic" << YAML::Value << topic;
277 emitter << YAML::Key <<
"color" << YAML::Value
278 <<
ui_.color->color().name().toStdString();
280 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
281 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
283 emitter << YAML::Key <<
"position_tolerance" <<
286 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
bufferSize();
288 bool show_laps =
ui_.show_laps->isChecked();
289 emitter << YAML::Key <<
"show_laps" << YAML::Value << show_laps;
291 emitter << YAML::Key <<
"static_arrow_sizes" << YAML::Value <<
ui_.static_arrow_sizes->isChecked();
293 emitter << YAML::Key <<
"arrow_size" << YAML::Value <<
ui_.arrow_size->value();
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
double bufferSize() const
virtual void PositionToleranceChanged(double value)
virtual void SetArrowSize(int arrowSize)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual bool DrawPoints(double scale)
double positionTolerance() const
QWidget * GetConfigWidget(QWidget *parent)
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)
void LoadConfig(const YAML::Node &node, const std::string &path)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
bool Initialize(QGLWidget *canvas)
void GPSFixCallback(const gps_common::GPSFixConstPtr &gps)
static Quaternion createQuaternionFromYaw(double yaw)
void Draw(double x, double y, double scale)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
virtual void BufferSizeChanged(int value)
virtual void LapToggled(bool checked)
virtual void SetColor(const QColor &color)
virtual void SetStaticArrowSizes(bool isChecked)
void PrintWarning(const std::string &message)
void PrintInfo(const std::string &message)
void pushPoint(StampedPoint point)
void PrintError(const std::string &message)
virtual void SetDrawStyle(QString style)
swri_transform_util::TransformManagerPtr tf_manager_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::Quaternion orientation