36 #include <boost/algorithm/string.hpp> 44 #define IS_INSTANCE(msg, type) \ 45 (msg->getDataType() == ros::message_traits::datatype<type>()) 48 config_widget_(new QWidget()),
53 ui_.color->setColor(Qt::red);
57 p.setColor(QPalette::Background, Qt::white);
61 QPalette p3(
ui_.status->palette());
62 p3.setColor(QPalette::Text, Qt::red);
63 ui_.status->setPalette(p3);
65 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this, SLOT(
SelectTopic()));
66 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this, SLOT(
TopicEdited()));
67 QObject::connect(
ui_.color, SIGNAL(colorEdited(
const QColor&)),
this,
90 "marti_nav_msgs/TrackedObjectArray",
91 "marti_nav_msgs/ObstacleArray");
93 if (topic.
name.empty())
98 ui_.topic->setText(QString::fromStdString(topic.
name));
104 std::string topic =
ui_.topic->text().trimmed().toStdString();
121 ROS_INFO(
"Subscribing to %s", topic_.c_str());
129 if (
IS_INSTANCE(msg, marti_nav_msgs::TrackedObjectArray))
133 auto objs = msg->instantiate<marti_nav_msgs::TrackedObjectArray>();
134 objects_.reserve(objs->objects.size());
135 for (
const auto& obj: objs->objects)
140 else if (
IS_INSTANCE(msg, marti_nav_msgs::ObstacleArray))
144 auto objs = msg->instantiate<marti_nav_msgs::ObstacleArray>();
145 objects_.reserve(objs->obstacles.size());
146 for (
const auto& obj: objs->obstacles)
153 PrintError(
"Unknown message type: " + msg->getDataType());
169 if (obj.pose.orientation.x ||
170 obj.pose.orientation.y ||
171 obj.pose.orientation.z ||
172 obj.pose.orientation.w)
175 obj.pose.orientation.y,
176 obj.pose.orientation.z,
177 obj.pose.orientation.w);
184 tf::Vector3(obj.pose.position.x,
186 obj.pose.position.z)));
189 data.
stamp = header.stamp;
199 data.
polygon.reserve(obj.polygon.size()+1);
200 for (
auto& point: obj.polygon)
202 tf::Vector3 pt(point.x, point.y, point.z);
204 tf::Vector3 transformed = transform *pt;
205 data.
polygon.push_back({pt, transformed});
226 if (obj.pose.pose.orientation.x ||
227 obj.pose.pose.orientation.y ||
228 obj.pose.pose.orientation.z ||
229 obj.pose.pose.orientation.w)
232 obj.pose.pose.orientation.y,
233 obj.pose.pose.orientation.z,
234 obj.pose.pose.orientation.w);
241 tf::Vector3(obj.pose.pose.position.x,
242 obj.pose.pose.position.y,
243 obj.pose.pose.position.z)));
244 data.
stamp = obj.header.stamp;
246 data.
id = std::to_string(obj.id);
256 data.
polygon.reserve(obj.polygon.size()+1);
257 for (
auto& point: obj.polygon)
259 tf::Vector3 pt(point.x, point.y, point.z);
261 tf::Vector3 transformed = transform *pt;
262 data.
polygon.push_back({pt, transformed});
305 if (!obj.transformed)
310 if (!obj.active && !
ui_.show_inactive->isChecked())
318 glBegin(GL_LINE_STRIP);
320 for (
const auto &point : obj.polygon) {
322 point.transformed_point.getX(),
323 point.transformed_point.getY());
334 if (!
ui_.show_ids->isChecked())
348 QTransform
tf = painter->worldTransform();
349 QFont font(
"Helvetica", 10);
350 painter->setFont(font);
352 painter->resetTransform();
356 if (!obj.transformed)
361 QPen pen(QBrush(QColor::fromRgbF(0, 0, 0, 1)), 1);
362 painter->setPen(pen);
368 auto text = QString::fromStdString(obj.id);
370 QRectF rect(point, QSizeF(10,10));
371 rect = painter->boundingRect(rect, Qt::AlignLeft | Qt::AlignHCenter, text);
372 painter->drawText(rect, text);
385 if (
GetTransform(obj.source_frame, obj.stamp, transform))
387 obj.transformed =
true;
389 for (
auto &point : obj.polygon)
391 point.transformed_point = transform * point.point;
396 obj.transformed =
false;
406 node[
"topic"] >> topic;
407 ui_.topic->setText(boost::trim_copy(topic).c_str());
415 node[
"color"] >> color;
416 QColor qcolor(color.c_str());
418 ui_.color->setColor(qcolor);
421 if (node[
"show_ids"])
424 node[
"show_ids"] >> checked;
425 ui_.show_ids->setChecked( checked );
428 if (node[
"show_inactive"])
431 node[
"show_inactive"] >> checked;
432 ui_.show_inactive->setChecked( checked );
438 emitter << YAML::Key <<
"topic" << YAML::Value << boost::trim_copy(
ui_.topic->text().toStdString());
440 emitter << YAML::Key <<
"color" << YAML::Value
441 <<
ui_.color->color().name().toStdString();
443 emitter << YAML::Key <<
"show_ids" << YAML::Value <<
ui_.show_ids->isChecked();
445 emitter << YAML::Key <<
"show_inactive" << YAML::Value <<
ui_.show_inactive->isChecked();
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void timerEvent(QTimerEvent *)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< ObjectData > objects_
void Draw(double x, double y, double scale)
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
bool Initialize(QGLWidget *canvas)
uint32_t getNumPublishers() const
static void PrintWarningHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Paint(QPainter *painter, double x, double y, double scale)
static void PrintErrorHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void PrintWarning(const std::string &message)
tf::Point transformed_point
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
QWidget * GetConfigWidget(QWidget *parent)
void SetColor(const QColor &color)
std::vector< StampedPoint > polygon
void LoadConfig(const YAML::Node &node, const std::string &path)
void handleObstacle(const marti_nav_msgs::Obstacle &obj, const std_msgs::Header &header)
void handleTrack(const marti_nav_msgs::TrackedObject &obj)
ros::Subscriber object_sub_
void PrintInfo(const std::string &message)
void transform(marti_nav_msgs::Path &path, const swri_transform_util::Transform &transform, const std::string &target_frame)
swri_transform_util::Transform local_transform
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void PrintError(const std::string &message)
#define IS_INSTANCE(msg, type)