30 #ifndef MAPVIZ_PLUGINS_DISPARITY_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_DISPARITY_PLUGIN_H_ 48 #include <opencv/highgui.h> 50 #include <stereo_msgs/DisparityImage.h> 56 #include "ui_disparity_config.h" 84 void Draw(
double x,
double y,
double scale);
88 void LoadConfig(
const YAML::Node& node,
const std::string& path);
89 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
95 void PrintInfo(
const std::string& message);
145 #endif // MAPVIZ_PLUGINS_DISPARITY_PLUGIN_H_
void PrintInfo(const std::string &message)
void disparityCallback(const stereo_msgs::DisparityImageConstPtr &image)
void Draw(double x, double y, double scale)
void PrintError(const std::string &message)
virtual ~DisparityPlugin()
void PrintWarning(const std::string &message)
std::string UnitsToString(Units units)
TFSIMD_FORCE_INLINE const tfScalar & y() const
cv::Mat_< cv::Vec3b > disparity_color_
void DrawIplImage(cv::Mat *image)
bool Initialize(QGLWidget *canvas)
void SetOffsetY(int offset)
std::string AnchorToString(Anchor anchor)
void ScaleImage(double width, double height)
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::Subscriber disparity_sub_
static const unsigned char COLOR_MAP[]
void SetUnits(QString units)
void SetHeight(int height)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
stereo_msgs::DisparityImage disparity_
void LoadConfig(const YAML::Node &node, const std::string &path)
void SetAnchor(QString anchor)
void SetOffsetX(int offset)
QWidget * GetConfigWidget(QWidget *parent)