38 #include <boost/algorithm/string.hpp> 58 TexturedMarkerPlugin::TexturedMarkerPlugin() :
59 config_widget_(new QWidget()),
60 is_marker_array_(false),
67 p.setColor(QPalette::Background, Qt::white);
71 QPalette p3(
ui_.status->palette());
72 p3.setColor(QPalette::Text, Qt::red);
73 ui_.status->setPalette(p3);
75 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this, SLOT(
SelectTopic()));
76 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this, SLOT(
TopicEdited()));
77 QObject::connect(
ui_.clear, SIGNAL(clicked()),
this, SLOT(
ClearHistory()));
78 QObject::connect(
ui_.alphaSlide, SIGNAL(valueChanged(
int)),
this, SLOT(
SetAlphaLevel(
int)));
82 qRegisterMetaType<marti_visualization_msgs::TexturedMarkerConstPtr>(
"TexturedMarkerConstPtr");
83 qRegisterMetaType<marti_visualization_msgs::TexturedMarkerArrayConstPtr>(
"TexturedMarkerArrayConstPtr");
85 QObject::connect(
this,
86 SIGNAL(
MarkerReceived(
const marti_visualization_msgs::TexturedMarkerConstPtr)),
88 SLOT(
ProcessMarker(
const marti_visualization_msgs::TexturedMarkerConstPtr)));
89 QObject::connect(
this,
90 SIGNAL(
MarkersReceived(
const marti_visualization_msgs::TexturedMarkerArrayConstPtr)),
92 SLOT(
ProcessMarkers(
const marti_visualization_msgs::TexturedMarkerArrayConstPtr)));
101 ROS_DEBUG(
"TexturedMarkerPlugin::ClearHistory()");
109 int max =
ui_.alphaSlide->maximum();
110 int min =
ui_.alphaSlide->minimum();
122 alphaVal_ = (
static_cast<float>(alpha) / max);
130 "marti_visualization_msgs/TexturedMarker",
131 "marti_visualization_msgs/TexturedMarkerArray");
133 if (!topic.
name.empty())
135 ui_.topic->setText(QString::fromStdString(topic.
name));
137 if (topic.
datatype ==
"marti_visualization_msgs/TexturedMarkerArray")
148 std::string topic =
ui_.topic->text().trimmed().toStdString();
193 if (marker.action == marti_visualization_msgs::TexturedMarker::ADD)
196 markerData.
stamp = marker.header.stamp;
199 markerData.
alpha_ = marker.alpha;
223 marker.pose.orientation.x,
224 marker.pose.orientation.y,
225 marker.pose.orientation.z,
226 marker.pose.orientation.w),
228 marker.pose.position.x,
229 marker.pose.position.y,
230 marker.pose.position.z));
232 double right = marker.image.width * marker.resolution / 2.0;
233 double left = -right;
234 double top = marker.image.height * marker.resolution / 2.0;
235 double bottom = -top;
242 top_left = offset * top_left;
243 top_right = offset * top_right;
244 bottom_left = offset * bottom_left;
245 bottom_right = offset * bottom_right;
247 markerData.
quad_.clear();
248 markerData.
quad_.push_back(top_left);
249 markerData.
quad_.push_back(top_right);
250 markerData.
quad_.push_back(bottom_right);
252 markerData.
quad_.push_back(top_left);
253 markerData.
quad_.push_back(bottom_right);
254 markerData.
quad_.push_back(bottom_left);
257 for (
size_t i = 0; i < markerData.
quad_.size(); i++)
262 int32_t max_dimension = std::max(marker.image.height, marker.image.width);
263 int32_t new_size = 1;
264 while (new_size < max_dimension)
265 new_size = new_size << 1;
271 markerData.
encoding_ = marker.image.encoding;
278 ids[0] =
static_cast<GLuint
>(markerData.
texture_id_);
279 glDeleteTextures(1, &ids[0]);
283 glGenTextures(1, &ids[0]);
287 glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(markerData.
texture_id_));
289 glPixelStorei(GL_UNPACK_ALIGNMENT, 1);
312 size_t expected = marker.image.height*marker.image.width*bpp;
313 if (markerData.
texture_.size() > 0 && marker.image.data.size() < expected)
315 ROS_ERROR(
"TexturedMarker image had expected data size %zu but only got %zu. Dropping message.", expected, marker.image.data.size());
319 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
320 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
322 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
323 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
325 glTexEnvf( GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_MODULATE );
327 glBindTexture(GL_TEXTURE_2D, 0);
329 glPixelStorei(GL_UNPACK_ALIGNMENT, 4);
332 glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(markerData.
texture_id_));
336 for (
size_t row = 0; row < marker.image.height; row++)
338 for (
size_t col = 0; col < marker.image.width; col++)
340 size_t src_index = (row * marker.image.width + col) * 4;
341 size_t dst_index = (row * markerData.
texture_size_ + col) * 4;
343 markerData.
texture_[dst_index + 0] = marker.image.data[src_index + 0];
344 markerData.
texture_[dst_index + 1] = marker.image.data[src_index + 1];
345 markerData.
texture_[dst_index + 2] = marker.image.data[src_index + 2];
346 markerData.
texture_[dst_index + 3] = marker.image.data[src_index + 3];
363 for (
size_t row = 0; row < marker.image.height; row++)
365 for (
size_t col = 0; col < marker.image.width; col++)
367 size_t src_index = (row * marker.image.width + col) * 3;
368 size_t dst_index = (row * markerData.
texture_size_ + col) * 3;
370 markerData.
texture_[dst_index + 0] = marker.image.data[src_index + 0];
371 markerData.
texture_[dst_index + 1] = marker.image.data[src_index + 1];
372 markerData.
texture_[dst_index + 2] = marker.image.data[src_index + 2];
389 for (
size_t row = 0; row < marker.image.height; row++)
391 for (
size_t col = 0; col < marker.image.width; col++)
393 size_t src_index = row * marker.image.width + col;
396 markerData.
texture_[dst_index] = marker.image.data[src_index];
412 glBindTexture(GL_TEXTURE_2D, 0);
415 markerData.
texture_y_ =
static_cast<float>(marker.image.height) / static_cast<float>(markerData.
texture_size_);
419 markers_[marker.ns].erase(marker.id);
425 for (
unsigned int i = 0; i < markers->markers.size(); i++)
477 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
480 std::map<int, MarkerData>::iterator markerIter;
481 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
490 glEnable(GL_TEXTURE_2D);
492 glBindTexture(GL_TEXTURE_2D, static_cast<GLuint>(marker.
texture_id_));
494 glBegin(GL_TRIANGLES);
496 glColor4f(1.0
f, 1.0
f, 1.0
f, marker.
alpha_);
511 glBindTexture(GL_TEXTURE_2D, 0);
513 glDisable(GL_TEXTURE_2D);
524 std::map<std::string, std::map<int, MarkerData> >::iterator nsIter;
527 std::map<int, MarkerData>::iterator markerIter;
528 for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter)
531 if (
GetTransform(markerIter->second.source_frame_, markerIter->second.stamp, transform))
533 markerIter->second.transformed_quad_.clear();
534 for (
size_t i = 0; i < markerIter->second.quad_.size(); i++)
536 markerIter->second.transformed_quad_.push_back(transform * markerIter->second.quad_[i]);
548 node[
"topic"] >> topic;
549 ui_.topic->setText(boost::trim_copy(topic).c_str());
552 if (node[
"is_marker_array"])
562 emitter << YAML::Key <<
"topic" << YAML::Value << boost::trim_copy(
ui_.topic->text().toStdString());
563 emitter << YAML::Key <<
"is_marker_array" << YAML::Value <<
is_marker_array_;
bool GetTransform(const ros::Time &stamp, swri_transform_util::Transform &transform, bool use_latest_transforms=true)
std::vector< tf::Vector3 > transformed_quad_
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void MarkersReceived(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
void PrintInfo(const std::string &message)
void MarkerArrayCallback(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
void ProcessMarkers(const marti_visualization_msgs::TexturedMarkerArrayConstPtr markers)
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
void LoadConfig(const YAML::Node &node, const std::string &path)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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)
bool Initialize(QGLWidget *canvas)
std::string target_frame_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintError(const std::string &message)
std::map< std::string, std::map< int, MarkerData > > markers_
void MarkerCallback(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
std::vector< tf::Vector3 > quad_
void PrintWarning(const std::string &message)
void MarkerReceived(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
QWidget * GetConfigWidget(QWidget *parent)
ROSTIME_DECL const Time TIME_MAX
virtual ~TexturedMarkerPlugin()
ros::Subscriber marker_sub_
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
std::vector< uint8_t > texture_
void SetAlphaLevel(int alpha)
std::string source_frame_
void ProcessMarker(const marti_visualization_msgs::TexturedMarkerConstPtr marker)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Ui::textured_marker_config ui_
void Draw(double x, double y, double scale)