31 #include <geometry_msgs/PointStamped.h> 35 #include <boost/shared_ptr.hpp> 44 config_widget_(new QWidget()),
51 connect(
ui_.topic, SIGNAL(textEdited(
const QString&)),
86 ui_.topic->setText(QString(tmp.c_str()));
92 node[
"output_frame"] >> tmp;
93 ui_.outputframe->addItem(QString(tmp.c_str()));
99 emitter << YAML::Key <<
"topic" << YAML::Value <<
ui_.topic->text().toStdString();
100 emitter << YAML::Key <<
"output_frame" << YAML::Value <<
ui_.outputframe->currentText().toStdString();
115 std::string output_frame =
ui_.outputframe->currentText().toStdString();
120 tf::Point tfPoint(transformed.x(), transformed.y(), 0.0);
123 tfPoint = tf * tfPoint;
127 std::stringstream error;
128 error <<
"Unable to find transform from " <<
target_frame_ <<
" to " << output_frame <<
".";
132 transformed.setX(tfPoint.x());
133 transformed.setY(tfPoint.y());
137 stamped->header.frame_id = output_frame;
139 stamped->point.x = transformed.x();
140 stamped->point.y = transformed.y();
141 stamped->point.z = 0.0;
143 std::stringstream ss;
144 ss <<
"Point in " << output_frame.c_str() <<
": " << transformed.x() <<
"," << transformed.y();
153 ss <<
" (but not publishing since plugin is hidden)";
186 std::stringstream ss;
187 ss <<
"Publishing points to topic: " << topic.toStdString().c_str();
190 if (!topic.isEmpty())
198 std::vector<std::string> frames;
199 tf_->getFrameStrings(frames);
201 bool supports_wgs84 =
tf_manager_->SupportsTransform(
210 if (
ui_.outputframe->count() >= 0 &&
211 static_cast<size_t>(
ui_.outputframe->count()) == frames.size())
213 bool changed =
false;
214 for (
size_t i = 0; i < frames.size(); i++)
216 if (frames[i] !=
ui_.outputframe->itemText(static_cast<int>(i)).toStdString())
226 std::string current_output =
ui_.outputframe->currentText().toStdString();
228 ui_.outputframe->clear();
229 for (
size_t i = 0; i < frames.size(); i++)
231 ui_.outputframe->addItem(frames[i].c_str());
234 if (current_output !=
"")
236 int index =
ui_.outputframe->findText(current_output.c_str());
239 ui_.outputframe->addItem(current_output.c_str());
242 index =
ui_.outputframe->findText(current_output.c_str());
243 ui_.outputframe->setCurrentIndex(index);
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
QPointF MapGlCoordToFixedFrame(const QPointF &point)
virtual ~PointClickPublisherPlugin()
virtual void SetNode(const ros::NodeHandle &node)
void pointClicked(const QPointF &point)
QWidget * GetConfigWidget(QWidget *parent)
bool Initialize(QGLWidget *canvas)
ros::Publisher point_publisher_
virtual void SetNode(const ros::NodeHandle &node)
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)
std::string target_frame_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void Draw(double x, double y, double scale)
void LoadConfig(const YAML::Node &node, const std::string &path)
CanvasClickFilter click_filter_
void publish(const boost::shared_ptr< M > &message) const
bool FindValue(const YAML::Node &node, const std::string &name)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void PrintError(const std::string &message)
Ui::point_click_publisher_config ui_
virtual void PrintInfo(const std::string &message)
PointClickPublisherPlugin()
mapviz::MapCanvas * canvas_
virtual void PrintWarning(const std::string &message)
boost::shared_ptr< tf::TransformListener > tf_
void topicChanged(const QString &topic)
swri_transform_util::TransformManagerPtr tf_manager_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)