38 #include <OGRE/OgreMaterialManager.h> 39 #include <OGRE/OgreTextureManager.h> 40 #include <OGRE/OgreTexture.h> 41 #include <OGRE/OgreHardwarePixelBuffer.h> 42 #include <OGRE/OgreTechnique.h> 52 :
Display(), width_(128), height_(128), left_(128), top_(128), alpha_(0.8),
53 is_msg_available_(false), require_update_(false), overwrite_alpha_(false)
58 ros::message_traits::datatype<sensor_msgs::Image>(),
59 "sensor_msgs::Image topic to subscribe to.",
62 "transport hint to subscribe topic",
65 "keep aspect ratio of original image",
68 "width of the image window",
71 "height of the image window",
74 "left of the image window",
77 "top of the image window",
80 "alpha belnding value",
83 "overwrite alpha value by alpha property " 84 "and ignore alpha channel of the image",
104 #if ROS_VERSION_MINIMUM(1,12,0) 146 if (topic_name.length() > 0 && topic_name !=
"/") {
156 const sensor_msgs::Image::ConstPtr& msg)
177 static int count = 0;
179 ss <<
"OverlayImageDisplayObject" << count++;
200 if (
msg_->width == 0 ||
msg_->height == 0) {
213 cv_ptr->image.copyTo(mat);
218 const cv::Mat bgr_image = cv_ptr->image;
219 std::vector<cv::Mat> channels;
222 cv::split(bgr_image, channels);
224 const cv::Mat
alpha(bgr_image.rows, bgr_image.cols, CV_8UC1,
225 cv::Scalar(
alpha_ * 255.0));
226 channels.push_back(alpha);
227 cv::merge(channels, mat);
233 memcpy(Hud.scanLine(0), mat.data, mat.cols * mat.rows * mat.elemSize());
238 ROS_ERROR(
"cv_bridge exception: %s", e.what());
270 double aspect_ratio =
msg_->height / (double)
msg_->width;
271 int height_from_width = std::ceil(
width_ * aspect_ratio);
325 return (top_ < y && top_ + height_ > y &&
326 left_ < x && left_ + width_ > x);
virtual bool setValue(const QVariant &new_value)
rviz::FloatProperty * alpha_property_
sensor_msgs::Image::ConstPtr msg_
rviz::IntProperty * width_property_
rviz::BoolProperty * keep_aspect_ratio_property_
virtual void movePosition(int x, int y)
virtual QImage getQImage(unsigned int width, unsigned int height)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
virtual int getInt() const
rviz::BoolProperty * overwrite_alpha_property_
virtual float getFloat() const
OverlayObject::Ptr overlay_
virtual void setPosition(int x, int y)
void updateOverwriteAlpha()
rviz::IntProperty * height_property_
virtual bool getBool() const
image_transport::TransportHints getTransportHints()
virtual bool isInRegion(int x, int y)
virtual void processMessage(const sensor_msgs::Image::ConstPtr &msg)
ImageTransportHintsProperty * transport_hint_property_
virtual void onInitialize()
virtual void unsubscribe()
virtual ~OverlayImageDisplay()
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void updateKeepAspectRatio()
rviz::IntProperty * left_property_
virtual void setHidden(bool hidden)
virtual void setImageSize()
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Subscriber sub_
rviz::IntProperty * top_property_
std::string getTopicStd() const
virtual void update(float wall_dt, float ros_dt)
rviz::RosTopicProperty * update_topic_property_