Go to the documentation of this file.
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;
136 jsk_recognition_msgs::PlotData
msg;
137 for (
size_t i = 0;
i <
stats.size();
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)) {
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)
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);
ros::Publisher pub_variance_plot
void publishPlotData(const std::vector< OneDataStat::Ptr > &stats, ros::Publisher &pub, boost::function< double(OneDataStat &)> accessor)
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
ros::Publisher pub_error_plot
publishers for plot data
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
double variance(const OneDataStat &d)
wrapper function for variance method for boost::function
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
Publisher advertise(AdvertiseOptions &ops)
sensor_msgs::PointCloud2::ConstPtr ground_truth
pointcloud of ground truth
double stddev(const OneDataStat &d)
wrapper function for stddev method for boost::function
class to store sensor value and compute mean, error and stddev and so on.
ROS_INFO ROS_ERROR int pointer * argv
ros::Publisher pub_stddev_plot
double count(const OneDataStat &d)
wrapper function for count method for boost::function
ros::Publisher pub_error_image
publishers for image visualization.
const std::string TYPE_32FC1
void groundTruthCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
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)
int main(int argc, char **argv)
boost::mutex mutex
global mutex.
message_filters::sync_policies::ExactTime< sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::PointCloud2 > SyncPolicy
void publishImage(const cv::Mat &image, ros::Publisher &pub)
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_mean_image
ros::Publisher pub_stddev_image
ros::Publisher pub_variance_image
double mean(const OneDataStat &d)
wrapper function for mean method for boost::function
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44