34 #include <QMouseEvent> 35 #include <QTextStream> 37 #if QT_VERSION >= 0x050000 38 #include <QGuiApplication> 40 #include <QApplication> 61 : config_widget_(new QWidget()),
67 QObject::connect(
ui_.selectframe, SIGNAL(clicked()),
69 QObject::connect(
ui_.frame, SIGNAL(editingFinished()),
71 QObject::connect(
ui_.copyCheckBox, SIGNAL(stateChanged(
int)),
73 QObject::connect(
ui_.clearListButton, SIGNAL(clicked()),
76 #if QT_VERSION >= 0x050000 77 ui_.coordTextEdit->setPlaceholderText(tr(
"Click on the map; coordinates appear here"));
111 ROS_DEBUG(
"Ignoring mouse event, since coordinate picker plugin is hidden");
115 switch (event->type())
117 case QEvent::MouseButtonPress:
119 case QEvent::MouseButtonRelease:
121 case QEvent::MouseMove:
130 #if QT_VERSION >= 0x050000 131 QPointF point =
event->localPos();
133 QPointF point =
event->posF();
135 ROS_DEBUG(
"Map point: %f %f", point.x(), point.y());
138 std::string frame =
ui_.frame->text().toStdString();
151 ROS_DEBUG(
"Transforming from fixed frame '%s' to (plugin) target frame '%s'",
155 ROS_DEBUG(
"Point in fixed frame: %f %f", transformed.x(), transformed.y());
156 tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
157 position = transform * position;
158 point.setX(position.x());
159 point.setY(position.y());
166 QTextStream(&warning) <<
"No available transform from '" << QString::fromStdString(
target_frame_) <<
"' to '" << QString::fromStdString(frame) <<
"'";
172 ROS_DEBUG(
"Transformed point in frame '%s': %f %f", frame.c_str(), point.x(), point.y());
174 QTextStream stream(&new_point);
177 stream.setRealNumberPrecision(9);
181 stream.setRealNumberPrecision(4);
183 stream << point.x() <<
", " << point.y();
187 #if QT_VERSION >= 0x050000 188 QClipboard* clipboard = QGuiApplication::clipboard();
190 QClipboard* clipboard = QApplication::clipboard();
192 clipboard->setText(new_point);
195 stream <<
" (" << QString::fromStdString(frame) <<
")\n";
197 ui_.coordTextEdit->setPlainText(
ui_.coordTextEdit->toPlainText().prepend(new_point));
220 ui_.frame->setText(QString::fromStdString(frame));
227 ROS_INFO(
"Setting target frame to %s",
ui_.frame->text().toStdString().c_str());
237 case Qt::PartiallyChecked:
247 ui_.coordTextEdit->setPlainText(QString());
259 node[
"frame"] >> frame;
260 ui_.frame->setText(QString::fromStdString(frame));
266 node[
"copy"] >> copy;
269 ui_.copyCheckBox->setCheckState(Qt::Checked);
273 ui_.copyCheckBox->setCheckState(Qt::Unchecked);
280 std::string frame =
ui_.frame->text().toStdString();
281 emitter << YAML::Key <<
"frame" << YAML::Value << frame;
283 bool copy_on_click =
ui_.copyCheckBox->isChecked();
284 emitter << YAML::Key <<
"copy" << YAML::Value << copy_on_click;
bool Initialize(QGLWidget *canvas)
bool handleMousePress(QMouseEvent *)
bool handleMouseRelease(QMouseEvent *)
QPointF MapGlCoordToFixedFrame(const QPointF &point)
QWidget * GetConfigWidget(QWidget *parent)
virtual ~CoordinatePickerPlugin()
void PrintInfo(const std::string &message)
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_
bool eventFilter(QObject *object, QEvent *event)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void PrintError(const std::string &message)
void PrintWarning(const std::string &message)
void Draw(double x, double y, double scale)
void LoadConfig(const YAML::Node &node, const std::string &path)
bool handleMouseMove(QMouseEvent *)
void transform(marti_nav_msgs::Path &path, const swri_transform_util::Transform &transform, const std::string &target_frame)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
boost::shared_ptr< tf::TransformListener > tf_
void ToggleCopyOnClick(int state)
swri_transform_util::TransformManagerPtr tf_manager_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Ui::coordinate_picker_config ui_
mapviz::MapCanvas * map_canvas_