45 DiagnosticNodelet::onInit();
46 if (
pnh_->hasParam(
"coefficients2")) {
53 if (
pnh_->hasParam(
"coefficients1")) {
61 if (
pnh_->hasParam(
"coefficients0")) {
72 "set_calibration_parameter",
75 pub_ = advertise<sensor_msgs::Image>(*
pnh_,
"output", 1);
81 NODELET_INFO(
"C2(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
83 NODELET_INFO(
"C1(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
85 NODELET_INFO(
"C0(u, v) = %fu^2 + %fu + %fv^2 + %fv + %f",
96 jsk_recognition_msgs::SetDepthCalibrationParameter::Request&
req,
97 jsk_recognition_msgs::SetDepthCalibrationParameter::Response&
res)
112 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
124 const sensor_msgs::Image::ConstPtr&
msg,
125 const sensor_msgs::CameraInfo::ConstPtr& camera_info)
138 cv::Mat image = cv_ptr->image;
139 cv::Mat output_image = image.clone();
140 double cu = camera_info->P[2];
141 double cv = camera_info->P[6];
142 for(
int v = 0;
v < image.rows;
v++) {
143 for(
int u = 0; u < image.cols; u++) {
144 float z = image.at<
float>(
v, u);
146 output_image.at<
float>(v, u) = z;
149 output_image.at<
float>(v, u) =
applyModel(z, u, v, cu, cv);
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::DepthCalibration, nodelet::Nodelet)
ros::ServiceServer set_calibration_parameter_srv_
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void unsubscribe()
virtual void calibrate(const sensor_msgs::Image::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &camera_info)
virtual void printModel()
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
const std::string TYPE_32FC1
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
std::vector< double > coefficients1_
std::vector< double > coefficients2_
#define NODELET_INFO(...)
virtual bool setCalibrationParameter(jsk_recognition_msgs::SetDepthCalibrationParameter::Request &req, jsk_recognition_msgs::SetDepthCalibrationParameter::Response &res)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::Subscriber< sensor_msgs::Image > sub_input_
std::vector< double > coefficients0_
sensor_msgs::ImagePtr toImageMsg() const
virtual double applyModel(double z, int u, int v, double cu, double cv)