56 #define IS_INSTANCE(msg, type) \ 57 (msg->getDataType() == ros::message_traits::datatype<type>()) 59 AttitudeIndicatorPlugin::AttitudeIndicatorPlugin() :
60 config_widget_(new QWidget())
66 p.setColor(QPalette::Background, Qt::white);
69 topics_.push_back(
"nav_msgs/Odometry");
70 topics_.push_back(
"geometry_msgs/Pose");
71 topics_.push_back(
"sensor_msgs/Imu");
73 QPalette p3(
ui_.status->palette());
74 p3.setColor(QPalette::Text, Qt::red);
75 ui_.status->setPalette(p3);
79 &
placer_, SLOT(setVisible(
bool)));
81 QObject::connect(
ui_.selecttopic, SIGNAL(clicked()),
this, SLOT(
SelectTopic()));
82 QObject::connect(
ui_.topic, SIGNAL(editingFinished()),
this, SLOT(
TopicEdited()));
93 if (topic.
name.empty())
98 ui_.topic->setText(QString::fromStdString(topic.
name));
104 std::string topic =
ui_.topic->text().trimmed().toStdString();
117 ROS_INFO(
"Subscribing to %s", topic_.c_str());
138 PrintError(
"Unknown message type: " + msg->getDataType());
168 pitch_ = pitch_ * (180.0 / M_PI);
169 yaw_ = yaw_ * (180.0 / M_PI);
216 GLdouble eqn[4] = {0.0, 0.0, 1.0, 0.0};
217 GLdouble eqn2[4] = {0.0, 0.0, -1.0, 0.0};
218 GLdouble eqn4[4] = {0.0, 0.0, 1.0, 0.05};
219 GLdouble eqn3[4] = {0.0, 0.0, -1.0, 0.05};
221 glEnable(GL_DEPTH_TEST);
222 glDepthFunc(GL_LESS);
226 glColor3f(0.392156863
f, 0.584313725
f, 0.929411765
f);
227 glRotated(90.0 +
pitch_, 1.0, 0.0, 0.0);
229 glRotated(
roll_, 0.0, 1.0, 0.0);
230 glRotated(
yaw_, 0.0, 0.0, 1.0);
231 glClipPlane(GL_CLIP_PLANE1, eqn2);
232 glEnable(GL_CLIP_PLANE1);
233 glutSolidSphere(.8, 20, 16);
234 glDisable(GL_CLIP_PLANE1);
240 glColor3f(1.0
f, 1.0
f, 1.0
f);
241 glRotated(90.0 +
pitch_, 1.0, 0.0, 0.0);
242 glRotated(
roll_, 0.0, 1.0, 0.0);
243 glRotated(
yaw_, 0.0, 0.0, 1.0);
244 glClipPlane(GL_CLIP_PLANE3, eqn4);
245 glClipPlane(GL_CLIP_PLANE2, eqn3);
246 glEnable(GL_CLIP_PLANE2);
247 glEnable(GL_CLIP_PLANE3);
248 glutWireSphere(.801, 10, 16);
249 glDisable(GL_CLIP_PLANE2);
250 glDisable(GL_CLIP_PLANE3);
254 glColor3f(0.62745098
f, 0.321568627
f, 0.176470588
f);
255 glRotated(90.0 +
pitch_, 1.0, 0.0, 0.0);
256 glRotated(
roll_, 0.0, 1.0, 0.0);
257 glRotated(
yaw_, 0.0, 0.0, 1.0);
258 glClipPlane(GL_CLIP_PLANE0, eqn);
259 glEnable(GL_CLIP_PLANE0);
260 glutSolidSphere(.8, 20, 16);
261 glDisable(GL_CLIP_PLANE0);
263 glDisable(GL_DEPTH_TEST);
268 glPushAttrib(GL_ALL_ATTRIB_BITS);
269 glMatrixMode(GL_PROJECTION);
273 glMatrixMode(GL_MODELVIEW);
279 double s_x = rect.width() / 2.0;
280 double s_y = -rect.height() / 2.0;
281 double t_x = rect.right() - s_x;
282 double t_y = rect.top() - s_y;
300 glMatrixMode(GL_PROJECTION);
302 glMatrixMode(GL_MODELVIEW);
309 glBegin(GL_TRIANGLES);
310 glColor4f(0.0
f, 0.0
f, 0.0
f, 1.0
f);
312 glVertex2d(-1.0, -1.0);
313 glVertex2d(-1.0, 1.0);
314 glVertex2d(1.0, 1.0);
316 glVertex2d(-1.0, -1.0);
317 glVertex2d(1.0, 1.0);
318 glVertex2d(1.0, -1.0);
327 glBegin(GL_LINE_STRIP);
328 glColor4f(1.0
f, 1.0
f, 1.0
f, 1.0
f);
330 glVertex2d(-0.9, 0.0);
331 glVertex2d(-0.2, 0.0);
334 for (
int i = 1; i < divisions; i++)
336 glVertex2d(-0.2 * std::cos(M_PI * i / divisions),
337 -0.2 * std::sin(M_PI * i / divisions));
340 glVertex2f(0.2, 0.0);
341 glVertex2f(0.9, 0.0);
345 glVertex2f(0.0, -0.2
f);
346 glVertex2f(0.0, -0.9
f);
355 node[
"topic"] >> topic;
356 ui_.topic->setText(topic.c_str());
362 int width = current.width();
363 int height = current.height();
377 node[
"width"] >> width;
382 node[
"height"] >> height;
385 QRect position(x, y, width, height);
393 emitter << YAML::Key <<
"topic" << YAML::Value <<
ui_.topic->text().toStdString();
397 emitter << YAML::Key <<
"x" << YAML::Value << position.x();
398 emitter << YAML::Key <<
"y" << YAML::Value << position.y();
399 emitter << YAML::Key <<
"width" << YAML::Value << position.width();
400 emitter << YAML::Key <<
"height" << YAML::Value << position.height();
static ros::master::TopicInfo selectTopic(const std::string &datatype, QWidget *parent=0)
void LoadConfig(const YAML::Node &node, const std::string &path)
PlaceableWindowProxy placer_
void AttitudeCallbackImu(const sensor_msgs::ImuConstPtr &imu)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setContainer(QWidget *)
void setRect(const QRect &)
void Draw(double x, double y, double scale)
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)
void PrintError(const std::string &message)
void applyAttitudeOrientation(const geometry_msgs::Quaternion &orientation)
TFSIMD_FORCE_INLINE const tfScalar & y() const
Ui::attitude_indicator_config ui_
static void PrintInfoHelper(QLabel *status_label, const std::string &message, double throttle=0.0)
#define IS_INSTANCE(msg, type)
bool FindValue(const YAML::Node &node, const std::string &name)
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void timerEvent(QTimerEvent *)
void VisibleChanged(bool visible)
virtual ~AttitudeIndicatorPlugin()
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void AttitudeCallbackOdom(const nav_msgs::OdometryConstPtr &odometry)
void PrintInfo(const std::string &message)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
ros::Subscriber odometry_sub_
void PrintWarning(const std::string &message)
std::vector< std::string > topics_
QWidget * GetConfigWidget(QWidget *parent)
bool Initialize(QGLWidget *canvas)
void AttitudeCallbackPose(const geometry_msgs::PoseConstPtr &pose)