Go to the documentation of this file.
41 #define BOOST_PARAMETER_MAX_ARITY 7
45 #include <sensor_msgs/LaserScan.h>
46 #include <sensor_msgs/Image.h>
49 #include <jsk_recognition_msgs/PlotData.h>
63 typedef boost::accumulators::accumulator_set<
66 boost::accumulators::tag::max> > MinMaxAccumulator;
67 MinMaxAccumulator acc;
68 for (
size_t i = 0;
i <
stats.size();
i++) {
73 double max = boost::accumulators::max(acc);
75 for (
size_t i = 0;
i <
stats.size();
i++) {
77 double relative_value = (
v -
min) / (
max -
min);
78 image.at<
float>(0,
i) = relative_value;
86 std::vector<OneDataStat::Ptr>
g_data;
121 for (
size_t i = 0;
i <
msg->ranges.size();
i++) {
125 if (
g_data.size() !=
msg->ranges.size()) {
126 ROS_ERROR(
"Size of g_data and ~input/ranges are not same");
130 for (
size_t i = 0;
i <
msg->ranges.size();
i++) {
138 cv::Mat mean_image(1,
msg->ranges.size(), CV_32FC1);
139 cv::Mat variance_image(1,
msg->ranges.size(), CV_32FC1);
140 cv::Mat stddev_image(1,
msg->ranges.size(), CV_32FC1);
148 jsk_recognition_msgs::PlotData plot_data;
149 jsk_recognition_msgs::PlotData plot_stddev_data;
150 for (
size_t i = 0;
i <
g_data.size();
i++) {
154 if (
x > 1.0 &&
x < 40 &&
stddev < 0.100) {
155 plot_data.xs.push_back(
x);
156 plot_data.ys.push_back(
y);
157 plot_stddev_data.xs.push_back(
x);
158 plot_stddev_data.ys.push_back(
stddev);
166 int main(
int argc,
char** argv)
std::vector< OneDataStat::Ptr > stats
global variable to store stats.
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
double min(const OneDataStat &d)
wrapper function for min method for boost::function
void publishImage(const cv::Mat &image, ros::Publisher &pub)
publish a float image.
ros::Publisher pub_mean
publisher for mean, variance and standard deviation images
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::vector< OneDataStat::Ptr > g_data
global variable to store stat information.
double stddev(const OneDataStat &d)
wrapper function for stddev method for boost::function
void generateImage(const std::vector< OneDataStat::Ptr > &stats, cv::Mat &image, boost::function< double(OneDataStat &)> accessor)
generate a float image according to accessor.
class to store sensor value and compute mean, error and stddev and so on.
ROS_INFO ROS_ERROR int pointer * argv
double count(const OneDataStat &d)
wrapper function for count method for boost::function
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Publisher pub_variance
ros::Publisher pub_variance_plot
publisher for variance and standard deviation values for plotting
const std::string TYPE_32FC1
ros::Publisher pub_stddev_plot
ros::Publisher pub_stddev
void callback(const sensor_msgs::LaserScan::ConstPtr &msg)
callback function
int main(int argc, char **argv)
double max(const OneDataStat &d)
wrapper function for max method for boost::function
double mean(const OneDataStat &d)
wrapper function for mean method for boost::function
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:12:12