30 #ifndef MAPVIZ_PLUGINS_ATTITUDE_INDICATOR_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_ATTITUDE_INDICATOR_PLUGIN_H_ 48 #include <geometry_msgs/Pose.h> 49 #include <nav_msgs/Odometry.h> 51 #include <sensor_msgs/Imu.h> 59 #include "ui_attitude_indicator_config.h" 74 void Draw(
double x,
double y,
double scale);
78 void LoadConfig(
const YAML::Node& node,
const std::string& path);
79 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
85 void PrintInfo(
const std::string& message);
113 Ui::attitude_indicator_config
ui_;
116 #endif // MAPVIZ_PLUGINS_ATTITUDE_INDICATOR_PLUGIN_H_
void LoadConfig(const YAML::Node &node, const std::string &path)
PlaceableWindowProxy placer_
void AttitudeCallbackImu(const sensor_msgs::ImuConstPtr &imu)
void Draw(double x, double y, double scale)
void PrintError(const std::string &message)
TFSIMD_FORCE_INLINE const tfScalar & y() const
Ui::attitude_indicator_config ui_
void handleMessage(const topic_tools::ShapeShifter::ConstPtr &msg)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void timerEvent(QTimerEvent *)
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)
AttitudeIndicatorPlugin()
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)