42 #include <opencv2/core/core.hpp> 57 OdometryPlugin::OdometryPlugin() : config_widget_(new QWidget())
61 ui_.color->setColor(Qt::green);
65 p.setColor(QPalette::Background, Qt::white);
69 QPalette p3(
ui_.status->palette());
70 p3.setColor(QPalette::Text, Qt::red);
71 ui_.status->setPalette(p3);
73 QObject::connect(
ui_.show_timestamps, SIGNAL(valueChanged(
int)),
this,
75 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this,
77 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this,
79 QObject::connect(
ui_.positiontolerance, SIGNAL(valueChanged(
double)),
this,
81 QObject::connect(
ui_.buffersize, SIGNAL(valueChanged(
int)),
this,
83 QObject::connect(
ui_.drawstyle, SIGNAL(activated(QString)),
this,
85 QObject::connect(
ui_.static_arrow_sizes, SIGNAL(clicked(
bool)),
87 QObject::connect(
ui_.arrow_size, SIGNAL(valueChanged(
int)),
89 connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
102 if (!topic.
name.empty())
104 ui_.topic->setText(QString::fromStdString(topic.
name));
111 std::string topic =
ui_.topic->text().trimmed().toStdString();
133 const nav_msgs::OdometryConstPtr odometry)
146 stamped_point.
stamp = odometry->header.stamp;
150 odometry->pose.pose.position.y,
151 odometry->pose.pose.position.z);
154 odometry->pose.pose.orientation.x,
155 odometry->pose.pose.orientation.y,
156 odometry->pose.pose.orientation.z,
157 odometry->pose.pose.orientation.w);
163 points_.push_back(stamped_point);
183 if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000)
185 cv::Mat cov_matrix_3d(3, 3, CV_32FC1);
186 for (int32_t r = 0; r < 3; r++)
188 for (int32_t c = 0; c < 3; c++)
190 cov_matrix_3d.at<
float>(r, c) = tf_cov[r][c];
194 cv::Mat cov_matrix_2d =
197 if (!cov_matrix_2d.empty())
206 ROS_ERROR(
"Failed to project x, y, z covariance to xy-plane.");
244 if (
ui_.show_covariance->isChecked())
258 int interval =
ui_.show_timestamps->value();
264 QTransform
tf = painter->worldTransform();
265 QFont font(
"Helvetica", 10);
266 painter->setFont(font);
268 painter->resetTransform();
271 QPen pen(QBrush(
ui_.color->color()), 1);
272 painter->setPen(pen);
274 std::list<StampedPoint>::iterator it =
points_.begin();
276 for (; it !=
points_.end(); ++it)
278 if (it->transformed && counter % interval == 0)
280 QPointF point = tf.map(QPointF(it->transformed_point.getX(),
281 it->transformed_point.getY()));
283 time.setNum(it->stamp.toSec(),
'g', 12);
284 painter->drawText(point, time);
300 glBegin(GL_LINE_STRIP);
316 const std::string& path)
321 node[
"topic"] >> topic;
322 ui_.topic->setText(topic.c_str());
328 node[
"color"] >> color;
333 if (node[
"draw_style"])
335 std::string draw_style;
336 node[
"draw_style"] >> draw_style;
338 if (draw_style ==
"lines")
341 ui_.drawstyle->setCurrentIndex(0);
343 else if (draw_style ==
"points")
346 ui_.drawstyle->setCurrentIndex(1);
348 else if (draw_style ==
"arrows")
351 ui_.drawstyle->setCurrentIndex(2);
355 if (node[
"position_tolerance"])
358 ui_.positiontolerance->setValue(position_tolerance_);
361 if (node[
"buffer_size"])
364 ui_.buffersize->setValue(buffer_size_);
367 if (node[
"show_covariance"])
369 bool show_covariance =
false;
370 node[
"show_covariance"] >> show_covariance;
371 ui_.show_covariance->setChecked(show_covariance);
373 if (node[
"show_laps"])
375 bool show_laps =
false;
376 node[
"show_laps"] >> show_laps;
377 ui_.show_laps->setChecked(show_laps);
380 if (node[
"static_arrow_sizes"])
382 bool static_arrow_sizes = node[
"static_arrow_sizes"].as<
bool>();
383 ui_.static_arrow_sizes->setChecked(static_arrow_sizes);
387 if (node[
"arrow_size"])
389 ui_.arrow_size->setValue(node[
"arrow_size"].as<int>());
392 if (node[
"show_timestamps"])
394 ui_.show_timestamps->setValue(node[
"show_timestamps"].as<int>());
401 const std::string& path)
403 std::string topic =
ui_.topic->text().toStdString();
404 emitter << YAML::Key <<
"topic" << YAML::Value << topic;
406 std::string color =
ui_.color->color().name().toStdString();
407 emitter << YAML::Key <<
"color" << YAML::Value << color;
409 std::string draw_style =
ui_.drawstyle->currentText().toStdString();
410 emitter << YAML::Key <<
"draw_style" << YAML::Value << draw_style;
412 emitter << YAML::Key <<
"position_tolerance" <<
416 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
buffer_size_;
420 emitter << YAML::Key <<
"buffer_size" << YAML::Value <<
buffer_holder_;
422 bool show_laps =
ui_.show_laps->isChecked();
423 emitter << YAML::Key <<
"show_laps" << YAML::Value << show_laps;
425 bool show_covariance =
ui_.show_covariance->isChecked();
426 emitter << YAML::Key <<
"show_covariance" << YAML::Value << show_covariance;
428 emitter << YAML::Key <<
"static_arrow_sizes" << YAML::Value <<
ui_.static_arrow_sizes->isChecked();
430 emitter << YAML::Key <<
"arrow_size" << YAML::Value <<
ui_.arrow_size->value();
432 emitter << YAML::Key <<
"show_timestamps" << YAML::Value <<
ui_.show_timestamps->value();
bool Initialize(QGLWidget *canvas)
std::vector< tf::Point > cov_points
cv::Mat ProjectEllipsoid(const cv::Mat &ellipsiod)
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void Draw(double x, double y, double scale)
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 odometry_sub_
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)
void PrintError(const std::string &message)
void odometryCallback(const nav_msgs::OdometryConstPtr odometry)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Paint(QPainter *painter, double x, double y, double scale)
QWidget * GetConfigWidget(QWidget *parent)
void PrintWarning(const std::string &message)
double position_tolerance_
std::vector< tf::Vector3 > GetEllipsePoints(const cv::Mat &ellipse, const tf::Vector3 ¢er, double scale, int32_t num_points)
virtual void BufferSizeChanged(int value)
virtual void SetColor(const QColor &color)
virtual void SetStaticArrowSizes(bool isChecked)
std::vector< tf::Point > transformed_cov_points
void PrintInfo(const std::string &message)
virtual void SetDrawStyle(QString style)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
tf::Quaternion orientation
void LoadConfig(const YAML::Node &node, const std::string &path)
virtual ~OdometryPlugin()
std::list< StampedPoint > points_