31 #include <opencv2/core/core.hpp> 51 ui_.color->setColor(Qt::green);
55 p.setColor(QPalette::Background, Qt::white);
59 QPalette p3(
ui_.status->palette());
60 p3.setColor(QPalette::Text, Qt::red);
61 ui_.status->setPalette(p3);
63 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this,
65 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this,
67 QObject::connect(
ui_.positiontolerance, SIGNAL(valueChanged(
double)),
this,
69 QObject::connect(
ui_.buffersize, SIGNAL(valueChanged(
int)),
this,
71 QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)),
this,
73 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
75 QObject::connect(
ui_.buttonResetBuffer, SIGNAL(pressed()),
this,
88 if (!topic.
name.empty())
90 ui_.topic->setText(QString::fromStdString(topic.
name));
97 std::string topic =
ui_.topic->text().trimmed().toStdString();
117 const sensor_msgs::NavSatFixConstPtr navsat)
130 stamped_point.
stamp = navsat->header.stamp;
134 tf_manager_->LocalXyUtil()->ToLocalXy(navsat->latitude, navsat->longitude, x, y);
185 node[
"topic"] >> topic;
186 ui_.topic->setText(topic.c_str());
192 node[
"color"] >> color;
193 QColor qcolor(color.c_str());
195 ui_.color->setColor(qcolor);
198 if (node[
"draw_style"])
200 std::string draw_style;
201 node[
"draw_style"] >> draw_style;
203 if (draw_style ==
"lines")
205 ui_.drawstyle->setCurrentIndex(0);
208 else if (draw_style ==
"points")
210 ui_.drawstyle->setCurrentIndex(1);
215 if (node[
"position_tolerance"])
217 double position_tolerance;
218 node[
"position_tolerance"] >> position_tolerance;
219 ui_.positiontolerance->setValue(position_tolerance);
223 if (node[
"buffer_size"])
226 node[
"buffer_size"] >> buffer_size;
227 ui_.buffersize->setValue(buffer_size);
236 std::string topic =
ui_.topic->text().toStdString();
237 emitter << YAML::Key <<
"topic" << YAML::Value << topic;
239 std::string color =
ui_.color->color().name().toStdString();
240 emitter << YAML::Key <<
"color" << YAML::Value << color;
242 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
243 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
245 emitter << YAML::Key <<
"position_tolerance" <<
248 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
bufferSize();
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void PrintInfo(const std::string &message)
double bufferSize() const
virtual void PositionToleranceChanged(double value)
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
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)
ros::Subscriber navsat_sub_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Draw(double x, double y, double scale)
static Quaternion createQuaternionFromYaw(double yaw)
void NavSatFixCallback(const sensor_msgs::NavSatFixConstPtr navsat)
virtual void BufferSizeChanged(int value)
virtual void SetColor(const QColor &color)
void PrintWarning(const std::string &message)
void LoadConfig(const YAML::Node &node, const std::string &path)
bool Initialize(QGLWidget *canvas)
void pushPoint(StampedPoint point)
virtual void SetDrawStyle(QString style)
void PrintError(const std::string &message)
swri_transform_util::TransformManagerPtr tf_manager_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::Quaternion orientation
void SaveConfig(YAML::Emitter &emitter, const std::string &path)