|
MFCPP
1.0
|
Corentin Chauvin-Hameau – 2019-2020
|
|
Coverage Path Planning for an underwater robot surveying a marine farm
|
|
Class to measure statistics about experiments. More...
#include <experiment_stats.hpp>

Public Member Functions | |
| ExperimentStatsNode () | |
| ~ExperimentStatsNode () | |
| void | run_node () |
| Runs the node. More... | |
Private Member Functions | |
| void | init_node () |
| Initialises the node and its parameters. More... | |
| geometry_msgs::Pose | find_closest (const std::vector< geometry_msgs::PoseStamped > &path, const geometry_msgs::Pose &pose) |
| Finds the closest pose in a path. More... | |
| float | compute_diff (const std::vector< std::vector< float >> &array1, const std::vector< std::vector< float >> &array2) |
| Computes the difference between two arrays. More... | |
| void | write_output (const geometry_msgs::Pose &pose, const geometry_msgs::Pose &reference, const mf_common::EulerPose &error, float gp_cov_trace, float information, float gp_diff_norm) |
| Writes the output statistics in the out file. More... | |
| bool | load_gp (std::string file_name, std::vector< float > &gp_mean) |
| Loads the GP mean from a file. More... | |
| void | save_gp () |
| Saves the mean of the Gaussian Process in a file. More... | |
| void | odom_cb (const nav_msgs::Odometry msg) |
| Callback for odometry. More... | |
| void | path_cb (const nav_msgs::Path msg) |
| Callback for the reference path. More... | |
| void | gp_mean_cb (const mf_common::Float32Array msg) |
| Callback for the mean of the Gaussian Process. More... | |
| void | gp_cov_cb (const mf_common::Array2D msg) |
| Callback for the covariance of the Gaussian Process. More... | |
| void | gp_eval_cb (const mf_common::Array2D msg) |
| Callback for the evaluated GP. More... | |
| void | algae_cb (const mf_farm_simulator::Algae msg) |
| Callback for farm algae. More... | |
Private Attributes | |
| ros::NodeHandle | nh_ |
| Node handler. More... | |
| ros::Subscriber | odom_sub_ |
| Subscriber for robot odometry. More... | |
| ros::Subscriber | path_sub_ |
| Subscriber for the reference path. More... | |
| ros::Subscriber | gp_mean_sub_ |
| Subscriber for mean of the GP. More... | |
| ros::Subscriber | gp_cov_sub_ |
| Subscriber for covariance of the GP. More... | |
| ros::Subscriber | gp_eval_sub_ |
| Subscriber for the evaluated GP. More... | |
| ros::Subscriber | algae_sub_ |
| Subscriber for the farm algae. More... | |
| ros::Publisher | ref_pub_ |
| Publisher for the reference pose. More... | |
| ros::Publisher | error_pub_ |
| Publisher for the tracking error. More... | |
| ros::Publisher | diff_img_pub_ |
| Publisher for the image of the difference between the mapped GP and the algae heatmap. More... | |
| ros::ServiceClient | load_gp_client_ |
| Service client for loading the GP. More... | |
| tf2_ros::Buffer | tf_buffer_ |
| Buffer for tf2. More... | |
| tf2_ros::TransformListener | tf_listener_ |
| Transform listener for tf2. More... | |
| nav_msgs::Odometry | odom_ |
| Last odometry message received. More... | |
| nav_msgs::Path | path_ |
| Reference path to follow. More... | |
| std::vector< float > | gp_mean_ |
| Mean of the Gaussian Process. More... | |
| std::vector< float > | gp_cov_ |
| Diagonal of the covariance of the Gaussian Proces. More... | |
| std::vector< float > | init_gp_cov_ |
| Diagonal of the initial covariance of the GP. More... | |
| std::vector< std::vector< float > > | gp_eval_ |
| Evaluated GP. More... | |
| std::vector< std::vector< std::vector< float > > > | algae_heatmaps_ |
| Disease heatmaps of the algae. More... | |
| bool | odom_received_ |
| Whether odometry has been received. More... | |
| bool | path_received_ |
| Whether the reference path has been received. More... | |
| bool | gp_mean_received_ |
| Whether the mean of the GP has been received. More... | |
| bool | gp_cov_received_ |
| Whether the covariance of the GP has been received. More... | |
| bool | gp_eval_received_ |
| Whether the evaluated GP has been received. More... | |
| bool | algae_received_ |
| Whether the farm algae have been received. More... | |
| float | moved_distance_ |
| Distance moved by the robot since the start. More... | |
| double | start_time_ |
| Start time of the test. More... | |
| std::ofstream | out_file_ |
| Output CSV file containg data of the experiment. More... | |
ROS parameters | |
| float | main_freq_ |
| Frequency of the main loop. More... | |
| float | gp_threshold_ |
| Threshold to consider a GP component in information gain computation. More... | |
| bool | save_gp_ |
| Whether to save the Gaussian Process at the end. More... | |
| bool | load_gp_ |
| Whether to load the Gaussian Process at the beginning. More... | |
| std::string | gp_file_name_ |
Class to measure statistics about experiments.
Measures different statistics and publishes it to ROS and to a text file. Statistics measured:
Definition at line 38 of file experiment_stats.hpp.
| mfcpp::ExperimentStatsNode::ExperimentStatsNode | ( | ) |
Definition at line 45 of file experiment_stats.cpp.
| mfcpp::ExperimentStatsNode::~ExperimentStatsNode | ( | ) |
Definition at line 53 of file experiment_stats.cpp.
|
private |
Callback for farm algae.
Definition at line 424 of file experiment_stats.cpp.
|
private |
Computes the difference between two arrays.
Computes the 2-norm of the difference between the two arrays, and publishes an image corresponding to the difference.
The arrays don't need to be of the same size (but of same proportions). The values will be scaled out by their maximum value.
| array1 | First array |
| array2 | Second array |
Definition at line 220 of file experiment_stats.cpp.
|
private |
Finds the closest pose in a path.
| [in] | path | List of poses |
| [in] | pose | Current pose |
pose in path Definition at line 197 of file experiment_stats.cpp.
|
private |
Callback for the covariance of the Gaussian Process.
Definition at line 393 of file experiment_stats.cpp.
|
private |
Callback for the evaluated GP.
Definition at line 408 of file experiment_stats.cpp.
|
private |
Callback for the mean of the Gaussian Process.
Definition at line 386 of file experiment_stats.cpp.
|
private |
Initialises the node and its parameters.
Definition at line 59 of file experiment_stats.cpp.
|
private |
Loads the GP mean from a file.
| [in] | file_name | Path of the file where to load the GP |
| [out] | gp_mean | Loaded gp_mean |
Definition at line 315 of file experiment_stats.cpp.
|
private |
Callback for odometry.
Increments distance moved by the robot
Definition at line 363 of file experiment_stats.cpp.
|
private |
Callback for the reference path.
Definition at line 379 of file experiment_stats.cpp.
| void mfcpp::ExperimentStatsNode::run_node | ( | ) |
Runs the node.
Definition at line 105 of file experiment_stats.cpp.
|
private |
Saves the mean of the Gaussian Process in a file.
Definition at line 341 of file experiment_stats.cpp.
|
private |
Writes the output statistics in the out file.
| pose | Current pose |
| reference | Reference pose |
| error | Error between current pose and reference |
| gp_cov_trace | Trace of the covariance of the Gaussian Process |
| information | Information (weighted sum of the diagonal coefficients of the covariance of the GP) |
| gp_diff_norm | Norm of the difference between the evaluated GP and the algae disease heatmaps |
Definition at line 284 of file experiment_stats.cpp.
|
private |
Disease heatmaps of the algae.
Definition at line 70 of file experiment_stats.hpp.
|
private |
Whether the farm algae have been received.
Definition at line 76 of file experiment_stats.hpp.
|
private |
Subscriber for the farm algae.
Definition at line 56 of file experiment_stats.hpp.
|
private |
Publisher for the image of the difference between the mapped GP and the algae heatmap.
Definition at line 59 of file experiment_stats.hpp.
|
private |
Publisher for the tracking error.
Definition at line 58 of file experiment_stats.hpp.
|
private |
Diagonal of the covariance of the Gaussian Proces.
Definition at line 67 of file experiment_stats.hpp.
|
private |
Whether the covariance of the GP has been received.
Definition at line 74 of file experiment_stats.hpp.
|
private |
Subscriber for covariance of the GP.
Definition at line 54 of file experiment_stats.hpp.
|
private |
Evaluated GP.
Definition at line 69 of file experiment_stats.hpp.
|
private |
Whether the evaluated GP has been received.
Definition at line 75 of file experiment_stats.hpp.
|
private |
Subscriber for the evaluated GP.
Definition at line 55 of file experiment_stats.hpp.
|
private |
Name/path of the file where to save the GP
Definition at line 88 of file experiment_stats.hpp.
|
private |
Mean of the Gaussian Process.
Definition at line 66 of file experiment_stats.hpp.
|
private |
Whether the mean of the GP has been received.
Definition at line 73 of file experiment_stats.hpp.
|
private |
Subscriber for mean of the GP.
Definition at line 53 of file experiment_stats.hpp.
|
private |
Threshold to consider a GP component in information gain computation.
Definition at line 85 of file experiment_stats.hpp.
|
private |
Diagonal of the initial covariance of the GP.
Definition at line 68 of file experiment_stats.hpp.
|
private |
Whether to load the Gaussian Process at the beginning.
Definition at line 87 of file experiment_stats.hpp.
|
private |
Service client for loading the GP.
Definition at line 60 of file experiment_stats.hpp.
|
private |
Frequency of the main loop.
Definition at line 84 of file experiment_stats.hpp.
|
private |
Distance moved by the robot since the start.
Definition at line 77 of file experiment_stats.hpp.
|
private |
Node handler.
Definition at line 50 of file experiment_stats.hpp.
|
private |
Last odometry message received.
Definition at line 64 of file experiment_stats.hpp.
|
private |
Whether odometry has been received.
Definition at line 71 of file experiment_stats.hpp.
|
private |
Subscriber for robot odometry.
Definition at line 51 of file experiment_stats.hpp.
|
private |
Output CSV file containg data of the experiment.
Definition at line 80 of file experiment_stats.hpp.
|
private |
Reference path to follow.
Definition at line 65 of file experiment_stats.hpp.
|
private |
Whether the reference path has been received.
Definition at line 72 of file experiment_stats.hpp.
|
private |
Subscriber for the reference path.
Definition at line 52 of file experiment_stats.hpp.
|
private |
Publisher for the reference pose.
Definition at line 57 of file experiment_stats.hpp.
|
private |
Whether to save the Gaussian Process at the end.
Definition at line 86 of file experiment_stats.hpp.
|
private |
Start time of the test.
Definition at line 79 of file experiment_stats.hpp.
|
private |
Buffer for tf2.
Definition at line 61 of file experiment_stats.hpp.
|
private |
Transform listener for tf2.
Definition at line 62 of file experiment_stats.hpp.
1.8.11