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());
145 odometry->pose.pose.orientation.x,
146 odometry->pose.pose.orientation.y,
147 odometry->pose.pose.orientation.z,
148 odometry->pose.pose.orientation.w);
153 pitch_ = pitch_ * (180.0 / M_PI);
154 yaw_ = yaw_ * (180.0 / M_PI);
171 pitch_ = pitch_ * (180.0 / M_PI);
172 yaw_ = yaw_ * (180.0 / M_PI);
184 pose->orientation.w);
189 pitch_ = pitch_ * (180.0 / M_PI);
190 yaw_ = yaw_ * (180.0 / M_PI);
238 GLdouble eqn[4] = {0.0, 0.0, 1.0, 0.0};
239 GLdouble eqn2[4] = {0.0, 0.0, -1.0, 0.0};
240 GLdouble eqn4[4] = {0.0, 0.0, 1.0, 0.05};
241 GLdouble eqn3[4] = {0.0, 0.0, -1.0, 0.05};
243 glEnable(GL_DEPTH_TEST);
244 glDepthFunc(GL_LESS);
248 glColor3f(0.392156863
f, 0.584313725
f, 0.929411765
f);
249 glRotated(90.0 +
pitch_, 1.0, 0.0, 0.0);
251 glRotated(
roll_, 0.0, 1.0, 0.0);
252 glRotated(
yaw_, 0.0, 0.0, 1.0);
253 glClipPlane(GL_CLIP_PLANE1, eqn2);
254 glEnable(GL_CLIP_PLANE1);
255 glutSolidSphere(.8, 20, 16);
256 glDisable(GL_CLIP_PLANE1);
262 glColor3f(1.0
f, 1.0
f, 1.0
f);
263 glRotated(90.0 +
pitch_, 1.0, 0.0, 0.0);
264 glRotated(
roll_, 0.0, 1.0, 0.0);
265 glRotated(
yaw_, 0.0, 0.0, 1.0);
266 glClipPlane(GL_CLIP_PLANE3, eqn4);
267 glClipPlane(GL_CLIP_PLANE2, eqn3);
268 glEnable(GL_CLIP_PLANE2);
269 glEnable(GL_CLIP_PLANE3);
270 glutWireSphere(.801, 10, 16);
271 glDisable(GL_CLIP_PLANE2);
272 glDisable(GL_CLIP_PLANE3);
276 glColor3f(0.62745098
f, 0.321568627
f, 0.176470588
f);
277 glRotated(90.0 +
pitch_, 1.0, 0.0, 0.0);
278 glRotated(
roll_, 0.0, 1.0, 0.0);
279 glRotated(
yaw_, 0.0, 0.0, 1.0);
280 glClipPlane(GL_CLIP_PLANE0, eqn);
281 glEnable(GL_CLIP_PLANE0);
282 glutSolidSphere(.8, 20, 16);
283 glDisable(GL_CLIP_PLANE0);
285 glDisable(GL_DEPTH_TEST);
290 glPushAttrib(GL_ALL_ATTRIB_BITS);
291 glMatrixMode(GL_PROJECTION);
295 glMatrixMode(GL_MODELVIEW);
301 double s_x = rect.width() / 2.0;
302 double s_y = -rect.height() / 2.0;
303 double t_x = rect.right() - s_x;
304 double t_y = rect.top() - s_y;
322 glMatrixMode(GL_PROJECTION);
324 glMatrixMode(GL_MODELVIEW);
331 glBegin(GL_TRIANGLES);
332 glColor4f(0.0
f, 0.0
f, 0.0
f, 1.0
f);
334 glVertex2d(-1.0, -1.0);
335 glVertex2d(-1.0, 1.0);
336 glVertex2d(1.0, 1.0);
338 glVertex2d(-1.0, -1.0);
339 glVertex2d(1.0, 1.0);
340 glVertex2d(1.0, -1.0);
349 glBegin(GL_LINE_STRIP);
350 glColor4f(1.0
f, 1.0
f, 1.0
f, 1.0
f);
352 glVertex2d(-0.9, 0.0);
353 glVertex2d(-0.2, 0.0);
356 for (
int i = 1; i < divisions; i++)
358 glVertex2d(-0.2 * std::cos(M_PI * i / divisions),
359 -0.2 * std::sin(M_PI * i / divisions));
362 glVertex2f(0.2, 0.0);
363 glVertex2f(0.9, 0.0);
367 glVertex2f(0.0, -0.2
f);
368 glVertex2f(0.0, -0.9
f);
377 node[
"topic"] >> topic;
378 ui_.topic->setText(topic.c_str());
384 int width = current.width();
385 int height = current.height();
399 node[
"width"] >> width;
404 node[
"height"] >> height;
407 QRect position(x, y, width, height);
415 emitter << YAML::Key <<
"topic" << YAML::Value <<
ui_.topic->text().toStdString();
419 emitter << YAML::Key <<
"x" << YAML::Value << position.x();
420 emitter << YAML::Key <<
"y" << YAML::Value << position.y();
421 emitter << YAML::Key <<
"width" << YAML::Value << position.width();
422 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)
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()
tf::Quaternion attitude_orientation_
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)