00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <mapviz_plugins/attitude_indicator_plugin.h>
00031 #include <GL/glut.h>
00032
00033
00034 #include <algorithm>
00035 #include <cstdio>
00036 #include <vector>
00037
00038
00039 #include <QDebug>
00040 #include <QDialog>
00041 #include <QGLWidget>
00042
00043
00044 #include <ros/master.h>
00045
00046 #include <mapviz/select_topic_dialog.h>
00047 #include <mapviz/select_frame_dialog.h>
00048
00049
00050 #include <pluginlib/class_list_macros.h>
00051
00052 PLUGINLIB_EXPORT_CLASS(mapviz_plugins::AttitudeIndicatorPlugin, mapviz::MapvizPlugin)
00053
00054 namespace mapviz_plugins
00055 {
00056 #define IS_INSTANCE(msg, type) \
00057 (msg->getDataType() == ros::message_traits::datatype<type>())
00058
00059 AttitudeIndicatorPlugin::AttitudeIndicatorPlugin() :
00060 config_widget_(new QWidget())
00061 {
00062 ui_.setupUi(config_widget_);
00063
00064
00065 QPalette p(config_widget_->palette());
00066 p.setColor(QPalette::Background, Qt::white);
00067 config_widget_->setPalette(p);
00068 roll_ = pitch_ = yaw_ = 0;
00069 topics_.push_back("nav_msgs/Odometry");
00070 topics_.push_back("geometry_msgs/Pose");
00071 topics_.push_back("sensor_msgs/Imu");
00072
00073 QPalette p3(ui_.status->palette());
00074 p3.setColor(QPalette::Text, Qt::red);
00075 ui_.status->setPalette(p3);
00076
00077 placer_.setRect(QRect(0, 0, 100, 100));
00078 QObject::connect(this, SIGNAL(VisibleChanged(bool)),
00079 &placer_, SLOT(setVisible(bool)));
00080
00081 QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic()));
00082 QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited()));
00083 }
00084
00085 AttitudeIndicatorPlugin::~AttitudeIndicatorPlugin()
00086 {
00087 }
00088
00089 void AttitudeIndicatorPlugin::SelectTopic()
00090 {
00091 ros::master::TopicInfo topic = mapviz::SelectTopicDialog::selectTopic(
00092 topics_);
00093 if (topic.name.empty())
00094 {
00095 return;
00096 }
00097
00098 ui_.topic->setText(QString::fromStdString(topic.name));
00099 TopicEdited();
00100 }
00101
00102 void AttitudeIndicatorPlugin::TopicEdited()
00103 {
00104 std::string topic = ui_.topic->text().trimmed().toStdString();
00105 if (topic != topic_)
00106 {
00107 initialized_ = true;
00108 PrintWarning("No messages received.");
00109
00110 odometry_sub_.shutdown();
00111 topic_ = topic;
00112 if (!topic_.empty())
00113 {
00114 odometry_sub_ = node_.subscribe<topic_tools::ShapeShifter>(
00115 topic_, 100, &AttitudeIndicatorPlugin::handleMessage, this);
00116
00117 ROS_INFO("Subscribing to %s", topic_.c_str());
00118 }
00119 }
00120 }
00121
00122 void AttitudeIndicatorPlugin::handleMessage(const topic_tools::ShapeShifter::ConstPtr& msg)
00123 {
00124 if (IS_INSTANCE(msg, nav_msgs::Odometry))
00125 {
00126 AttitudeCallbackOdom(msg->instantiate<nav_msgs::Odometry>());
00127 }
00128 else if (IS_INSTANCE(msg, sensor_msgs::Imu))
00129 {
00130 AttitudeCallbackImu(msg->instantiate<sensor_msgs::Imu>());
00131 }
00132 else if (IS_INSTANCE(msg, geometry_msgs::Pose))
00133 {
00134 AttitudeCallbackPose(msg->instantiate<geometry_msgs::Pose>());
00135 }
00136 else
00137 {
00138 PrintError("Unknown message type: " + msg->getDataType());
00139 }
00140 }
00141
00142 void AttitudeIndicatorPlugin::AttitudeCallbackOdom(const nav_msgs::OdometryConstPtr& odometry)
00143 {
00144 attitude_orientation_ = tf::Quaternion(
00145 odometry->pose.pose.orientation.x,
00146 odometry->pose.pose.orientation.y,
00147 odometry->pose.pose.orientation.z,
00148 odometry->pose.pose.orientation.w);
00149
00150 tf::Matrix3x3 m(attitude_orientation_);
00151 m.getRPY(roll_, pitch_, yaw_);
00152 roll_ = roll_ * (180.0 / M_PI);
00153 pitch_ = pitch_ * (180.0 / M_PI);
00154 yaw_ = yaw_ * (180.0 / M_PI);
00155
00156 ROS_INFO("roll %f,pitch %f, yaw %f", roll_, pitch_, yaw_);
00157 canvas_->update();
00158 }
00159
00160 void AttitudeIndicatorPlugin::AttitudeCallbackImu(const sensor_msgs::ImuConstPtr& imu)
00161 {
00162 attitude_orientation_ = tf::Quaternion(
00163 imu->orientation.x,
00164 imu->orientation.y,
00165 imu->orientation.z,
00166 imu->orientation.w);
00167
00168 tf::Matrix3x3 m(attitude_orientation_);
00169 m.getRPY(roll_, pitch_, yaw_);
00170 roll_ = roll_ * (180.0 / M_PI);
00171 pitch_ = pitch_ * (180.0 / M_PI);
00172 yaw_ = yaw_ * (180.0 / M_PI);
00173 ROS_INFO("roll %f,pitch %f, yaw %f", roll_, pitch_, yaw_);
00174
00175 canvas_->update();
00176 }
00177
00178 void AttitudeIndicatorPlugin::AttitudeCallbackPose(const geometry_msgs::PoseConstPtr& pose)
00179 {
00180 attitude_orientation_ = tf::Quaternion(
00181 pose->orientation.x,
00182 pose->orientation.y,
00183 pose->orientation.z,
00184 pose->orientation.w);
00185
00186 tf::Matrix3x3 m(attitude_orientation_);
00187 m.getRPY(roll_, pitch_, yaw_);
00188 roll_ = roll_ * (180.0 / M_PI);
00189 pitch_ = pitch_ * (180.0 / M_PI);
00190 yaw_ = yaw_ * (180.0 / M_PI);
00191
00192 ROS_INFO("roll %f,pitch %f, yaw %f", roll_, pitch_, yaw_);
00193 canvas_->update();
00194 }
00195
00196 void AttitudeIndicatorPlugin::PrintError(const std::string& message)
00197 {
00198 PrintErrorHelper(ui_.status, message);
00199 }
00200
00201 void AttitudeIndicatorPlugin::PrintInfo(const std::string& message)
00202 {
00203 PrintInfoHelper(ui_.status, message);
00204 }
00205
00206 void AttitudeIndicatorPlugin::PrintWarning(const std::string& message)
00207 {
00208 PrintWarningHelper(ui_.status, message);
00209 }
00210
00211 QWidget* AttitudeIndicatorPlugin::GetConfigWidget(QWidget* parent)
00212 {
00213 config_widget_->setParent(parent);
00214 return config_widget_;
00215 }
00216
00217 bool AttitudeIndicatorPlugin::Initialize(QGLWidget* canvas)
00218 {
00219 initialized_ = true;
00220 canvas_ = canvas;
00221 placer_.setContainer(canvas_);
00222 startTimer(50);
00223 return true;
00224 }
00225
00226 void AttitudeIndicatorPlugin::Shutdown()
00227 {
00228 placer_.setContainer(NULL);
00229 }
00230
00231 void AttitudeIndicatorPlugin::timerEvent(QTimerEvent*)
00232 {
00233 canvas_->update();
00234 }
00235
00236 void AttitudeIndicatorPlugin::drawBall()
00237 {
00238 GLdouble eqn[4] = {0.0, 0.0, 1.0, 0.0};
00239 GLdouble eqn2[4] = {0.0, 0.0, -1.0, 0.0};
00240 GLdouble eqn4[4] = {0.0, 0.0, 1.0, 0.05};
00241 GLdouble eqn3[4] = {0.0, 0.0, -1.0, 0.05};
00242
00243 glEnable(GL_DEPTH_TEST);
00244 glDepthFunc(GL_LESS);
00245
00246 glPushMatrix();
00247
00248 glColor3f(0.392156863f, 0.584313725f, 0.929411765f);
00249 glRotated(90.0 + pitch_, 1.0, 0.0, 0.0);
00250
00251 glRotated(roll_, 0.0, 1.0, 0.0);
00252 glRotated(yaw_, 0.0, 0.0, 1.0);
00253 glClipPlane(GL_CLIP_PLANE1, eqn2);
00254 glEnable(GL_CLIP_PLANE1);
00255 glutSolidSphere(.8, 20, 16);
00256 glDisable(GL_CLIP_PLANE1);
00257 glPopMatrix();
00258
00259 glPushMatrix();
00260
00261 glLineWidth(2);
00262 glColor3f(1.0f, 1.0f, 1.0f);
00263 glRotated(90.0 + pitch_, 1.0, 0.0, 0.0);
00264 glRotated(roll_, 0.0, 1.0, 0.0);
00265 glRotated(yaw_, 0.0, 0.0, 1.0);
00266 glClipPlane(GL_CLIP_PLANE3, eqn4);
00267 glClipPlane(GL_CLIP_PLANE2, eqn3);
00268 glEnable(GL_CLIP_PLANE2);
00269 glEnable(GL_CLIP_PLANE3);
00270 glutWireSphere(.801, 10, 16);
00271 glDisable(GL_CLIP_PLANE2);
00272 glDisable(GL_CLIP_PLANE3);
00273 glPopMatrix();
00274
00275 glPushMatrix();
00276 glColor3f(0.62745098f, 0.321568627f, 0.176470588f);
00277 glRotated(90.0 + pitch_, 1.0, 0.0, 0.0);
00278 glRotated(roll_, 0.0, 1.0, 0.0);
00279 glRotated(yaw_, 0.0, 0.0, 1.0);
00280 glClipPlane(GL_CLIP_PLANE0, eqn);
00281 glEnable(GL_CLIP_PLANE0);
00282 glutSolidSphere(.8, 20, 16);
00283 glDisable(GL_CLIP_PLANE0);
00284 glPopMatrix();
00285 glDisable(GL_DEPTH_TEST);
00286 }
00287
00288 void AttitudeIndicatorPlugin::Draw(double x, double y, double scale)
00289 {
00290 glPushAttrib(GL_ALL_ATTRIB_BITS);
00291 glMatrixMode(GL_PROJECTION);
00292 glPushMatrix();
00293 glLoadIdentity();
00294 glOrtho(0, canvas_->width(), canvas_->height(), 0, -1.0f, 1.0f);
00295 glMatrixMode(GL_MODELVIEW);
00296 glPushMatrix();
00297 glLoadIdentity();
00298
00299
00300 QRect rect = placer_.rect();
00301 double s_x = rect.width() / 2.0;
00302 double s_y = -rect.height() / 2.0;
00303 double t_x = rect.right() - s_x;
00304 double t_y = rect.top() - s_y;
00305
00306 double m[16] = {
00307 s_x, 0, 0, 0,
00308 0, s_y, 0, 0,
00309 0, 0, 1.0, 0,
00310 t_x, t_y, 0, 1.0};
00311 glMultMatrixd(m);
00312
00313
00314
00315
00316 drawBackground();
00317 drawBall();
00318
00319 drawPanel();
00320
00321 glPopMatrix();
00322 glMatrixMode(GL_PROJECTION);
00323 glPopMatrix();
00324 glMatrixMode(GL_MODELVIEW);
00325 glPopAttrib();
00326 PrintInfo("OK!");
00327 }
00328
00329 void AttitudeIndicatorPlugin::drawBackground()
00330 {
00331 glBegin(GL_TRIANGLES);
00332 glColor4f(0.0f, 0.0f, 0.0f, 1.0f);
00333
00334 glVertex2d(-1.0, -1.0);
00335 glVertex2d(-1.0, 1.0);
00336 glVertex2d(1.0, 1.0);
00337
00338 glVertex2d(-1.0, -1.0);
00339 glVertex2d(1.0, 1.0);
00340 glVertex2d(1.0, -1.0);
00341
00342 glEnd();
00343 }
00344
00345 void AttitudeIndicatorPlugin::drawPanel()
00346 {
00347 glLineWidth(2);
00348
00349 glBegin(GL_LINE_STRIP);
00350 glColor4f(1.0f, 1.0f, 1.0f, 1.0f);
00351
00352 glVertex2d(-0.9, 0.0);
00353 glVertex2d(-0.2, 0.0);
00354
00355 int divisions = 20;
00356 for (int i = 1; i < divisions; i++)
00357 {
00358 glVertex2d(-0.2 * std::cos(M_PI * i / divisions),
00359 -0.2 * std::sin(M_PI * i / divisions));
00360 }
00361
00362 glVertex2f(0.2, 0.0);
00363 glVertex2f(0.9, 0.0);
00364 glEnd();
00365
00366 glBegin(GL_LINES);
00367 glVertex2f(0.0, -0.2f);
00368 glVertex2f(0.0, -0.9f);
00369 glEnd();
00370 }
00371
00372 void AttitudeIndicatorPlugin::LoadConfig(const YAML::Node& node, const std::string& path)
00373 {
00374 if (node["topic"])
00375 {
00376 std::string topic;
00377 node["topic"] >> topic;
00378 ui_.topic->setText(topic.c_str());
00379 }
00380
00381 QRect current = placer_.rect();
00382 int x = current.x();
00383 int y = current.y();
00384 int width = current.width();
00385 int height = current.height();
00386
00387 if (swri_yaml_util::FindValue(node, "x"))
00388 {
00389 node["x"] >> x;
00390 }
00391
00392 if (swri_yaml_util::FindValue(node, "y"))
00393 {
00394 node["y"] >> y;
00395 }
00396
00397 if (swri_yaml_util::FindValue(node, "width"))
00398 {
00399 node["width"] >> width;
00400 }
00401
00402 if (swri_yaml_util::FindValue(node, "height"))
00403 {
00404 node["height"] >> height;
00405 }
00406
00407 QRect position(x, y, width, height);
00408 placer_.setRect(position);
00409
00410 TopicEdited();
00411 }
00412
00413 void AttitudeIndicatorPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path)
00414 {
00415 emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString();
00416
00417 QRect position = placer_.rect();
00418
00419 emitter << YAML::Key << "x" << YAML::Value << position.x();
00420 emitter << YAML::Key << "y" << YAML::Value << position.y();
00421 emitter << YAML::Key << "width" << YAML::Value << position.width();
00422 emitter << YAML::Key << "height" << YAML::Value << position.height();
00423 }
00424 }