52 TfFramePlugin::TfFramePlugin() : config_widget_(new QWidget())
56 ui_.color->setColor(Qt::green);
60 p.setColor(QPalette::Background, Qt::white);
64 QPalette p3(
ui_.status->palette());
65 p3.setColor(QPalette::Text, Qt::red);
66 ui_.status->setPalette(p3);
68 QObject::connect(
ui_.selectframe, SIGNAL(clicked()),
this,
70 QObject::connect(
ui_.frame, SIGNAL(editingFinished()),
this,
72 QObject::connect(
ui_.positiontolerance, SIGNAL(valueChanged(
double)),
this,
74 QObject::connect(
ui_.buffersize, SIGNAL(valueChanged(
int)),
this,
76 QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)),
this,
78 QObject::connect(
ui_.static_arrow_sizes, SIGNAL(clicked(
bool)),
80 QObject::connect(
ui_.arrow_size, SIGNAL(valueChanged(
int)),
82 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
95 ui_.frame->setText(QString::fromStdString(frame));
123 std::pow(stamped_point.
point.
x() -
points_.back().point.x(), 2) +
124 std::pow(stamped_point.
point.
y() -
points_.back().point.y(), 2));
128 points_.push_back(stamped_point);
185 const std::string& path)
190 ui_.frame->setText(source_frame_.c_str());
196 node[
"color"] >> color;
201 if (node[
"draw_style"])
203 std::string draw_style;
204 node[
"draw_style"] >> draw_style;
206 if (draw_style ==
"lines")
209 ui_.drawstyle->setCurrentIndex(0);
211 else if (draw_style ==
"points")
214 ui_.drawstyle->setCurrentIndex(1);
216 else if (draw_style ==
"arrows")
219 ui_.drawstyle->setCurrentIndex(2);
223 if (node[
"position_tolerance"])
226 ui_.positiontolerance->setValue(position_tolerance_);
229 if (node[
"buffer_size"])
232 ui_.buffersize->setValue(buffer_size_);
235 if (node[
"static_arrow_sizes"])
237 bool static_arrow_sizes = node[
"static_arrow_sizes"].as<
bool>();
238 ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
242 if (node[
"arrow_size"])
244 ui_.arrow_size->setValue(node[
"arrow_size"].as<int>());
251 const std::string& path)
253 emitter << YAML::Key <<
"frame" << YAML::Value
254 <<
ui_.frame->text().toStdString();
255 emitter << YAML::Key <<
"color" << YAML::Value
256 <<
ui_.color->color().name().toStdString();
258 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
259 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
261 emitter << YAML::Key <<
"position_tolerance" <<
264 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
buffer_size_;
266 emitter << YAML::Key <<
"static_arrow_sizes" << YAML::Value <<
ui_.static_arrow_sizes->isChecked();
268 emitter << YAML::Key <<
"arrow_size" << YAML::Value <<
ui_.arrow_size->value();
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
void Draw(double x, double y, double scale)
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
virtual void PositionToleranceChanged(double value)
virtual void SetArrowSize(int arrowSize)
void PrintWarning(const std::string &message)
void PrintError(const std::string &message)
virtual bool DrawPoints(double scale)
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)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
std::string target_frame_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
std::string source_frame_
TFSIMD_FORCE_INLINE const tfScalar & x() const
void TimerCallback(const ros::TimerEvent &event)
double position_tolerance_
void LoadConfig(const YAML::Node &node, const std::string &path)
TFSIMD_FORCE_INLINE const tfScalar & y() const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
virtual void BufferSizeChanged(int value)
virtual void SetColor(const QColor &color)
virtual void SetStaticArrowSizes(bool isChecked)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
boost::shared_ptr< tf::TransformListener > tf_
void PrintInfo(const std::string &message)
virtual void SetDrawStyle(QString style)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::Quaternion orientation
bool Initialize(QGLWidget *canvas)
std::list< StampedPoint > points_