oriented_gradient_node.cpp
Go to the documentation of this file.
00001 // @brief sample node to use oriented gradient
00002 // @author Hiroaki Yaguchi, JSK
00003 
00004 #include <vector>
00005 #include <string>
00006 
00007 #include <ros/ros.h>
00008 #include <jsk_topic_tools/log_utils.h>
00009 #include <image_transport/image_transport.h>
00010 #include <cv_bridge/cv_bridge.h>
00011 #include <sensor_msgs/image_encodings.h>
00012 #include <opencv2/imgproc/imgproc.hpp>
00013 #include <opencv2/highgui/highgui.hpp>
00014 
00015 #include "jsk_perception/oriented_gradient.hpp"
00016 
00017 namespace jsk_perception {
00018 
00019 class OrientedGradientNode {
00020  public:
00021   explicit OrientedGradientNode(const ros::NodeHandle& nh) :
00022       handle_(nh), image_transport_(nh) {
00023     image_pub_ = image_transport_.advertise("image", 1);
00024     image_sub_ = image_transport_.subscribe(
00025         "/camera/rgb/image_raw", 1,
00026         &OrientedGradientNode::imageCallback, this);
00027     cv::namedWindow("OrinetedGradient");
00028   }
00029 
00030   ~OrientedGradientNode() {
00031   }
00032 
00033  private:
00034   ros::NodeHandle handle_;
00035   image_transport::ImageTransport image_transport_;
00036   image_transport::Subscriber image_sub_;
00037   image_transport::Publisher image_pub_;
00038   void imageCallback(const sensor_msgs::ImageConstPtr& msg) {
00039     cv_bridge::CvImagePtr cv_ptr;
00040 
00041     try {
00042       cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00043     } catch (cv_bridge::Exception& e) {
00044       ROS_ERROR("cv_bridge exception: %s", e.what());
00045       return;
00046     }
00047 
00048     cv::Mat cv_img = cv_ptr->image;
00049     cv::Mat cv_og_img;
00050     cv::Mat cv_out_img;
00051 
00052     // calcOrientedGradient() will write oriented gradient to
00053     // 2nd arg image as HSV format,
00054     // H is orientation and V is intensity
00055     calcOrientedGradient(cv_img, cv_og_img);
00056     cv::cvtColor(cv_og_img, cv_out_img, CV_HSV2BGR);
00057     // cv::imshow("OrinetedGradient", cv_out_img);
00058     // cv::waitKey(1);
00059     sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(
00060       msg->header,
00061       sensor_msgs::image_encodings::BGR8,
00062       cv_out_img).toImageMsg();
00063     image_pub_.publish(out_img);
00064   }
00065 };
00066 
00067 }  // namespace
00068 
00069 
00070 int main(int argc, char** argv) {
00071   ros::init(argc, argv, "oriented_gradient");
00072   ros::NodeHandle handle("~");
00073   jsk_perception::OrientedGradientNode ognode(handle);
00074   ros::spin();
00075   return 0;
00076 }
00077 
00078 


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07