Go to the documentation of this file.
6 #include <jsk_topic_tools/log_utils.h>
7 #include <sensor_msgs/Image.h>
8 #include <sensor_msgs/CameraInfo.h>
14 #if ( CV_MAJOR_VERSION >= 4)
15 #include <opencv2/opencv.hpp>
41 void imageCB(
const sensor_msgs::ImageConstPtr &img) {
50 bool prevImg_update_required =
false;
51 if((
flow.cols != (
int)
img->width) ||
52 (
flow.rows != (
int)
img->height)) {
54 cv_ptr->image.copyTo(
flow);
55 prevImg_update_required =
true;
57 if(prevImg_update_required) {
59 prevImg_update_required =
false;
67 cv::Mat nextImg(
img->height,
img->width, CV_8UC1);
69 cv_ptr->image.copyTo(nextImg);
71 cv::calcOpticalFlowFarneback(
prevImg, nextImg,
flow,
72 0.5, 3, 15, 3, 5, 1.2, 0 );
86 CvPoint2D32f *ptr = (CvPoint2D32f *)
flow.data;
87 for(
int i = 0;
i<
result.data.size();
i++) {
90 int val = 10 *
sqrt(ptr[
i].
x * ptr[
i].
x + ptr[
i].y * ptr[
i].y);
91 result.data[
i] = 255>val?val:255;
97 int main(
int argc,
char **argv)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
image_transport::Subscriber sub_
image_transport::ImageTransport it_
void publish(const boost::shared_ptr< M > &message) const
void imageCB(const sensor_msgs::ImageConstPtr &img)
Publisher advertise(AdvertiseOptions &ops)
std::string resolveName(const std::string &name, bool remap=true) const
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
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())
ROS_INFO ROS_ERROR int pointer * argv
int main(int argc, char **argv)
ros::Publisher result_pub_
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16