12 #include <opencv2/imgproc/imgproc.hpp> 13 #include <opencv2/highgui/highgui.hpp> 25 "/camera/rgb/image_raw", 1,
27 cv::namedWindow(
"OrinetedGradient");
44 ROS_ERROR(
"cv_bridge exception: %s", e.what());
48 cv::Mat cv_img = cv_ptr->image;
56 cv::cvtColor(cv_og_img, cv_out_img, CV_HSV2BGR);
70 int main(
int argc,
char** argv) {
71 ros::init(argc, argv,
"oriented_gradient");
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)
image_transport::Publisher image_pub_
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)
image_transport::Subscriber image_sub_
OrientedGradientNode(const ros::NodeHandle &nh)
image_transport::ImageTransport image_transport_
sensor_msgs::ImagePtr toImageMsg() const