39 PoseArrayPlugin::PoseArrayPlugin() : config_widget_(new QWidget())
43 ui_.color->setColor(Qt::green);
47 p.setColor(QPalette::Background, Qt::white);
51 QPalette p3(
ui_.status->palette());
52 p3.setColor(QPalette::Text, Qt::red);
53 ui_.status->setPalette(p3);
55 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this,
57 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this,
59 QObject::connect(
ui_.positiontolerance, SIGNAL(valueChanged(
double)),
this,
61 QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)),
this,
63 QObject::connect(
ui_.static_arrow_sizes, SIGNAL(clicked(
bool)),
65 QObject::connect(
ui_.arrow_size, SIGNAL(valueChanged(
int)),
67 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
80 if (!topic.
name.empty())
82 ui_.topic->setText(QString::fromStdString(topic.
name));
89 std::string topic =
ui_.topic->text().trimmed().toStdString();
120 for (
unsigned int i=0 ; i < msg->poses.size(); i++)
122 stamped_point.
stamp = msg->header.stamp;
124 geometry_msgs::Pose pose = msg->poses[i];
183 node[
"topic"] >> topic;
184 ui_.topic->setText(topic.c_str());
190 node[
"color"] >> color;
191 QColor qcolor(color.c_str());
193 ui_.color->setColor(qcolor);
196 if (node[
"draw_style"])
198 std::string draw_style;
199 node[
"draw_style"] >> draw_style;
201 if (draw_style ==
"arrows")
203 ui_.drawstyle->setCurrentIndex(0);
206 else if (draw_style ==
"points")
208 ui_.drawstyle->setCurrentIndex(1);
213 if (node[
"position_tolerance"])
215 double position_tolerance;
216 node[
"position_tolerance"] >> position_tolerance;
217 ui_.positiontolerance->setValue(position_tolerance);
221 if (node[
"static_arrow_sizes"])
223 bool static_arrow_sizes = node[
"static_arrow_sizes"].as<
bool>();
224 ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
228 if (node[
"arrow_size"])
230 int arrow_size = node[
"arrow_size"].as<
int>();
231 ui_.arrow_size->setValue(arrow_size);
240 std::string topic =
ui_.topic->text().toStdString();
241 emitter << YAML::Key <<
"topic" << YAML::Value << topic;
243 emitter << YAML::Key <<
"color" << YAML::Value
244 <<
ui_.color->color().name().toStdString();
246 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
247 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
249 emitter << YAML::Key <<
"position_tolerance" <<
252 emitter << YAML::Key <<
"static_arrow_sizes" << YAML::Value <<
ui_.static_arrow_sizes->isChecked();
254 emitter << YAML::Key <<
"arrow_size" << YAML::Value <<
ui_.arrow_size->value();
void LoadConfig(const YAML::Node &node, const std::string &path)
double positionTolerance() const
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
QWidget * GetConfigWidget(QWidget *parent)
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())
ros::Subscriber pose_sub_
virtual bool DrawPoints(double scale)
bool Initialize(QGLWidget *canvas)
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)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void Draw(double x, double y, double scale)
Ui::pose_array_config ui_
virtual void SetColor(const QColor &color)
virtual void SetStaticArrowSizes(bool isChecked)
virtual ~PoseArrayPlugin()
void PrintInfo(const std::string &message)
void PoseArrayCallback(const geometry_msgs::PoseArrayConstPtr &msg)
void pushPoint(StampedPoint point)
virtual void SetDrawStyle(QString style)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::Quaternion orientation
void PrintWarning(const std::string &message)
void PrintError(const std::string &message)