Go to the documentation of this file.
36 #include <sensor_msgs/Image.h>
40 #include <opencv2/core/core.hpp>
41 #include <opencv2/highgui/highgui.hpp>
75 std::string temp_filename;
77 "/normalization_image.png";
84 ROS_ERROR(
"Planning to write normalization image to: %s",
97 void image_cb(
const sensor_msgs::ImageConstPtr& msg)
113 cv::Mat image(im_ptr->image);
126 if (!norm_im.empty())
132 catch (
const std::exception& e)
134 ROS_ERROR(
"Failed to save the normalization image: %s",
138 ROS_ERROR(
"Successfully wrote normalization image to: %s",
145 ROS_ERROR(
"Failed to generate a normalization image");
159 "/normalization_image.png";
171 fprintf(stderr,
"\nNode killed before enough frames received to generate "
172 "normalized image, so a normalized image was generated with "
173 "available frames (%d vs. %d)\n",
179 fprintf(stderr,
"\nNode killed before enough frames received to generate "
180 "normalized image: Too few frames in the buffer to generate a "
181 "normalization image\n");
185 fprintf(stderr,
"\nExiting normally\n");
195 int main(
int argc,
char **argv)
197 ros::init(argc, argv,
"image_normalization_node");
ROSLIB_DECL std::string getPath(const std::string &package_name)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
std::vector< cv::Mat > image_array_
ros::Subscriber image_sub_
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
int main(int argc, char **argv)
void image_cb(const sensor_msgs::ImageConstPtr &msg)
int32_t max_num_to_average_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void generate_and_write_image()
const ROSCPP_DECL std::string & getName()
cv::Mat generate_normalization_image(const std::vector< cv::Mat > &image_list)
Computes a best estimate of a normalization image from a vector of images.
T param(const std::string ¶m_name, const T &default_val) const
void subscribe_to_topics()
NormalizationImageNode(const ros::NodeHandle &nh)
swri_image_util
Author(s): Kris Kozak
autogenerated on Fri Aug 2 2024 08:39:19