40 #include <QMouseEvent>
43 #include <QStaticText>
61 config_widget_(new QWidget()),
63 is_mouse_down_(false),
64 move_base_client_(
"move_base", true),
65 monitoring_action_state_(false)
73 p.setColor(QPalette::Background, Qt::white);
77 ui_.status->setText(
"OK");
78 QPalette p3(
ui_.status->palette());
79 p3.setColor(QPalette::Text, Qt::green);
80 ui_.status->setPalette(p3);
82 QObject::connect(
ui_.pushButtonInitialPose, SIGNAL(toggled(
bool)),
85 QObject::connect(
ui_.pushButtonGoalPose, SIGNAL(toggled(
bool)),
88 QObject::connect(
ui_.pushButtonAbort, SIGNAL(clicked()),
134 switch (event->type())
136 case QEvent::MouseButtonPress:
138 case QEvent::MouseButtonRelease:
140 case QEvent::MouseMove:
150 ui_.pushButtonAbort->setEnabled( connected );
151 ui_.pushButtonGoalPose->setEnabled( connected );
152 ui_.pushButtonInitialPose->setEnabled( connected );
197 bool init_checked =
ui_.pushButtonInitialPose->isChecked();
198 bool goal_checked =
ui_.pushButtonGoalPose->isChecked();
199 if( !init_checked && !goal_checked)
204 if (event->button() == Qt::LeftButton)
208 #if QT_VERSION >= 0x050000
222 #if QT_VERSION >= 0x050000
242 bool init_checked =
ui_.pushButtonInitialPose->isChecked();
243 bool goal_checked =
ui_.pushButtonGoalPose->isChecked();
244 if( !init_checked && !goal_checked)
259 geometry_msgs::Pose& pose =
move_base_msg_.action_goal.goal.target_pose.pose;
262 pose.position.z = 0.0;
266 ui_.pushButtonGoalPose->setChecked(
false);
270 geometry_msgs::PoseWithCovarianceStamped initpose;
275 initpose.pose.pose.position.z = 0.0;
279 ui_.pushButtonInitialPose->setChecked(
false);
287 std::array<QPointF, 7> arrow_points;
288 arrow_points[0] = QPointF(10, 0);
289 arrow_points[1] = QPointF(6, -2.5);
290 arrow_points[2] = QPointF(6.5, -1);
291 arrow_points[3] = QPointF(0, -1);
292 arrow_points[4] = QPointF(0, 1);
293 arrow_points[5] = QPointF(6.5, 1);
294 arrow_points[6] = QPointF(6, 2.5);
298 QPointF transformed_points[7];
299 for (
size_t i=0; i<7; i++ )
301 tf::Vector3 point(arrow_points[i].x(), arrow_points[i].y(), 0);
307 glColor3f(0.1, 0.9, 0.1);
309 glBegin(GL_TRIANGLE_FAN);
310 for (
const QPointF& point: transformed_points )
312 glVertex2d(point.x(), point.y());
316 glColor3f(0.0, 0.6, 0.0);
317 glBegin(GL_LINE_LOOP);
318 for (
const QPointF& point: transformed_points )
320 glVertex2d(point.x(), point.y());
339 const bool other_checked =
ui_.pushButtonGoalPose->isChecked();
343 ui_.pushButtonGoalPose->setChecked(
false);
346 QPixmap cursor_pixmap = QPixmap(
":/images/green-arrow.png");
347 QApplication::setOverrideCursor(QCursor(cursor_pixmap));
350 if( !checked && !other_checked )
352 QApplication::restoreOverrideCursor();
358 const bool other_checked =
ui_.pushButtonInitialPose->isChecked();
361 ui_.pushButtonInitialPose->setChecked(
false);
364 QPixmap cursor_pixmap = QPixmap(
":/images/green-arrow.png");
365 QApplication::setOverrideCursor(QCursor(cursor_pixmap));
368 if( !checked && !other_checked )
370 QApplication::restoreOverrideCursor();