Skip to content

Commit

Permalink
currently non-compiling code with fixed pointers
Browse files Browse the repository at this point in the history
  • Loading branch information
aPonza committed Mar 16, 2020
1 parent 9167a1d commit fb8ca1b
Show file tree
Hide file tree
Showing 32 changed files with 248 additions and 236 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <QtGui/QColor>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/statistics.h>
#include <pcl/pcl_macros.h> // for pcl::shared_ptr, pcl::weak_ptr
#ifdef OPENGL_IS_A_FRAMEWORK
# include <OpenGL/gl.h>
# include <OpenGL/glu.h>
Expand All @@ -56,6 +57,10 @@
# include <GL/glu.h>
#endif

/// avoid circular dependencies by forward declaring
class CopyBuffer;
class Selection;

/// @brief A wrapper which allows to use any implementation of cloud provided by
/// a third-party library.
/// @details This wrapper attempts to create a simple interface for displaying
Expand All @@ -75,6 +80,12 @@
class Cloud : public Statistics
{
public:
/// The type for shared pointer pointing to a cloud object
using Ptr = pcl::shared_ptr<Cloud>;

/// The type for shared pointer pointing to a constant cloud object
using ConstPtr = pcl::shared_ptr<const Cloud>;

/// @brief Default Constructor
Cloud ();

Expand All @@ -85,7 +96,7 @@ class Cloud : public Statistics
Cloud (const Cloud& copy);

/// @brief Construct a cloud from a Cloud3D.
/// @details This constructor creates a cloud object with the passed
/// @details This constructor creates a cloud object with the passed
/// cloud object stored with the internal representation. The member
/// variables of this object are initialized but not set.
Cloud (const Cloud3D& cloud, bool register_stats=false);
Expand Down Expand Up @@ -201,7 +212,7 @@ class Cloud : public Statistics
/// a faster rendering mode; this also occurs if the selection object is
/// empty.
void
setSelection (const SelectionPtr& selection_ptr);
setSelection (const Selection::Ptr& selection_ptr);

/// @brief Sets the RGB values for coloring points in COLOR_BY_PURE mode.
/// @param r the value for red color
Expand Down Expand Up @@ -274,12 +285,12 @@ class Cloud : public Statistics
/// @param point the new point to be added.
void
append (const Point3D& point);

/// @brief Appends the points of the passed cloud to this cloud.
/// @param cloud the cloud to be appended to this cloud.
void
append (const Cloud& cloud);

/// @brief Removes the points in selection from the cloud.
/// @details Each indexed point in the selection will be removed from this
/// container.
Expand Down Expand Up @@ -309,7 +320,7 @@ class Cloud : public Statistics
/// @param new_size the new size of the cloud.
void
resize (unsigned int new_size);

/// @brief Removes all points from the cloud and resets the object
void
clear ();
Expand Down Expand Up @@ -412,7 +423,7 @@ class Cloud : public Statistics
/// @brief A weak pointer pointing to the selection object.
/// @details This implementation uses the weak pointer to allow for a lazy
/// update of the cloud if the selection object is destroyed.
std::weak_ptr<Selection> selection_wk_ptr_;
Selection::WeakPtr selection_wk_ptr_;

/// Flag that indicates whether a color ramp should be used (true) or not
/// (false) when displaying the cloud
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,13 @@

#pragma once

#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/common.h>
#include <pcl/apps/point_cloud_editor/cloud.h>
#include <pcl/apps/point_cloud_editor/commandQueue.h>
#include <pcl/apps/point_cloud_editor/common.h>
#include <pcl/apps/point_cloud_editor/copyBuffer.h>
#include <pcl/apps/point_cloud_editor/denoiseParameterForm.h>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/selection.h>
#include <pcl/apps/point_cloud_editor/statisticsDialog.h>
#include <pcl/apps/point_cloud_editor/toolInterface.h>

Expand Down Expand Up @@ -188,7 +191,7 @@ class CloudEditorWidget : public QGLWidget
void
showStat ();

protected:
protected:
/// initializes GL
void
initializeGL () override;
Expand Down Expand Up @@ -218,17 +221,16 @@ class CloudEditorWidget : public QGLWidget
keyPressEvent (QKeyEvent *event) override;

private:

/// @brief Attempts to load a pcd file
/// @param filename The name of the pcd file to be loaded.
/// @remarks throws if the passed file can not be loaded.
void
loadFilePCD(const std::string &filename);

/// @brief Adds all of our file loader functions to the extension map
void
initFileLoadMap();

/// @brief Returns true if the cloud stored in a file is colored
/// @param fileName a reference to a string storing the path of a cloud
bool
Expand Down Expand Up @@ -259,9 +261,9 @@ class CloudEditorWidget : public QGLWidget

/// a map of file type extensions to loader functions.
FileLoadMap cloud_load_func_map_;

/// a pointer to the cloud being edited.
CloudPtr cloud_ptr_;
Cloud::Ptr cloud_ptr_;

/// The display size, in pixels, of the cloud points
unsigned int point_size_;
Expand All @@ -271,16 +273,16 @@ class CloudEditorWidget : public QGLWidget

/// The transformation tool being used. Either a cloud transform tool or
/// a selection transform tool is activated at a time.
std::shared_ptr<ToolInterface> tool_ptr_;
ToolInterface::Ptr tool_ptr_;

/// a pointer to the selection object
SelectionPtr selection_ptr_;
Selection::Ptr selection_ptr_;

/// a pointer to the copy buffer object.
CopyBufferPtr copy_buffer_ptr_;
CopyBuffer::Ptr copy_buffer_ptr_;

/// a pointer to the command queue object
CommandQueuePtr command_queue_ptr_;
CommandQueue::Ptr command_queue_ptr_;

/// The camera field of view
double cam_fov_;
Expand Down Expand Up @@ -311,6 +313,4 @@ class CloudEditorWidget : public QGLWidget

/// a dialog displaying the statistics of the cloud editor
StatisticsDialog stat_dialog_;


};
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,9 @@

#pragma once

#include <pcl/apps/point_cloud_editor/toolInterface.h>
#include <pcl/apps/point_cloud_editor/cloud.h>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/toolInterface.h>
#include <pcl/apps/point_cloud_editor/trackball.h>

/// @brief The cloud transform tool computes the transform matrix from user's
Expand All @@ -52,7 +53,7 @@ class CloudTransformTool : public ToolInterface
public:
/// @brief Constructor
/// @param cloud_ptr a shared pointer pointing to the cloud object.
CloudTransformTool (CloudPtr cloud_ptr);
CloudTransformTool (Cloud::Ptr cloud_ptr);

/// @brief Destructor
~CloudTransformTool ();
Expand Down Expand Up @@ -123,11 +124,11 @@ class CloudTransformTool : public ToolInterface
float transform_matrix_[MATRIX_SIZE];

/// a shared pointer pointing to the cloud object.
CloudPtr cloud_ptr_;
Cloud::Ptr cloud_ptr_;

/// the trackball associated with this transform
TrackBall trackball_;

/// last recorded mouse positions
int x_, y_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,16 @@

#include <pcl/apps/point_cloud_editor/localTypes.h>

#include <pcl/pcl_macros.h> // for pcl::shared_ptr

/// @brief The abstract parent class of all the command classes. Commands are
/// non-copyable.
class Command
{
public:
/// The type for shared pointer pointing to a command object
using Ptr = pcl::shared_ptr<Command>;

/// @brief Destructor
virtual ~Command ()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,9 @@

#include <deque>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/command.h>

#include <pcl/pcl_macros.h> // for pcl::shared_ptr

/// @brief A structure for managing commands
/// @details A command queue object provides a dequeue of commands as well as
Expand All @@ -52,6 +55,9 @@
class CommandQueue
{
public:
/// The type for shared pointer pointing to a command queue object
using Ptr = pcl::shared_ptr<CommandQueue>;

/// @brief Default Constructor
/// @details Creates a command queue object and makes its depth limit
/// be the default value.
Expand All @@ -73,7 +79,7 @@ class CommandQueue
/// @param command_ptr a shared pointer pointing to a command object whose
/// execute function will be invoked by this object.
void
execute (const CommandPtr&);
execute (const Command::Ptr&);

/// @brief Undoes the last command by popping the tail of the queue, invoke
/// the undo function of the command.
Expand All @@ -92,16 +98,16 @@ class CommandQueue

/// @brief The default maximal size of the depth limit
static const unsigned int DEFAULT_MAX_SIZE_ = 200;

private:
/// @brief Copy constructor - object is non-copyable
CommandQueue(const CommandQueue&)
{
assert(false);
}

/// @brief Equal operator - object is non-copyable
CommandQueue&
CommandQueue&
operator= (const CommandQueue&)
{
assert(false); return (*this);
Expand All @@ -113,7 +119,7 @@ class CommandQueue
enforceDequeLimit ();

/// The internal representation of this object.
std::deque<CommandPtr> command_deque_;
std::deque<Command::Ptr> command_deque_;

/// The depth limit of the command queue.
unsigned int depth_limit_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,14 +40,23 @@

#pragma once

#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/cloud.h>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/statistics.h>

#include <pcl/pcl_macros.h> // for pcl::shared_ptr

/// @brief a buffer holding the points being copied and a set of operations for
/// manipulating the buffer.
class CopyBuffer : public Statistics
{
public:
/// The type for shared pointer pointing to a copy buffer
using Ptr = pcl::shared_ptr<CopyBuffer>;

/// The type for shared pointer pointing to a constant copy buffer
using ConstPtr = pcl::shared_ptr<const CopyBuffer>;

/// @brief Default Constructor
/// @details This creates an empty buffer
CopyBuffer (bool register_stats=false)
Expand All @@ -66,7 +75,7 @@ class CopyBuffer : public Statistics
/// copied
/// @param selection a const reference to the selected points object
void
set (const ConstCloudPtr& cloud_ptr, const Selection& selection);
set (const Cloud::ConstPtr& cloud_ptr, const Selection& selection);

/// @brief Returns the points stored in the internal buffer as a const Cloud
const Cloud&
Expand All @@ -75,11 +84,11 @@ class CopyBuffer : public Statistics
/// @brief Returns the points stored in the internal buffer as a Cloud
Cloud&
get();

/// @brief Removes all the points from the copy buffer.
void
clean ();

/// @brief Get the statistics of the copied points in string.
std::string
getStat () const override;
Expand All @@ -93,5 +102,5 @@ class CopyBuffer : public Statistics

private:
/// a cloud object holding all the copied points.
Cloud buffer_;
Cloud buffer_;
};
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,11 @@

#pragma once

#include <pcl/apps/point_cloud_editor/cloud.h>
#include <pcl/apps/point_cloud_editor/command.h>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/copyBuffer.h>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/selection.h>

class CopyCommand : public Command
{
Expand All @@ -51,9 +53,9 @@ class CopyCommand : public Command
/// @param copy_buffer_ptr a shared pointer pointing to the copy buffer.
/// @param selection_ptr a shared pointer pointing to the selection object.
/// @param cloud_ptr a shared pointer pointing to the cloud object.
CopyCommand (CopyBufferPtr copy_buffer_ptr,
ConstSelectionPtr selection_ptr,
ConstCloudPtr cloud_ptr)
CopyCommand (CopyBuffer::Ptr copy_buffer_ptr,
Selection::ConstPtr selection_ptr,
Cloud::ConstPtr cloud_ptr)
: copy_buffer_ptr_(std::move(copy_buffer_ptr)), selection_ptr_(std::move(selection_ptr)),
cloud_ptr_(std::move(cloud_ptr))
{
Expand Down Expand Up @@ -88,11 +90,11 @@ class CopyCommand : public Command

private:
/// a pointer to the copy buffer.
CopyBufferPtr copy_buffer_ptr_;
CopyBuffer::Ptr copy_buffer_ptr_;

/// a shared pointer pointing to the selection
ConstSelectionPtr selection_ptr_;
Selection::ConstPtr selection_ptr_;

/// a shared pointer pointing to the cloud
ConstCloudPtr cloud_ptr_;
Cloud::ConstPtr cloud_ptr_;
};
Loading

0 comments on commit fb8ca1b

Please sign in to comment.