Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add const qualifiers to RangeLikelihood getters. #2411

Merged
merged 1 commit into from
Sep 4, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
35 changes: 18 additions & 17 deletions simulation/include/pcl/simulation/range_likelihood.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ namespace pcl
float &camera_fx_in,
float &camera_fy_in,
float &camera_cx_in,
float &camera_cy_in)
float &camera_cy_in) const
{
camera_width_in = camera_width_;
camera_height_in = camera_height_;
Expand All @@ -124,23 +124,23 @@ namespace pcl
void setSigma (double sigma_in){ sigma_ = sigma_in; }
void setFloorProportion (double floor_proportion_in){ floor_proportion_ = floor_proportion_in;}

int getRows () {return rows_;}
int getCols () {return cols_;}
int getRowHeight () {return row_height_;}
int getColWidth () {return col_width_;}
int getWidth () {return width_;}
int getHeight () {return height_;}
int getRows () const {return rows_;}
int getCols () const {return cols_;}
int getRowHeight () const {return row_height_;}
int getColWidth () const {return col_width_;}
int getWidth () const {return width_;}
int getHeight () const {return height_;}

// Convenience function to return simulated RGB-D PointCloud
// Two modes:
// global=false - PointCloud is as would be captured by an RGB-D camera [default]
// global=true - PointCloud is transformed into the model/world frame using the camera pose
void getPointCloud (pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc,
bool make_global, const Eigen::Isometry3d & pose, bool organized = false);
bool make_global, const Eigen::Isometry3d & pose, bool organized = false) const;

// Convenience function to return RangeImagePlanar containing
// simulated RGB-D:
void getRangeImagePlanar (pcl::RangeImagePlanar &rip);
void getRangeImagePlanar (pcl::RangeImagePlanar &rip) const;

// Add various types of noise to simulated RGB-D data
void addNoise ();
Expand All @@ -156,19 +156,19 @@ namespace pcl
setUseColor(bool use_color) { use_color_ = use_color; }

const uint8_t*
getColorBuffer ();
getColorBuffer () const;

const float*
getDepthBuffer ();
getDepthBuffer () const;

const float*
getScoreBuffer ();
getScoreBuffer () const;

float
getZNear (){ return z_near_; }
getZNear () const { return z_near_; }

float
getZFar (){ return z_far_; }
getZFar () const { return z_far_; }

void
setZNear (float z){ z_near_ = z; }
Expand Down Expand Up @@ -228,9 +228,10 @@ namespace pcl
float z_near_;
float z_far_;

bool depth_buffer_dirty_;
bool color_buffer_dirty_;
bool score_buffer_dirty_;
// For caching only, not part of observable state.
mutable bool depth_buffer_dirty_;
mutable bool color_buffer_dirty_;
mutable bool score_buffer_dirty_;

int which_cost_function_;
double floor_proportion_;
Expand Down
10 changes: 5 additions & 5 deletions simulation/src/range_likelihood.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -651,7 +651,7 @@ void
pcl::simulation::RangeLikelihood::getPointCloud (pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc,
bool make_global,
const Eigen::Isometry3d & pose,
bool organized)
bool organized) const
{
// TODO: check if this works for for rows/cols >1 and for width&height != 640x480
// i.e. multiple tiled images
Expand Down Expand Up @@ -762,7 +762,7 @@ pcl::simulation::RangeLikelihood::getPointCloud (pcl::PointCloud<pcl::PointXYZRG
}

void
pcl::simulation::RangeLikelihood::getRangeImagePlanar(pcl::RangeImagePlanar &rip)
pcl::simulation::RangeLikelihood::getRangeImagePlanar(pcl::RangeImagePlanar &rip) const
{
rip.setDepthImage (depth_buffer_,
camera_width_,camera_height_, camera_fx_,camera_fy_,
Expand Down Expand Up @@ -1053,7 +1053,7 @@ RangeLikelihood::render (const std::vector<Eigen::Isometry3d, Eigen::aligned_all
}

const float*
RangeLikelihood::getDepthBuffer ()
RangeLikelihood::getDepthBuffer () const
{
if (depth_buffer_dirty_)
{
Expand All @@ -1073,7 +1073,7 @@ RangeLikelihood::getDepthBuffer ()
}

const uint8_t*
RangeLikelihood::getColorBuffer ()
RangeLikelihood::getColorBuffer () const
{
// It's only possible to read the color buffer if it
// was rendered in the first place.
Expand Down Expand Up @@ -1105,7 +1105,7 @@ RangeLikelihood::getColorBuffer ()

// The scores are in score_texture_
const float*
RangeLikelihood::getScoreBuffer ()
RangeLikelihood::getScoreBuffer () const
{
if (score_buffer_dirty_ && !compute_likelihood_on_cpu_)
{
Expand Down