30 #ifndef MAPVIZ_PLUGINS_IMAGE_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_IMAGE_PLUGIN_H_ 48 #include <sensor_msgs/Image.h> 49 #include <opencv2/highgui.hpp> 56 #include "ui_image_config.h" 85 void Draw(
double x,
double y,
double scale);
92 void LoadConfig(
const YAML::Node& node,
const std::string& path);
93 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
99 void PrintInfo(
const std::string& message);
157 #endif // MAPVIZ_PLUGINS_IMAGE_PLUGIN_H_ void KeepRatioChanged(bool checked)
void PrintInfo(const std::string &message)
ros::NodeHandle local_node_
void DrawIplImage(cv::Mat *image)
bool Initialize(QGLWidget *canvas)
virtual void SetNode(const ros::NodeHandle &node)
void SetOffsetY(int offset)
void SetOffsetX(int offset)
sensor_msgs::Image image_
void PrintError(const std::string &message)
void SetWidth(double width)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void ScaleImage(double width, double height)
void SetAnchor(QString anchor)
image_transport::Subscriber image_sub_
void SetUnits(QString units)
double original_aspect_ratio_
void LoadConfig(const YAML::Node &node, const std::string &path)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void SetSubscription(bool visible)
std::string AnchorToString(Anchor anchor)
void SetTransport(const QString &transport)
void PrintWarning(const std::string &message)
QWidget * GetConfigWidget(QWidget *parent)
cv_bridge::CvImagePtr cv_image_
std::string UnitsToString(Units units)
void SetHeight(double height)
void imageCallback(const sensor_msgs::ImageConstPtr &image)
void Draw(double x, double y, double scale)