|
MFCPP
1.0
|
Corentin Chauvin-Hameau – 2019-2020
|
|
Coverage Path Planning for an underwater robot surveying a marine farm
|
|
Nodelet for a Gaussian Process mapping an algae wall. More...
#include <gp_nodelet.hpp>


Classes | |
| struct | RectArea |
| 2D rectangular area More... | |
Public Member Functions | |
| GPNodelet () | |
| ~GPNodelet () | |
| virtual void | onInit () |
| Function called at beginning of nodelet execution. More... | |
Private Types | |
| typedef std::vector< float > | vec_f |
Private Member Functions | |
| void | main_cb (const ros::TimerEvent &timer_event) |
| Main callback which is called by a timer. More... | |
| bool | get_tf () |
| Gets necessary tf transforms. More... | |
| void | camera_cb (const mf_sensors_simulator::CameraOutputConstPtr &msg) |
| Callback for the camera output. More... | |
| bool | update_gp_cb (mf_mapping::UpdateGP::Request &req, mf_mapping::UpdateGP::Response &res) |
| Service to update the Gaussian Process for several sets of measurements. More... | |
| bool | load_gp_cb (mf_mapping::LoadGP::Request &req, mf_mapping::LoadGP::Response &res) |
| Service to load the Gaussian Process mean. More... | |
| bool | transform_points (const vec_f &x_in, const vec_f &y_in, const vec_f &z_in, vec_f &x_out, vec_f &y_out, vec_f &z_out, std::string frame_in, std::string frame_out) |
| Transforms points from one frame to another. More... | |
| bool | transform_points (const vec_f &x_in, const vec_f &y_in, const vec_f &z_in, vec_f &x_out, vec_f &y_out, vec_f &z_out, const geometry_msgs::TransformStamped &transform) |
| Transforms points from one frame to another. More... | |
| void | init_gp () |
| Initialises the Gaussian Process. More... | |
| float | camera_noise (float distance) const |
| Camera sensor noise model. More... | |
| double | matern_kernel (double x1, double y1, double x2, double y2) const |
| Matern 3/2 kernel function. More... | |
| void | pop_reordered_idx (unsigned int size_obs, unsigned int size_nobs, unsigned int min_x, unsigned int max_x, unsigned int min_y, unsigned int max_y, std::vector< unsigned int > &idx_obs, std::vector< unsigned int > &idx_nobs) const |
| Populates indices correspondance for reordered states. More... | |
| void | notif_changing_pxls (const RectArea &coord) |
| Notifies changing pixels during GP update. More... | |
| void | build_Kalman_objects (const std::vector< unsigned int > &idx_obs, const std::vector< unsigned int > &idx_nobs, Eigen::VectorXf &mu, Eigen::VectorXf &mu_obs, Eigen::MatrixXf &P, Eigen::MatrixXf &P_obs, Eigen::MatrixXf &B, Eigen::MatrixXf &C_obs, Eigen::MatrixXf &C_obs_inv, Eigen::VectorXf &x_coord, Eigen::VectorXf &y_coord) const |
| Builds vectors and matrices needed during Kalman update. More... | |
| void | update_reordered_gp (const std::vector< unsigned int > &idx_obs, const std::vector< unsigned int > &idx_nobs, const Eigen::VectorXf &mu, const Eigen::MatrixXf &P, Eigen::VectorXf &gp_mean, Eigen::MatrixXf &gp_cov) const |
| Fills GP mean and covariance from reordered objects. More... | |
| void | update_gp (const vec_f &x_meas, const vec_f &y_meas, const vec_f &z_meas, const vec_f &distances, const vec_f &values, Eigen::VectorXf &gp_mean, Eigen::MatrixXf &gp_cov, std::vector< unsigned int > &idx_obs, RectArea &obs_coord, bool update_mean=true) const |
| Updates the Gaussian Process given measured data points. More... | |
| void | prepare_eval (const std::vector< unsigned int > &idx_obs, const Eigen::VectorXf &gp_mean, Eigen::VectorXf &x_obs, Eigen::VectorXf &y_obs, Eigen::VectorXf &W) const |
| Prepares objects needed for Gaussian Process evaluation. More... | |
| float | eval_gp (float x, float y, const Eigen::VectorXf &x_obs, const Eigen::VectorXf &y_obs, const Eigen::VectorXf &W) const |
| Evaluates the Gaussian Process at a given point. More... | |
| void | publish_gp_state () |
| Publishes mean and covariance of the Gaussian Process. More... | |
| void | publish_gp_eval () |
| Publishes the evaluated GP and its covariance. More... | |
| double | lambert_w0 (double z, double precision=0.01, double init_w=1.0) const |
| Evaluates the Lambert W (0 branch) function. More... | |
| double | lambert_wm1 (double z, double precision=0.01, double init_w=-2.0) const |
| Evaluates the Lambert W (-1 branch) function. More... | |
| double | lambert_w (double z, double precision, double init_w) const |
| Applies Netwton's method to evaluate Lambert W function. More... | |
Static Private Member Functions | |
| static void | sigint_handler (int s) |
| SINGINT (Ctrl+C) callback to stop the nodelet properly. More... | |
Private Attributes | |
| ros::NodeHandle | nh_ |
| Node handler (for topics and services) More... | |
| ros::NodeHandle | private_nh_ |
| Private node handler (for parameters) More... | |
| ros::Subscriber | camera_sub_ |
| Subscriber for the camera. More... | |
| ros::Publisher | wall_img_pub_ |
| Publisher for an image of the wall GP. More... | |
| ros::Publisher | cov_img_pub_ |
| Publisher for an image of the GP covariance. More... | |
| ros::Publisher | gp_mean_pub_ |
| Publisher for the GP mean. More... | |
| ros::Publisher | gp_cov_pub_ |
| Publisher for the GP covariance. More... | |
| ros::Publisher | gp_eval_pub_ |
| Publisher for the evaluated GP over the wall. More... | |
| ros::ServiceServer | update_gp_serv_ |
| Service server for updating the GP. More... | |
| ros::ServiceServer | load_gp_serv_ |
| Service server for loading the GP. More... | |
| tf2_ros::Buffer | tf_buffer_ |
| Tf2 buffer for getting tf transforms. More... | |
| tf2_ros::TransformListener | tf_listener_ |
| Tf2 listener for getting tf transforms. More... | |
| bool | gp_initialised_ |
| Whether the Gaussian Process is initialised. More... | |
| bool | gp_loaded_ |
| Whether the GP has been loaded from an external source. More... | |
| bool | camera_msg_available_ |
| Whether a new camera message is available. More... | |
| bool | tf_got_ |
| Whether transforms have been retrieved. More... | |
| mf_sensors_simulator::CameraOutput::ConstPtr | camera_msg_ |
| Last camera message. More... | |
| float | delta_x_ |
| Increment (m) in the x direction. More... | |
| float | delta_y_ |
| Increment (m) in the y direction. More... | |
| unsigned int | size_gp_ |
| Total size of the Gaussian Process. More... | |
| unsigned int | size_img_ |
| Total size of the image. More... | |
| geometry_msgs::TransformStamped | wall_camera_tf_ |
| float | radius_obs_ |
| Radius of influence of an observation on the GP. More... | |
| Eigen::VectorXf | gp_mean_ |
| Mean of the Gaussian Process. More... | |
| Eigen::MatrixXf | gp_cov_ |
| Covariance of the Gaussian Process. More... | |
| Eigen::MatrixXf | gp_C_ |
| Covariance of the values of the mean of the GP. More... | |
| Eigen::MatrixXf | gp_C_inv_ |
| Inverse of gp_C_. More... | |
| std::vector< unsigned int > | idx_obs_ |
| Array of corresponding indices for observed states. More... | |
| Eigen::VectorXf | x_coord_ |
| X coordinates of the state on the wall. More... | |
| Eigen::VectorXf | y_coord_ |
| Y coordinates of the state on the wall. More... | |
| std::vector< float > | out_values_ |
| Output values of the Gaussian Process. More... | |
| std::vector< bool > | changed_pxl_ |
| Whether an output pixel has been updated. More... | |
ROS parameters | |
| float | main_freq_ |
| Frequency of the main loop. More... | |
| std::string | wall_frame_ |
| Name of the wall frame. More... | |
| std::string | camera_frame_ |
| Name of the camera frame. More... | |
| float | camera_var_ |
| Max variance on camera measurements. More... | |
| float | camera_decay_ |
| Exponential decay rate on camera measurements. More... | |
| float | matern_length_ |
| Lengthscale of the Matern kernel. More... | |
| float | matern_var_ |
| Signal variance of the Matern kernel. More... | |
| float | matern_thresh_ |
| Threshold to consider that the kernel value is 0. More... | |
| float | gp_init_mean_ |
| Initial mean values of the Gaussian Process. More... | |
| float | gp_noise_var_ |
| Noise variance of the Gaussian Process. More... | |
| float | gp_cov_thresh_ |
| Threshold to consider a value as 0 in the covariance. More... | |
| float | out_scale_ |
| float | size_wall_x_ |
| Size (m) of the algae wall in the x direction. More... | |
| float | size_wall_y_ |
| Size (m) of the algae wall in the y direction. More... | |
| int | size_gp_x_ |
| Size of the Gaussian Process mean in the x direction. More... | |
| int | size_gp_y_ |
| Size of the Gaussian Process mean in the y direction. More... | |
| int | size_img_x_ |
| Size of the output image in the x direction. More... | |
| int | size_img_y_ |
Static Private Attributes | |
| static sig_atomic_t volatile | b_sigint_ = 0 |
| Whether SIGINT signal has been received. More... | |
| static ros::Timer | main_timer_ = ros::Timer() |
| Timer callback for the main function. More... | |
Nodelet for a Gaussian Process mapping an algae wall.
Definition at line 32 of file gp_nodelet.hpp.
|
private |
Definition at line 59 of file gp_nodelet.hpp.
| mfcpp::GPNodelet::GPNodelet | ( | ) |
Definition at line 44 of file gp_nodelet.cpp.
| mfcpp::GPNodelet::~GPNodelet | ( | ) |
Definition at line 50 of file gp_nodelet.cpp.
|
private |
Builds vectors and matrices needed during Kalman update.
| [in] | idx_obs | Array of corresponding indices for obs states |
| [in] | idx_nobs | Array of corresponding indices for non obs states |
| [out] | mu | Reordered state |
| [out] | mu_obs | Observed part of the state |
| [out] | P | Reordered covariance |
| [out] | P_obs | Observed part of the covariance |
| [out] | B | Off diagonal block matrix in the covariance |
| [out] | C_obs | Covariance matrix of the GP for obs states |
| [out] | C_obs_inv | Inverse of C_obs |
| [out] | x_coord | X coordinates of the reordered state |
| [out] | y_coord | Y coordinates of the reordered state |
|
private |
Callback for the camera output.
| msg | Pointer to the camera message |
Definition at line 178 of file gp_nodelet.cpp.
|
inlineprivate |
Camera sensor noise model.
Computes the variance on a camera measurement. The variance depends on the distance of the measured point: the greater the distance, the greater the variance is.
| distance | Distance between the measured point and the camera origin |
Definition at line 416 of file gp_nodelet.hpp.
|
private |
Evaluates the Gaussian Process at a given point.
| x | X coordinate of the evaluated point |
| y | Y coordinate of the evaluated point |
| x_obs | X coordinates of the observed state |
| x_obs | Y coordinates of the observed state |
| W | Vector needed for evaluation ( ) |
|
private |
Gets necessary tf transforms.
Definition at line 187 of file gp_nodelet.cpp.
|
private |
|
private |
Applies Netwton's method to evaluate Lambert W function.
The initial point should be < -1.0 for branch -1 and > 0.0 for branch 0.
GPNodelet::lambert_w0 and GPNodelet::lambert_wm1.| z | Real number in [-1/e, +inf) |
| precision | Desired precision for the result |
| init_w | Initial point of Newton's evaluation |
Definition at line 447 of file gp_nodelet.cpp.
|
private |
Evaluates the Lambert W (0 branch) function.
The Lambert W function solves the equation w*exp(w) = z with w = W0(z) when z >= 0. Uses Newton's method as indicated at https://en.wikipedia.org/wiki/Lambert_W_function#Numerical_evaluation
| z | Positive real number |
| precision | Desired precision for the result |
| init_w | Initial point of Newton's evaluation |
Definition at line 421 of file gp_nodelet.cpp.
|
private |
Evaluates the Lambert W (-1 branch) function.
The Lambert W function solves the equation w*exp(w) = z with w = W0(z) when -1/e <= z < 0. Uses Newton's method as indicated at https://en.wikipedia.org/wiki/Lambert_W_function#Numerical_evaluation
| z | Real number in [-1/e, 0) |
| precision | Desired precision for the result |
| init_w | Initial point of Newton's evaluation |
Definition at line 434 of file gp_nodelet.cpp.
|
private |
Service to load the Gaussian Process mean.
Definition at line 326 of file gp_nodelet.cpp.
|
private |
Main callback which is called by a timer.
| timer_event | Timer event information |
Definition at line 122 of file gp_nodelet.cpp.
|
inlineprivate |
Matern 3/2 kernel function.
| x1 | X coordinate of the first point |
| y1 | Y coordinate of the first point |
| x2 | X coordinate of the second point |
| y2 | Y coordinate of the second point |
Definition at line 422 of file gp_nodelet.hpp.
|
private |
|
virtual |
Function called at beginning of nodelet execution.
Definition at line 53 of file gp_nodelet.cpp.
|
private |
Populates indices correspondance for reordered states.
Used to reorder the state by putting observed states at the beginning and not observed states at the end.
| [in] | size_obs | Size of the observed state |
| [in] | size_nobs | Size of the non observed state |
| [in] | min_x | Minimal x index of the observed states |
| [in] | max_x | Maximal x index of the observed states |
| [in] | min_y | Minimal y index of the observed states |
| [in] | max_y | Maximal y index of the observed states |
| [out] | idx_obs | Array of corr. indices for obs states to populate |
| [out] | idx_nobs | Array of corr. indices for not obs states to populate |
|
private |
Prepares objects needed for Gaussian Process evaluation.
| [in] | idx_obs | Array of corresponding indices for obs states |
| [in] | gp_mean | Mean of the Gaussian Process |
| [out] | x_obs | X coordinates of the observed state |
| [out] | y_obs | Y coordinates of the observed state |
| [out] | W | Vector needed for evaluation ( ) |
|
private |
Publishes the evaluated GP and its covariance.
Definition at line 50 of file gp_output.cpp.
|
private |
Publishes mean and covariance of the Gaussian Process.
Definition at line 26 of file gp_output.cpp.
|
staticprivate |
SINGINT (Ctrl+C) callback to stop the nodelet properly.
Definition at line 170 of file gp_nodelet.cpp.
|
private |
Transforms points from one frame to another.
| [in] | x_in | X coordinate of the input points |
| [in] | y_in | Y coordinate of the input points |
| [in] | z_in | Z coordinate of the input points |
| [out] | x_out | X coordinate of the transformed points |
| [out] | y_out | Y coordinate of the transformed points |
| [out] | z_out | Z coordinate of the transformed points |
| [in] | frame_in | Frame of the input points |
| [in] | frame_out | Frame of the output points |
|
private |
Transforms points from one frame to another.
| [in] | x_in | X coordinate of the input points |
| [in] | y_in | Y coordinate of the input points |
| [in] | z_in | Z coordinate of the input points |
| [out] | x_out | X coordinate of the transformed points |
| [out] | y_out | Y coordinate of the transformed points |
| [out] | z_out | Z coordinate of the transformed points |
| [in] | transform | Transform to apply |
Definition at line 396 of file gp_nodelet.cpp.
|
private |
Updates the Gaussian Process given measured data points.
| [in] | x_meas | X coordinate of the measured data points (in wall frame= |
| [in] | y_meas | Y coordinate of the measured data points (in wall frame= |
| [in] | z_meas | Z coordinate of the measured data points (in wall frame= |
| [in] | distances | Distances between the camera origin and the measured points |
| [in] | values | Measured value of the points at coordinates (x, y) |
| [in,out] | gp_mean | Mean of the Gaussian Process |
| [in,out] | gp_cov | Covariance of the Gaussian Process |
| [out] | idx_obs | Array of corresponding indices for obs states |
| [out] | obs_coord | Coordinates of the rectangular area of the observed state |
| [in] | update_mean | Whether to update the mean |
|
private |
Service to update the Gaussian Process for several sets of measurements.
Definition at line 204 of file gp_nodelet.cpp.
|
private |
Fills GP mean and covariance from reordered objects.
| [in] | idx_obs | Array of corresponding indices for obs states |
| [in] | idx_nobs | Array of corresponding indices for non obs states |
| [in] | mu | Reordered state |
| [in] | P | Reordered covariance |
| [out] | gp_mean | GP mean to fill |
| [out] | gp_cov | GP covariance to fill |
|
staticprivate |
Whether SIGINT signal has been received.
Definition at line 63 of file gp_nodelet.hpp.
|
private |
Exponential decay rate on camera measurements.
Definition at line 109 of file gp_nodelet.hpp.
|
private |
Name of the camera frame.
Definition at line 106 of file gp_nodelet.hpp.
|
private |
Last camera message.
Definition at line 84 of file gp_nodelet.hpp.
|
private |
Whether a new camera message is available.
Definition at line 82 of file gp_nodelet.hpp.
|
private |
Subscriber for the camera.
Definition at line 69 of file gp_nodelet.hpp.
|
private |
Max variance on camera measurements.
Definition at line 108 of file gp_nodelet.hpp.
|
private |
Whether an output pixel has been updated.
Definition at line 100 of file gp_nodelet.hpp.
|
private |
Publisher for an image of the GP covariance.
Definition at line 71 of file gp_nodelet.hpp.
|
private |
Increment (m) in the x direction.
Definition at line 85 of file gp_nodelet.hpp.
|
private |
Increment (m) in the y direction.
Definition at line 86 of file gp_nodelet.hpp.
|
private |
Covariance of the values of the mean of the GP.
Definition at line 94 of file gp_nodelet.hpp.
|
private |
Inverse of gp_C_.
Definition at line 95 of file gp_nodelet.hpp.
|
private |
Covariance of the Gaussian Process.
Definition at line 93 of file gp_nodelet.hpp.
|
private |
Publisher for the GP covariance.
Definition at line 73 of file gp_nodelet.hpp.
|
private |
Threshold to consider a value as 0 in the covariance.
Definition at line 116 of file gp_nodelet.hpp.
|
private |
Publisher for the evaluated GP over the wall.
Definition at line 74 of file gp_nodelet.hpp.
|
private |
Initial mean values of the Gaussian Process.
Definition at line 114 of file gp_nodelet.hpp.
|
private |
Whether the Gaussian Process is initialised.
Definition at line 80 of file gp_nodelet.hpp.
|
private |
Whether the GP has been loaded from an external source.
Definition at line 81 of file gp_nodelet.hpp.
|
private |
Mean of the Gaussian Process.
Definition at line 92 of file gp_nodelet.hpp.
|
private |
Publisher for the GP mean.
Definition at line 72 of file gp_nodelet.hpp.
|
private |
Noise variance of the Gaussian Process.
Definition at line 115 of file gp_nodelet.hpp.
|
private |
Array of corresponding indices for observed states.
Definition at line 96 of file gp_nodelet.hpp.
|
private |
Service server for loading the GP.
Definition at line 76 of file gp_nodelet.hpp.
|
private |
Frequency of the main loop.
Definition at line 104 of file gp_nodelet.hpp.
|
staticprivate |
Timer callback for the main function.
Definition at line 64 of file gp_nodelet.hpp.
|
private |
Lengthscale of the Matern kernel.
Definition at line 111 of file gp_nodelet.hpp.
|
private |
Threshold to consider that the kernel value is 0.
Definition at line 113 of file gp_nodelet.hpp.
|
private |
Signal variance of the Matern kernel.
Definition at line 112 of file gp_nodelet.hpp.
|
private |
Node handler (for topics and services)
Definition at line 67 of file gp_nodelet.hpp.
|
private |
Exponential scale factor for the output (higher value implies sharper transition between 0 and 1)
Definition at line 117 of file gp_nodelet.hpp.
|
private |
Output values of the Gaussian Process.
Definition at line 99 of file gp_nodelet.hpp.
|
private |
Private node handler (for parameters)
Definition at line 68 of file gp_nodelet.hpp.
|
private |
Radius of influence of an observation on the GP.
Definition at line 90 of file gp_nodelet.hpp.
|
private |
Total size of the Gaussian Process.
Definition at line 87 of file gp_nodelet.hpp.
|
private |
Size of the Gaussian Process mean in the x direction.
Definition at line 122 of file gp_nodelet.hpp.
|
private |
Size of the Gaussian Process mean in the y direction.
Definition at line 123 of file gp_nodelet.hpp.
|
private |
Total size of the image.
Definition at line 88 of file gp_nodelet.hpp.
|
private |
Size of the output image in the x direction.
Definition at line 124 of file gp_nodelet.hpp.
|
private |
Size of the output image in the y direction
Definition at line 125 of file gp_nodelet.hpp.
|
private |
Size (m) of the algae wall in the x direction.
Definition at line 120 of file gp_nodelet.hpp.
|
private |
Size (m) of the algae wall in the y direction.
Definition at line 121 of file gp_nodelet.hpp.
|
private |
Tf2 buffer for getting tf transforms.
Definition at line 77 of file gp_nodelet.hpp.
|
private |
Whether transforms have been retrieved.
Definition at line 83 of file gp_nodelet.hpp.
|
private |
Tf2 listener for getting tf transforms.
Definition at line 78 of file gp_nodelet.hpp.
|
private |
Service server for updating the GP.
Definition at line 75 of file gp_nodelet.hpp.
|
private |
Definition at line 89 of file gp_nodelet.hpp.
|
private |
Name of the wall frame.
Definition at line 105 of file gp_nodelet.hpp.
|
private |
Publisher for an image of the wall GP.
Definition at line 70 of file gp_nodelet.hpp.
|
private |
X coordinates of the state on the wall.
Definition at line 97 of file gp_nodelet.hpp.
|
private |
Y coordinates of the state on the wall.
Definition at line 98 of file gp_nodelet.hpp.
1.8.11