Corentin Chauvin-Hameau – 2019-2020
Coverage Path Planning for an underwater robot surveying a marine farm
Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
mfcpp::GPNodelet Class Reference

Nodelet for a Gaussian Process mapping an algae wall. More...

#include <gp_nodelet.hpp>

Inheritance diagram for mfcpp::GPNodelet:
Inheritance graph
[legend]
Collaboration diagram for mfcpp::GPNodelet:
Collaboration graph
[legend]

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...
 

Detailed Description

Nodelet for a Gaussian Process mapping an algae wall.

Definition at line 32 of file gp_nodelet.hpp.

Member Typedef Documentation

typedef std::vector<float> mfcpp::GPNodelet::vec_f
private

Definition at line 59 of file gp_nodelet.hpp.

Constructor & Destructor Documentation

mfcpp::GPNodelet::GPNodelet ( )

Definition at line 44 of file gp_nodelet.cpp.

mfcpp::GPNodelet::~GPNodelet ( )

Definition at line 50 of file gp_nodelet.cpp.

Member Function Documentation

void mfcpp::GPNodelet::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
private

Builds vectors and matrices needed during Kalman update.

Note
It assumes the following objects are already of the right size
Parameters
[in]idx_obsArray of corresponding indices for obs states
[in]idx_nobsArray of corresponding indices for non obs states
[out]muReordered state
[out]mu_obsObserved part of the state
[out]PReordered covariance
[out]P_obsObserved part of the covariance
[out]BOff diagonal block matrix in the covariance
[out]C_obsCovariance matrix of the GP for obs states
[out]C_obs_invInverse of C_obs
[out]x_coordX coordinates of the reordered state
[out]y_coordY coordinates of the reordered state

Definition at line 131 of file gp.cpp.

void mfcpp::GPNodelet::camera_cb ( const mf_sensors_simulator::CameraOutputConstPtr &  msg)
private

Callback for the camera output.

Parameters
msgPointer to the camera message

Definition at line 178 of file gp_nodelet.cpp.

float mfcpp::GPNodelet::camera_noise ( float  distance) const
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.

Parameters
distanceDistance between the measured point and the camera origin

Definition at line 416 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::eval_gp ( float  x,
float  y,
const Eigen::VectorXf &  x_obs,
const Eigen::VectorXf &  y_obs,
const Eigen::VectorXf &  W 
) const
private

Evaluates the Gaussian Process at a given point.

Parameters
xX coordinate of the evaluated point
yY coordinate of the evaluated point
x_obsX coordinates of the observed state
x_obsY coordinates of the observed state
WVector needed for evaluation ( $ W = (C^{-1})_{obs} \mu_{obs} $)
Returns
Value of the evaluated Gaussian Process

Definition at line 385 of file gp.cpp.

bool mfcpp::GPNodelet::get_tf ( )
private

Gets necessary tf transforms.

Returns
Whether the transforms could be retrieved

Definition at line 187 of file gp_nodelet.cpp.

void mfcpp::GPNodelet::init_gp ( )
private

Initialises the Gaussian Process.

Definition at line 21 of file gp.cpp.

double mfcpp::GPNodelet::lambert_w ( double  z,
double  precision,
double  init_w 
) const
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.

Warning
Does not care of bounds, so to use with care. Prefer using GPNodelet::lambert_w0 and GPNodelet::lambert_wm1.
Parameters
zReal number in [-1/e, +inf)
precisionDesired precision for the result
init_wInitial point of Newton's evaluation
Returns
The Lambert W function evaluated at z.

Definition at line 447 of file gp_nodelet.cpp.

double mfcpp::GPNodelet::lambert_w0 ( double  z,
double  precision = 0.01,
double  init_w = 1.0 
) const
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

Note
This function is better implemented in Boost in versions >=1.69, which is not supported by ROS 1 (as of January 2020)
Parameters
zPositive real number
precisionDesired precision for the result
init_wInitial point of Newton's evaluation
Returns
The Lambert W function evaluated at z if z >= 0, 0 otherwise.

Definition at line 421 of file gp_nodelet.cpp.

double mfcpp::GPNodelet::lambert_wm1 ( double  z,
double  precision = 0.01,
double  init_w = -2.0 
) const
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

Note
This function is better implemented in Boost in versions >=1.69, which is not supported by ROS 1 (as of January 2020)
Parameters
zReal number in [-1/e, 0)
precisionDesired precision for the result
init_wInitial point of Newton's evaluation
Returns
The Lambert W function evaluated at z if z is in the right bound, 0 otherwise.

Definition at line 434 of file gp_nodelet.cpp.

bool mfcpp::GPNodelet::load_gp_cb ( mf_mapping::LoadGP::Request &  req,
mf_mapping::LoadGP::Response &  res 
)
private

Service to load the Gaussian Process mean.

Definition at line 326 of file gp_nodelet.cpp.

void mfcpp::GPNodelet::main_cb ( const ros::TimerEvent &  timer_event)
private

Main callback which is called by a timer.

Parameters
timer_eventTimer event information

Definition at line 122 of file gp_nodelet.cpp.

double mfcpp::GPNodelet::matern_kernel ( double  x1,
double  y1,
double  x2,
double  y2 
) const
inlineprivate

Matern 3/2 kernel function.

Parameters
x1X coordinate of the first point
y1Y coordinate of the first point
x2X coordinate of the second point
y2Y coordinate of the second point

Definition at line 422 of file gp_nodelet.hpp.

void mfcpp::GPNodelet::notif_changing_pxls ( const RectArea coord)
private

Notifies changing pixels during GP update.

Parameters
coordCoordinates of the rectangular area of the observed state

Definition at line 107 of file gp.cpp.

void mfcpp::GPNodelet::onInit ( )
virtual

Function called at beginning of nodelet execution.

Definition at line 53 of file gp_nodelet.cpp.

void mfcpp::GPNodelet::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
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.

Parameters
[in]size_obsSize of the observed state
[in]size_nobsSize of the non observed state
[in]min_xMinimal x index of the observed states
[in]max_xMaximal x index of the observed states
[in]min_yMinimal y index of the observed states
[in]max_yMaximal y index of the observed states
[out]idx_obsArray of corr. indices for obs states to populate
[out]idx_nobsArray of corr. indices for not obs states to populate

Definition at line 65 of file gp.cpp.

void mfcpp::GPNodelet::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
private

Prepares objects needed for Gaussian Process evaluation.

Parameters
[in]idx_obsArray of corresponding indices for obs states
[in]gp_meanMean of the Gaussian Process
[out]x_obsX coordinates of the observed state
[out]y_obsY coordinates of the observed state
[out]WVector needed for evaluation ( $ W = (C^{-1})_{obs} \mu_{obs} $)

Definition at line 358 of file gp.cpp.

void mfcpp::GPNodelet::publish_gp_eval ( )
private

Publishes the evaluated GP and its covariance.

Definition at line 50 of file gp_output.cpp.

void mfcpp::GPNodelet::publish_gp_state ( )
private

Publishes mean and covariance of the Gaussian Process.

Definition at line 26 of file gp_output.cpp.

void mfcpp::GPNodelet::sigint_handler ( int  s)
staticprivate

SINGINT (Ctrl+C) callback to stop the nodelet properly.

Definition at line 170 of file gp_nodelet.cpp.

bool mfcpp::GPNodelet::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 
)
private

Transforms points from one frame to another.

Parameters
[in]x_inX coordinate of the input points
[in]y_inY coordinate of the input points
[in]z_inZ coordinate of the input points
[out]x_outX coordinate of the transformed points
[out]y_outY coordinate of the transformed points
[out]z_outZ coordinate of the transformed points
[in]frame_inFrame of the input points
[in]frame_outFrame of the output points
Returns
Whether the points could be transformed
bool mfcpp::GPNodelet::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 
)
private

Transforms points from one frame to another.

Parameters
[in]x_inX coordinate of the input points
[in]y_inY coordinate of the input points
[in]z_inZ coordinate of the input points
[out]x_outX coordinate of the transformed points
[out]y_outY coordinate of the transformed points
[out]z_outZ coordinate of the transformed points
[in]transformTransform to apply
Returns
Whether the points could be transformed

Definition at line 396 of file gp_nodelet.cpp.

void mfcpp::GPNodelet::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
private

Updates the Gaussian Process given measured data points.

Parameters
[in]x_measX coordinate of the measured data points (in wall frame=
[in]y_measY coordinate of the measured data points (in wall frame=
[in]z_measZ coordinate of the measured data points (in wall frame=
[in]distancesDistances between the camera origin and the measured points
[in]valuesMeasured value of the points at coordinates (x, y)
[in,out]gp_meanMean of the Gaussian Process
[in,out]gp_covCovariance of the Gaussian Process
[out]idx_obsArray of corresponding indices for obs states
[out]obs_coordCoordinates of the rectangular area of the observed state
[in]update_meanWhether to update the mean

Definition at line 234 of file gp.cpp.

bool mfcpp::GPNodelet::update_gp_cb ( mf_mapping::UpdateGP::Request &  req,
mf_mapping::UpdateGP::Response &  res 
)
private

Service to update the Gaussian Process for several sets of measurements.

Definition at line 204 of file gp_nodelet.cpp.

void mfcpp::GPNodelet::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
private

Fills GP mean and covariance from reordered objects.

Parameters
[in]idx_obsArray of corresponding indices for obs states
[in]idx_nobsArray of corresponding indices for non obs states
[in]muReordered state
[in]PReordered covariance
[out]gp_meanGP mean to fill
[out]gp_covGP covariance to fill

Definition at line 188 of file gp.cpp.

Member Data Documentation

sig_atomic_t volatile mfcpp::GPNodelet::b_sigint_ = 0
staticprivate

Whether SIGINT signal has been received.

Definition at line 63 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::camera_decay_
private

Exponential decay rate on camera measurements.

Definition at line 109 of file gp_nodelet.hpp.

std::string mfcpp::GPNodelet::camera_frame_
private

Name of the camera frame.

Definition at line 106 of file gp_nodelet.hpp.

mf_sensors_simulator::CameraOutput::ConstPtr mfcpp::GPNodelet::camera_msg_
private

Last camera message.

Definition at line 84 of file gp_nodelet.hpp.

bool mfcpp::GPNodelet::camera_msg_available_
private

Whether a new camera message is available.

Definition at line 82 of file gp_nodelet.hpp.

ros::Subscriber mfcpp::GPNodelet::camera_sub_
private

Subscriber for the camera.

Definition at line 69 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::camera_var_
private

Max variance on camera measurements.

Definition at line 108 of file gp_nodelet.hpp.

std::vector<bool> mfcpp::GPNodelet::changed_pxl_
private

Whether an output pixel has been updated.

Definition at line 100 of file gp_nodelet.hpp.

ros::Publisher mfcpp::GPNodelet::cov_img_pub_
private

Publisher for an image of the GP covariance.

Definition at line 71 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::delta_x_
private

Increment (m) in the x direction.

Definition at line 85 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::delta_y_
private

Increment (m) in the y direction.

Definition at line 86 of file gp_nodelet.hpp.

Eigen::MatrixXf mfcpp::GPNodelet::gp_C_
private

Covariance of the values of the mean of the GP.

Definition at line 94 of file gp_nodelet.hpp.

Eigen::MatrixXf mfcpp::GPNodelet::gp_C_inv_
private

Inverse of gp_C_.

Definition at line 95 of file gp_nodelet.hpp.

Eigen::MatrixXf mfcpp::GPNodelet::gp_cov_
private

Covariance of the Gaussian Process.

Definition at line 93 of file gp_nodelet.hpp.

ros::Publisher mfcpp::GPNodelet::gp_cov_pub_
private

Publisher for the GP covariance.

Definition at line 73 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::gp_cov_thresh_
private

Threshold to consider a value as 0 in the covariance.

Definition at line 116 of file gp_nodelet.hpp.

ros::Publisher mfcpp::GPNodelet::gp_eval_pub_
private

Publisher for the evaluated GP over the wall.

Definition at line 74 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::gp_init_mean_
private

Initial mean values of the Gaussian Process.

Definition at line 114 of file gp_nodelet.hpp.

bool mfcpp::GPNodelet::gp_initialised_
private

Whether the Gaussian Process is initialised.

Definition at line 80 of file gp_nodelet.hpp.

bool mfcpp::GPNodelet::gp_loaded_
private

Whether the GP has been loaded from an external source.

Definition at line 81 of file gp_nodelet.hpp.

Eigen::VectorXf mfcpp::GPNodelet::gp_mean_
private

Mean of the Gaussian Process.

Definition at line 92 of file gp_nodelet.hpp.

ros::Publisher mfcpp::GPNodelet::gp_mean_pub_
private

Publisher for the GP mean.

Definition at line 72 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::gp_noise_var_
private

Noise variance of the Gaussian Process.

Definition at line 115 of file gp_nodelet.hpp.

std::vector<unsigned int> mfcpp::GPNodelet::idx_obs_
private

Array of corresponding indices for observed states.

Definition at line 96 of file gp_nodelet.hpp.

ros::ServiceServer mfcpp::GPNodelet::load_gp_serv_
private

Service server for loading the GP.

Definition at line 76 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::main_freq_
private

Frequency of the main loop.

Definition at line 104 of file gp_nodelet.hpp.

ros::Timer mfcpp::GPNodelet::main_timer_ = ros::Timer()
staticprivate

Timer callback for the main function.

Definition at line 64 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::matern_length_
private

Lengthscale of the Matern kernel.

Definition at line 111 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::matern_thresh_
private

Threshold to consider that the kernel value is 0.

Definition at line 113 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::matern_var_
private

Signal variance of the Matern kernel.

Definition at line 112 of file gp_nodelet.hpp.

ros::NodeHandle mfcpp::GPNodelet::nh_
private

Node handler (for topics and services)

Definition at line 67 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::out_scale_
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.

std::vector<float> mfcpp::GPNodelet::out_values_
private

Output values of the Gaussian Process.

Definition at line 99 of file gp_nodelet.hpp.

ros::NodeHandle mfcpp::GPNodelet::private_nh_
private

Private node handler (for parameters)

Definition at line 68 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::radius_obs_
private

Radius of influence of an observation on the GP.

Definition at line 90 of file gp_nodelet.hpp.

unsigned int mfcpp::GPNodelet::size_gp_
private

Total size of the Gaussian Process.

Definition at line 87 of file gp_nodelet.hpp.

int mfcpp::GPNodelet::size_gp_x_
private

Size of the Gaussian Process mean in the x direction.

Definition at line 122 of file gp_nodelet.hpp.

int mfcpp::GPNodelet::size_gp_y_
private

Size of the Gaussian Process mean in the y direction.

Definition at line 123 of file gp_nodelet.hpp.

unsigned int mfcpp::GPNodelet::size_img_
private

Total size of the image.

Definition at line 88 of file gp_nodelet.hpp.

int mfcpp::GPNodelet::size_img_x_
private

Size of the output image in the x direction.

Definition at line 124 of file gp_nodelet.hpp.

int mfcpp::GPNodelet::size_img_y_
private

Size of the output image in the y direction

Definition at line 125 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::size_wall_x_
private

Size (m) of the algae wall in the x direction.

Definition at line 120 of file gp_nodelet.hpp.

float mfcpp::GPNodelet::size_wall_y_
private

Size (m) of the algae wall in the y direction.

Definition at line 121 of file gp_nodelet.hpp.

tf2_ros::Buffer mfcpp::GPNodelet::tf_buffer_
private

Tf2 buffer for getting tf transforms.

Definition at line 77 of file gp_nodelet.hpp.

bool mfcpp::GPNodelet::tf_got_
private

Whether transforms have been retrieved.

Definition at line 83 of file gp_nodelet.hpp.

tf2_ros::TransformListener mfcpp::GPNodelet::tf_listener_
private

Tf2 listener for getting tf transforms.

Definition at line 78 of file gp_nodelet.hpp.

ros::ServiceServer mfcpp::GPNodelet::update_gp_serv_
private

Service server for updating the GP.

Definition at line 75 of file gp_nodelet.hpp.

geometry_msgs::TransformStamped mfcpp::GPNodelet::wall_camera_tf_
private

Definition at line 89 of file gp_nodelet.hpp.

std::string mfcpp::GPNodelet::wall_frame_
private

Name of the wall frame.

Definition at line 105 of file gp_nodelet.hpp.

ros::Publisher mfcpp::GPNodelet::wall_img_pub_
private

Publisher for an image of the wall GP.

Definition at line 70 of file gp_nodelet.hpp.

Eigen::VectorXf mfcpp::GPNodelet::x_coord_
private

X coordinates of the state on the wall.

Definition at line 97 of file gp_nodelet.hpp.

Eigen::VectorXf mfcpp::GPNodelet::y_coord_
private

Y coordinates of the state on the wall.

Definition at line 98 of file gp_nodelet.hpp.


The documentation for this class was generated from the following files: