oriented_gradient_node.cpp
Go to the documentation of this file.
1 // @brief sample node to use oriented gradient
2 // @author Hiroaki Yaguchi, JSK
3 
4 #include <vector>
5 #include <string>
6 
7 #include <ros/ros.h>
10 #include <cv_bridge/cv_bridge.h>
12 #include <opencv2/imgproc/imgproc.hpp>
13 #include <opencv2/highgui/highgui.hpp>
14 
16 
17 namespace jsk_perception {
18 
20  public:
21  explicit OrientedGradientNode(const ros::NodeHandle& nh) :
22  handle_(nh), image_transport_(nh) {
25  "/camera/rgb/image_raw", 1,
27  cv::namedWindow("OrinetedGradient");
28  }
29 
31  }
32 
33  private:
38  void imageCallback(const sensor_msgs::ImageConstPtr& msg) {
39  cv_bridge::CvImagePtr cv_ptr;
40 
41  try {
43  } catch (cv_bridge::Exception& e) {
44  ROS_ERROR("cv_bridge exception: %s", e.what());
45  return;
46  }
47 
48  cv::Mat cv_img = cv_ptr->image;
49  cv::Mat cv_og_img;
50  cv::Mat cv_out_img;
51 
52  // calcOrientedGradient() will write oriented gradient to
53  // 2nd arg image as HSV format,
54  // H is orientation and V is intensity
55  calcOrientedGradient(cv_img, cv_og_img);
56  cv::cvtColor(cv_og_img, cv_out_img, CV_HSV2BGR);
57  // cv::imshow("OrinetedGradient", cv_out_img);
58  // cv::waitKey(1);
59  sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(
60  msg->header,
62  cv_out_img).toImageMsg();
63  image_pub_.publish(out_img);
64  }
65 };
66 
67 } // namespace
68 
69 
70 int main(int argc, char** argv) {
71  ros::init(argc, argv, "oriented_gradient");
72  ros::NodeHandle handle("~");
74  ros::spin();
75  return 0;
76 }
77 
78 
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void calcOrientedGradient(cv::Mat &src, cv::Mat &dst)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin(Spinner &spinner)
void publish(const sensor_msgs::Image &message) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
int main(int argc, char **argv)
OrientedGradientNode(const ros::NodeHandle &nh)
image_transport::ImageTransport image_transport_
#define ROS_ERROR(...)
sensor_msgs::ImagePtr toImageMsg() const


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27