32 #include <sensor_msgs/Image.h> 40 #include <opencv2/highgui/highgui.hpp> 64 std::string modelPath;
65 pnh.
param(
"model", modelPath, modelPath);
69 NODELET_ERROR(
"undistort_depth: \"model\" parameter should be set!");
75 NODELET_ERROR(
"Loaded distortion model from \"%s\" is not valid!", modelPath.c_str());
85 void callback(
const sensor_msgs::ImageConstPtr& depth)
105 NODELET_ERROR(
"Input depth image size (%dx%d) and distortion model " 106 "size (%dx%d) don't match! Cannot undistort image.",
107 depth->width, depth->height,
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())
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
std::string resolveName(const std::string &name, bool remap=true) const
clams::DiscreteDepthDistortionModel model_
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const sensor_msgs::Image &message) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string TYPE_32FC1
void callback(const sensor_msgs::ImageConstPtr &depth)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string TYPE_16UC1
virtual ~UndistortDepth()
ros::NodeHandle & getNodeHandle() const
void load(const std::string &path)
image_transport::Publisher pub_
image_transport::Subscriber sub_
void undistort(cv::Mat &depth) const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)