Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <string>
00031
00032 #include <opencv2/core/core.hpp>
00033 #include <opencv2/imgproc/imgproc.hpp>
00034
00035 #include <ros/ros.h>
00036 #include <nodelet/nodelet.h>
00037 #include <image_transport/image_transport.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <sensor_msgs/Image.h>
00040 #include <cv_bridge/cv_bridge.h>
00041 #include <swri_math_util/math_util.h>
00042
00043 namespace swri_image_util
00044 {
00045 class DrawTextNodelet : public nodelet::Nodelet
00046 {
00047 public:
00048 DrawTextNodelet() :
00049 text_("label"),
00050 offset_x_(0),
00051 offset_y_(0),
00052 font_scale_(1.0),
00053 font_thickness_(1)
00054 {
00055 }
00056
00057 ~DrawTextNodelet()
00058 {
00059 }
00060
00061 void onInit()
00062 {
00063 ros::NodeHandle &node = getNodeHandle();
00064 ros::NodeHandle &priv = getPrivateNodeHandle();
00065
00066 priv.param("text", text_, text_);
00067 priv.param("offset_x", offset_x_, offset_x_);
00068 priv.param("offset_y", offset_y_, offset_y_);
00069 priv.param("font_scale", font_scale_, font_scale_);
00070 priv.param("font_thickness", font_thickness_, font_thickness_);
00071
00072 image_transport::ImageTransport it(node);
00073 image_pub_ = it.advertise("stamped_image", 1);
00074 image_sub_ = it.subscribe("image", 1, &DrawTextNodelet::ImageCallback, this);
00075 }
00076
00077 void ImageCallback(const sensor_msgs::ImageConstPtr& image)
00078 {
00079 cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(image);
00080
00081 cv::putText(
00082 cv_image->image,
00083 text_,
00084 cv::Point(offset_x_, offset_y_),
00085 cv::FONT_HERSHEY_SIMPLEX,
00086 font_scale_,
00087 cv::Scalar(255, 255, 255),
00088 font_thickness_);
00089
00090 image_pub_.publish(cv_image->toImageMsg());
00091 }
00092
00093 private:
00094 std::string text_;
00095 double offset_x_;
00096 double offset_y_;
00097 double font_scale_;
00098 int font_thickness_;
00099
00100 image_transport::Subscriber image_sub_;
00101 image_transport::Publisher image_pub_;
00102 };
00103 }
00104
00105
00106 #include <pluginlib/class_list_macros.h>
00107 PLUGINLIB_DECLARE_CLASS(
00108 swri_image_util,
00109 draw_text,
00110 swri_image_util::DrawTextNodelet,
00111 nodelet::Nodelet)