32 image_transport::ImageTransport
it_;
44 cv_bridge::CvImagePtr
cv_ptr;
64 void imageCb (
const sensor_msgs::ImageConstPtr & msg)
73 cv_ptr = cv_bridge::toCvCopy (msg,
"rgb8");
78 catch (cv_bridge::Exception & e)
80 ROS_ERROR (
"cv_bridge exception: %s", e.what ());
90 Mat MergedChannels (Img.rows, Img.cols, CV_64FC (
CHANNELNR));
95 cvtColor (Img, Img, CV_BGR2RGB, 0);
97 cvtColor (Img,
GrayImg, CV_RGB2GRAY, 0);
101 Sobel (
GrayImg,
xsobel, CV_32FC1, 1, 0, 3, 1, 0, BORDER_DEFAULT);
102 Sobel (
GrayImg,
ysobel, CV_32FC1, 0, 1, 3, 1, 0, BORDER_DEFAULT);
112 cvtColor (Img,
GrayImg, CV_RGB2GRAY, 0);
119 sensor_msgs::ImagePtr msg_out =
cv_ptr->toImageMsg ();
120 msg_out->encoding =
"32FC1";
121 msg_out->header.frame_id =
"Image_Out";
122 msg_out->header.stamp = ros::Time::now ();
132 int main (
int argc,
char **argv)
134 ros::init (argc, argv,
"image_converter");
vector< vec10d > d10Vector
MatVector LUVcolourchannels(Mat Img)
image_transport::Publisher image_pub_
int main(int argc, char **argv)
cv_bridge::CvImagePtr cv_ptr
MatVector OrientedGradientsDiagram(Mat GradMag, Mat xsobel, Mat ysobel)
void imageCb(const sensor_msgs::ImageConstPtr &msg)
image_transport::ImageTransport it_
Mat GradientMagnitude(Mat src)
image_transport::Subscriber image_sub_