40 #include <QMouseEvent> 43 #include <QStaticText> 45 #include <opencv2/core/core.hpp> 53 #include <marti_nav_msgs/PlanRoute.h> 59 namespace mnm = marti_nav_msgs;
65 PlanRoutePlugin::PlanRoutePlugin() :
66 config_widget_(new QWidget()),
68 failed_service_(false),
70 is_mouse_down_(false),
71 max_ms_(Q_INT64_C(500)),
76 ui_.color->setColor(Qt::green);
79 p.setColor(QPalette::Background, Qt::white);
82 QPalette p3(
ui_.status->palette());
83 p3.setColor(QPalette::Text, Qt::red);
84 ui_.status->setPalette(p3);
85 QObject::connect(
ui_.service, SIGNAL(editingFinished()),
this,
87 QObject::connect(
ui_.publish, SIGNAL(clicked()),
this,
89 QObject::connect(
ui_.clear, SIGNAL(clicked()),
this,
119 bool start_from_vehicle =
ui_.start_from_vehicle->isChecked();
120 if (
waypoints_.size() + start_from_vehicle < 2)
125 std::string service =
ui_.service->text().toStdString();
128 mnm::PlanRoute plan_route;
129 plan_route.request.header.frame_id = stu::_wgs84_frame;
131 plan_route.request.plan_from_vehicle =
static_cast<unsigned char>(start_from_vehicle);
134 if (client.
call(plan_route))
136 if (plan_route.response.success)
138 route_preview_ = boost::make_shared<sru::Route>(plan_route.response.route);
200 switch (event->type())
202 case QEvent::MouseButtonPress:
204 case QEvent::MouseButtonRelease:
206 case QEvent::MouseMove:
216 int closest_point = 0;
217 double closest_distance = std::numeric_limits<double>::max();
219 QPointF point =
event->localPos();
223 for (
size_t i = 0; i <
waypoints_.size(); i++)
229 waypoint = transform * waypoint;
233 double distance = QLineF(transformed, point).length();
235 if (distance < closest_distance)
237 closest_distance = distance;
238 closest_point =
static_cast<int>(i);
243 if (event->button() == Qt::LeftButton)
245 if (closest_distance < 15)
258 else if (event->button() == Qt::RightButton)
260 if (closest_distance < 15)
275 QPointF point =
event->localPos();
280 tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
281 position = transform * position;
301 QPointF point =
event->localPos();
307 tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
310 position = transform * position;
312 geometry_msgs::Pose pose;
313 pose.position.
x = position.x();
314 pose.position.y = position.y();
329 QPointF point =
event->localPos();
334 tf::Vector3 position(transformed.x(), transformed.y(), 0.0);
335 position = transform * position;
359 const QColor color =
ui_.color->color();
360 glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0);
361 glBegin(GL_LINE_STRIP);
363 for (
size_t i = 0; i < route.
points.size(); i++)
365 glVertex2d(route.
points[i].position().x(), route.
points[i].position().y());
377 glColor4f(0.0, 1.0, 1.0, 1.0);
380 for (
size_t i = 0; i <
waypoints_.size(); i++)
383 point = transform * point;
384 glVertex2d(point.x(), point.y());
397 painter->resetTransform();
399 QPen pen(QBrush(QColor(Qt::darkCyan).darker()), 1);
400 painter->setPen(pen);
401 painter->setFont(QFont(
"DejaVu Sans Mono", 7));
406 for (
size_t i = 0; i <
waypoints_.size(); i++)
409 point = transform * point;
411 QPointF corner(gl_point.x() - 20, gl_point.y() - 20);
412 QRectF rect(corner, QSizeF(40, 40));
413 painter->drawText(rect, Qt::AlignHCenter | Qt::AlignVCenter, QString::fromStdString(boost::lexical_cast<std::string>(i + 1)));
422 if (node[
"route_topic"])
424 std::string route_topic;
425 node[
"route_topic"] >> route_topic;
426 ui_.topic->setText(route_topic.c_str());
431 node[
"color"] >> color;
432 ui_.color->setColor(QColor(color.c_str()));
437 node[
"service"] >> service;
438 ui_.service->setText(service.c_str());
440 if (node[
"start_from_vehicle"])
442 bool start_from_vehicle;
443 node[
"start_from_vehicle"] >> start_from_vehicle;
444 ui_.start_from_vehicle->setChecked(start_from_vehicle);
452 std::string route_topic =
ui_.topic->text().toStdString();
453 emitter << YAML::Key <<
"route_topic" << YAML::Value << route_topic;
455 std::string color =
ui_.color->color().name().toStdString();
456 emitter << YAML::Key <<
"color" << YAML::Value << color;
458 std::string service =
ui_.service->text().toStdString();
459 emitter << YAML::Key <<
"service" << YAML::Value << service;
461 bool start_from_vehicle =
ui_.start_from_vehicle->isChecked();
462 emitter << YAML::Key <<
"start_from_vehicle" << YAML::Value << start_from_vehicle;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void Retry(const ros::TimerEvent &e)
QPointF MapGlCoordToFixedFrame(const QPointF &point)
std::vector< geometry_msgs::Pose > waypoints_
swri_transform_util::TransformManager tf_manager_
void publish(const boost::shared_ptr< M > &message) const
void transform(Route &route, const swri_transform_util::Transform &transform, const std::string &target_frame)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void Paint(QPainter *painter, double x, double y, double scale)
bool call(MReq &req, MRes &res)
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)
swri_route_util::RoutePtr route_preview_
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
std::string target_frame_
virtual ~PlanRoutePlugin()
bool handleMousePress(QMouseEvent *)
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
void LoadConfig(const YAML::Node &node, const std::string &path)
void PrintError(const std::string &message)
void PrintInfo(const std::string &message)
void Draw(double x, double y, double scale)
bool eventFilter(QObject *object, QEvent *event)
TFSIMD_FORCE_INLINE const tfScalar & x() const
QPointF FixedFrameToMapGlCoord(const QPointF &point)
bool handleMouseMove(QMouseEvent *)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::Publisher route_pub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Ui::plan_route_config ui_
std::vector< RoutePoint > points
bool Initialize(QGLWidget *canvas)
mapviz::MapCanvas * map_canvas_
void PrintWarning(const std::string &message)
bool handleMouseRelease(QMouseEvent *)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
QWidget * GetConfigWidget(QWidget *parent)