36 #define BOOST_PARAMETER_MAX_ARITY 7 40 #include <sensor_msgs/Image.h> 41 #include <sensor_msgs/PointCloud2.h> 42 #include <sensor_msgs/CameraInfo.h> 51 #include <jsk_recognition_msgs/PlotData.h> 66 sensor_msgs::CameraInfo,
98 std::vector<OneDataStat::Ptr>
stats;
111 const std::vector<OneDataStat::Ptr>&
stats,
115 for (
size_t i = 0; i < image.rows; i++) {
116 for (
size_t j = 0; j < image.cols; j++) {
117 size_t index = i * image.cols + j;
118 if (stats[index]->
count() > 2) {
119 image.at<
float>(i, j) = accessor(*stats[index]);
136 jsk_recognition_msgs::PlotData
msg;
137 for (
size_t i = 0; i < stats.size(); i++) {
139 if (stats[i]->
count() > 2) {
140 msg.xs.push_back(stats[i]->
mean());
141 msg.ys.push_back(accessor(*stats[i]));
149 const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg,
150 const sensor_msgs::Image::ConstPtr& left_image_msg,
151 const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg)
158 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
162 if (stats.size() == 0) {
163 for (
size_t i = 0; i < cloud->points.size(); i++) {
176 for (
size_t i = 0; i < cloud->points.size(); i++) {
177 pcl::PointXYZ
p = cloud->points[i];
180 if (std::isnan(p.x) || std::isnan(p.y) || std::isnan(p.z)) {
183 stats[i]->addData(p.z);
187 cv::Mat mean_image = cv::Mat::zeros(cloud->height, cloud->width, CV_32FC1);
188 cv::Mat variance_image = cv::Mat::zeros(cloud->height, cloud->width, CV_32FC1);
189 cv::Mat stddev_image = cv::Mat::zeros(cloud->height, cloud->width, CV_32FC1);
200 int main(
int argc,
char** argv)
202 ros::init(argc, argv,
"depth_camera_error_visualization");
205 pub_error_image = nh.
advertise<sensor_msgs::Image>(
"output/error_image", 1);
206 pub_variance_image = nh.
advertise<sensor_msgs::Image>(
"output/variance_image", 1);
207 pub_stddev_image = nh.
advertise<sensor_msgs::Image>(
"output/stddev_image", 1);
208 pub_mean_image = nh.
advertise<sensor_msgs::Image>(
"output/mean_image", 1);
209 pub_error_plot = nh.
advertise<jsk_recognition_msgs::PlotData>(
"output/error_plot", 1);
210 pub_variance_plot = nh.
advertise<jsk_recognition_msgs::PlotData>(
"output/variance_plot", 1);
211 pub_stddev_plot = nh.
advertise<jsk_recognition_msgs::PlotData>(
"output/stddev_plot", 1);
216 sub_camera_info.
subscribe(nh,
"input/camera_info", 1);
217 sub_left_image.
subscribe(nh,
"input/left_image", 1);
218 sub_point_cloud.
subscribe(nh,
"input/point_cloud", 1);
220 sync.
connectInput(sub_camera_info, sub_left_image, sub_point_cloud);
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
void publishImage(const cv::Mat &image, ros::Publisher &pub)
void dataCallback(const sensor_msgs::CameraInfo::ConstPtr &camera_info_msg, const sensor_msgs::Image::ConstPtr &left_image_msg, const sensor_msgs::PointCloud2::ConstPtr &point_cloud_msg)
ros::Publisher pub_stddev_plot
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void publishPlotData(const std::vector< OneDataStat::Ptr > &stats, ros::Publisher &pub, boost::function< double(OneDataStat &)> accessor)
double mean(const OneDataStat &d)
wrapper function for mean method for boost::function
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void generateImage(const std::vector< OneDataStat::Ptr > &stats, cv::Mat &image, boost::function< double(OneDataStat &)> accessor)
generate a image generated by accessor
ros::Publisher pub_variance_plot
ros::Publisher pub_mean_image
class to store sensor value and compute mean, error and stddev and so on.
ros::Publisher pub_error_plot
publishers for plot data
ROSCPP_DECL void spin(Spinner &spinner)
sensor_msgs::PointCloud2::ConstPtr ground_truth
pointcloud of ground truth
Connection registerCallback(C &callback)
double variance(const OneDataStat &d)
wrapper function for variance method for boost::function
double stddev(const OneDataStat &d)
wrapper function for stddev method for boost::function
const std::string TYPE_32FC1
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void connectInput(F0 &f0, F1 &f1)
boost::mutex mutex
global mutex.
void groundTruthCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
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)
ros::Publisher pub_stddev_image
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::PointCloud2 > SyncPolicy
ros::Publisher pub_error_image
publishers for image visualization.
double count(const OneDataStat &d)
wrapper function for count method for boost::function
ros::Publisher pub_variance_image