36 #ifndef JSK_PCL_ROS_DEPTH_CALIBRATION_H_ 37 #define JSK_PCL_ROS_DEPTH_CALIBRATION_H_ 41 #include "jsk_recognition_msgs/SetDepthCalibrationParameter.h" 45 #include <sensor_msgs/CameraInfo.h> 46 #include <sensor_msgs/Image.h> 66 const sensor_msgs::Image::ConstPtr&
msg,
67 const sensor_msgs::CameraInfo::ConstPtr& camera_info);
71 virtual inline double applyModel(
double z,
int u,
int v,
double cu,
double cv) {
91 return c2 * z2 + c1 * z + c0;
95 jsk_recognition_msgs::SetDepthCalibrationParameter::Request&
req,
96 jsk_recognition_msgs::SetDepthCalibrationParameter::Response&
res);
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
ros::ServiceServer set_calibration_parameter_srv_
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_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_camera_info_
std::vector< double > coefficients1_
boost::mutex mutex
global mutex.
std::vector< double > coefficients2_
virtual bool setCalibrationParameter(jsk_recognition_msgs::SetDepthCalibrationParameter::Request &req, jsk_recognition_msgs::SetDepthCalibrationParameter::Response &res)
message_filters::Subscriber< sensor_msgs::Image > sub_input_
std::vector< double > coefficients0_
virtual double applyModel(double z, int u, int v, double cu, double cv)